123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672 |
- #include <iostream>
- #include <ros/ros.h>
- #include "hdl_backend.hpp"
- #include <pcl_ros/point_cloud.h>
- #include <hdl_graph_slam/ros_utils.hpp>
- #include <functional>
- #include "hdl_graph_slam/keyframe_updater.hpp"
- #include <visualization_msgs/MarkerArray.h>
- #include <glog/logging.h>
- #include <geometry_msgs/TransformStamped.h>
- #include <geometry_msgs/PoseWithCovarianceStamped.h>
- hdl_backend* instance = nullptr;
- typedef pcl::PointXYZI PointT;
- int main(int argc, char* argv[]) {
-
- ros::init(argc, argv, "hdl_backend");
- std::cout << "hdl backend get in ...===============" << std::endl;
- instance = new hdl_backend();
-
- instance->init();
- return 0;
- }
- void hdl_backend::init() {
- map_frame_id = "map";
- odom_frame_id = "odom";
- map_cloud_resolution = 0.01;
- trans_odom2map.setIdentity();
- max_keyframes_per_update = 10;
- keyframe_updater.reset(new hdl_graph_slam::KeyframeUpdater(nh));
- points_topic = "/velodyne_points";
- graph_slam.reset(new hdl_graph_slam::GraphSLAM("lm_var_cholmod"));
-
- auto voxelgrid = new pcl::VoxelGrid<PointT>();
- voxelgrid->setLeafSize(downsample_resolution, downsample_resolution, downsample_resolution);
- downsample_filter.reset(voxelgrid);
- inf_calclator.reset(new hdl_graph_slam::InformationMatrixCalculator(nh));
- loop_detector.reset(new hdl_graph_slam::LoopDetector(nh));
- anchor_node = nullptr;
- anchor_edge = nullptr;
- odom_sub.reset(new message_filters::Subscriber<nav_msgs::Odometry>(nh, "/laser_odom", 256));
-
-
- cloud_sub.reset(new message_filters::Subscriber<sensor_msgs::PointCloud2>(nh, "/filtered_points", 32));
-
-
- sync.reset(new message_filters::Synchronizer<ApproxSyncPolicy>(ApproxSyncPolicy(32), *odom_sub, *cloud_sub));
- sync->registerCallback(boost::bind(&hdl_backend::cloud_callback, this, _1, _2));
- markers_pub = nh.advertise<visualization_msgs::MarkerArray>("/hdl_graph_slam/markers", 16);
- odom2map_pub = nh.advertise<geometry_msgs::TransformStamped>("/hdl_graph_slam/odom2pub", 16);
- map_points_pub = nh.advertise<sensor_msgs::PointCloud2>("/hdl_graph_slam/map_points", 1, true);
- map_points_pub2 = nh.advertise<sensor_msgs::PointCloud2>("/hdl_graph_slam/map_points2", 1, true);
- read_until_pub = nh.advertise<std_msgs::Header>("/hdl_graph_slam/read_until", 32);
- odom_pub = nh.advertise<geometry_msgs::PoseStamped>("/opt_odom", 32);
- save_map_service_server = nh.advertiseService("/hdl_graph_slam/save_map", &hdl_backend::save_map_service, this);
- graph_updated = false;
- double graph_update_interval = 3;
- double map_cloud_update_interval = 5;
-
- map_publish_timer = nh.createWallTimer(ros::WallDuration(map_cloud_update_interval), &hdl_backend::map_points_publish_timer_callback, this);
- pcl::RadiusOutlierRemoval<PointT>::Ptr rad(new pcl::RadiusOutlierRemoval<PointT>());
- rad->setRadiusSearch(0.8);
- rad->setMinNeighborsInRadius(1);
- outlier_removal_filter = rad;
- std::thread proc_thread(&hdl_backend::optimization_timer_callback, this);
- proc_thread.detach();
- ros::spin();
- }
- void hdl_backend::optimization_timer_callback() {
- LOG(INFO) << "begin()";
- while(ros::ok()) {
- std::lock_guard<std::mutex> lock(main_thread_mutex);
-
- bool keyframe_updated = flush_keyframe_queue();
- if(!keyframe_updated) {
- std_msgs::Header read_until;
- read_until.stamp = ros::Time::now() + ros::Duration(30, 0);
- read_until.frame_id = points_topic;
- read_until_pub.publish(read_until);
- read_until.frame_id = "/filtered_points";
- read_until_pub.publish(read_until);
- }
- if(!keyframe_updated) {
-
-
-
- usleep(30000);
- continue;
- }
-
- std::vector<hdl_graph_slam::Loop::Ptr> loops = loop_detector->detect(keyframes, new_keyframes, *graph_slam);
-
- for(const auto& loop : loops) {
- Eigen::Isometry3d relpose(loop->relative_pose.cast<double>());
- Eigen::MatrixXd information_matrix = inf_calclator->calc_information_matrix(loop->key1->cloud, loop->key2->cloud, relpose);
- auto edge = graph_slam->add_se3_edge(loop->key1->node, loop->key2->node, relpose, information_matrix);
- graph_slam->add_robust_kernel(edge, "Huber", 2);
-
- }
- std::copy(new_keyframes.begin(), new_keyframes.end(), std::back_inserter(keyframes));
- new_keyframes.clear();
-
-
- if(anchor_node && true) {
- Eigen::Isometry3d anchor_target = static_cast<g2o::VertexSE3*>(anchor_edge->vertices()[1])->estimate();
- anchor_node->setEstimate(anchor_target);
-
- }
-
- int num_iterations = 5000;
-
-
-
-
-
- graph_slam->optimize(num_iterations);
-
- num_added_keyframe++;
- LOG(INFO) << "完成g2o的图优化==============";
-
-
-
-
- std::vector<hdl_graph_slam::KeyFrameSnapshot::Ptr> snapshot(keyframes.size());
- std::transform(keyframes.begin(), keyframes.end(), snapshot.begin(), [=](const hdl_graph_slam::KeyFrame::Ptr& k) { return std::make_shared<hdl_graph_slam::KeyFrameSnapshot>(k); });
- keyframes_snapshot_mutex.lock();
- keyframes_snapshot.swap(snapshot);
- keyframes_snapshot_mutex.unlock();
- graph_updated = true;
-
- const auto& keyframe = keyframes.back();
- Eigen::Isometry3d trans = keyframe->node->estimate() * keyframe->odom.inverse();
- trans_odom2map_mutex.lock();
- trans_odom2map = trans.matrix().cast<float>();
- trans_odom2map_mutex.unlock();
-
- geometry_msgs::TransformStamped ts = hdl_graph_slam::matrix2transform(keyframe->stamp, trans.matrix().cast<float>(), map_frame_id, odom_frame_id);
-
-
-
-
-
- auto markers = create_marker_array(ros::Time::now());
- markers_pub.publish(markers);
-
-
- publishMatrixAsPose(odom_pub, keyframes[keyframes.size() - 1]->node->estimate().matrix().cast<float>());
-
- usleep(30000);
- }
- LOG(INFO) << "end()";
- }
- void hdl_backend::publishMatrixAsPose(ros::Publisher& publisher, const Eigen::Matrix4f& matrix) {
-
- Eigen::Vector3f translation = matrix.block<3, 1>(0, 3);
-
- Eigen::Matrix3f rotation_matrix = matrix.block<3, 3>(0, 0);
- Eigen::Quaternionf quaternion(rotation_matrix);
-
- geometry_msgs::PoseStamped pose_msg;
- pose_msg.header.stamp = ros::Time ::now();
- pose_msg.header.frame_id = "odom";
- pose_msg.pose.position.x = translation.x();
- pose_msg.pose.position.y = translation.y();
- pose_msg.pose.position.z = translation.z();
- pose_msg.pose.orientation.x = quaternion.x();
- pose_msg.pose.orientation.y = quaternion.y();
- pose_msg.pose.orientation.z = quaternion.z();
- pose_msg.pose.orientation.w = quaternion.w();
-
- publisher.publish(pose_msg);
- }
- void hdl_backend::map_points_publish_timer_callback(const ros::WallTimerEvent& event) {
-
-
- if(!graph_updated) {
-
- return;
- }
-
- pcl::PointCloud<PointT>::Ptr trans_cloud;
- trans_cloud.reset(new pcl::PointCloud<PointT>());
- for(int i = 0; i < keyframes.size(); i++) {
- pcl::PointCloud<PointT>::Ptr cloud_i(new pcl::PointCloud<PointT>());
- pcl::transformPointCloud(*keyframes[i]->cloud, *cloud_i, keyframes[i]->node->estimate().matrix());
- *trans_cloud += *cloud_i;
- }
- trans_cloud->header.frame_id = map_frame_id;
- trans_cloud->header.stamp = keyframes_snapshot.back()->cloud->header.stamp;
-
- sensor_msgs::PointCloud2Ptr cloud2_msg(new sensor_msgs::PointCloud2());
- pcl::toROSMsg(*trans_cloud, *cloud2_msg);
- cloud2_msg->header.frame_id = "map";
-
- map_points_pub2.publish(*cloud2_msg);
-
- std::vector<hdl_graph_slam::KeyFrameSnapshot::Ptr> snapshot;
- snapshot = keyframes_snapshot;
-
- auto cloud = map_cloud_generator->generate(snapshot, map_cloud_resolution);
- if(!cloud) {
- return;
- }
- cloud->header.frame_id = map_frame_id;
- cloud->header.stamp = snapshot.back()->cloud->header.stamp;
- sensor_msgs::PointCloud2Ptr cloud_msg(new sensor_msgs::PointCloud2());
- pcl::toROSMsg(*cloud, *cloud_msg);
- map_points_pub.publish(*cloud_msg);
-
-
- }
- pcl::PointCloud<PointT>::ConstPtr hdl_backend::downsample(const pcl::PointCloud<PointT>::ConstPtr& cloud) {
- if(!downsample_filter) {
- return cloud;
- }
- pcl::PointCloud<PointT>::Ptr filtered(new pcl::PointCloud<PointT>());
- downsample_filter->setInputCloud(cloud);
- downsample_filter->filter(*filtered);
- return filtered;
- }
- pcl::PointCloud<PointT>::ConstPtr hdl_backend::outlier_removal(const pcl::PointCloud<PointT>::ConstPtr& cloud) {
- if(!outlier_removal_filter) {
- return cloud;
- }
- pcl::PointCloud<PointT>::Ptr filtered(new pcl::PointCloud<PointT>());
- outlier_removal_filter->setInputCloud(cloud);
- outlier_removal_filter->filter(*filtered);
- filtered->header = cloud->header;
- return filtered;
- }
- void hdl_backend::cloud_callback(const nav_msgs::OdometryConstPtr& odom_msg, const sensor_msgs::PointCloud2::ConstPtr& cloud_msg) {
- const ros::Time& stamp = cloud_msg->header.stamp;
- Eigen::Isometry3d odom = hdl_graph_slam::odom2isometry(odom_msg);
- pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>());
- pcl::fromROSMsg(*cloud_msg, *cloud);
- if(base_frame_id.empty()) {
- base_frame_id = cloud_msg->header.frame_id;
- }
- auto filtered = downsample(cloud);
- filtered = outlier_removal(filtered);
-
- double delta_time = 1000;
- if(keyframe_queue.size() != 0) delta_time = (stamp - keyframe_queue.back()->stamp).toSec();
- if(!keyframe_updater->update(odom, delta_time)) {
-
- if(keyframe_queue.empty()) {
-
- std_msgs::Header read_until;
- read_until.stamp = stamp + ros::Duration(10, 0);
- read_until.frame_id = points_topic;
- read_until_pub.publish(read_until);
- read_until.frame_id = "/filtered_points";
- read_until_pub.publish(read_until);
- }
- return;
- }
- double accum_d = keyframe_updater->get_accum_distance();
-
- hdl_graph_slam::KeyFrame::Ptr keyframe(new hdl_graph_slam::KeyFrame(stamp, odom, accum_d, filtered));
-
-
- keyframe_queue.push_back(keyframe);
-
- }
- bool hdl_backend::flush_keyframe_queue() {
- std::lock_guard<std::mutex> lock(keyframe_queue_mutex);
-
-
- if(keyframe_queue.empty()) {
- return false;
- }
- trans_odom2map_mutex.lock();
- Eigen::Isometry3d odom2map(trans_odom2map.cast<double>());
- trans_odom2map_mutex.unlock();
-
- int num_processed = 0;
-
-
- for(int i = 0; i < keyframe_queue.size(); i++) {
- num_processed = i;
- const auto& keyframe = keyframe_queue[i];
-
- new_keyframes.push_back(keyframe);
-
- Eigen::Isometry3d odom = odom2map * keyframe->odom;
- keyframe->node = graph_slam->add_se3_node(odom);
-
- if(keyframes.empty() && new_keyframes.size() == 1) {
-
- Eigen::MatrixXd inf = Eigen::MatrixXd::Identity(6, 6);
-
- std::stringstream sst("10 10 10 1 1 1");
- for(int i = 0; i < 6; i++) {
- double stddev = 1.0;
- sst >> stddev;
- inf(i, i) = 1.0 / stddev;
- }
- anchor_node = graph_slam->add_se3_node(Eigen::Isometry3d::Identity());
- anchor_node->setFixed(true);
- anchor_edge = graph_slam->add_se3_edge(anchor_node, keyframe->node, Eigen::Isometry3d::Identity(), inf);
-
- }
- if(i == 0 && keyframes.empty()) {
- continue;
- }
-
- const auto& prev_keyframe = i == 0 ? keyframes.back() : keyframe_queue[i - 1];
- Eigen::Isometry3d relative_pose = keyframe->odom.inverse() * prev_keyframe->odom;
- Eigen::MatrixXd information = inf_calclator->calc_information_matrix(keyframe->cloud, prev_keyframe->cloud, relative_pose);
- auto edge = graph_slam->add_se3_edge(keyframe->node, prev_keyframe->node, relative_pose, information);
- graph_slam->add_robust_kernel(edge, "NONE", 1.0);
-
-
-
- }
- std_msgs::Header read_until;
- read_until.stamp = keyframe_queue[num_processed]->stamp + ros::Duration(10, 0);
- read_until.frame_id = points_topic;
- read_until_pub.publish(read_until);
- read_until.frame_id = "/filtered_points";
- read_until_pub.publish(read_until);
- keyframe_queue.erase(keyframe_queue.begin(), keyframe_queue.begin() + num_processed + 1);
- return true;
- }
-
- bool hdl_backend::save_map_service(hdl_graph_slam::SaveMapRequest& req, hdl_graph_slam::SaveMapResponse& res) {
- std::cout << "get in save_map_service !!!" << std::endl;
- std::vector<hdl_graph_slam::KeyFrameSnapshot::Ptr> snapshot1;
-
- snapshot1 = keyframes_snapshot;
-
- auto cloud = map_cloud_generator->generate(snapshot1, req.resolution);
- if(!cloud) {
- res.success = false;
- return true;
- }
- if(zero_utm && req.utm) {
- for(auto& pt : cloud->points) {
- pt.getVector3fMap() += (*zero_utm).cast<float>();
- }
- }
- cloud->header.frame_id = "map";
- cloud->header.stamp = snapshot1.back()->cloud->header.stamp;
- if(zero_utm) {
- std::ofstream ofs(req.destination + ".utm");
- ofs << boost::format("%.6f %.6f %.6f") % zero_utm->x() % zero_utm->y() % zero_utm->z() << std::endl;
- }
- int ret = pcl::io::savePCDFileBinary(req.destination, *cloud);
- res.success = ret == 0;
- return true;
- }
- visualization_msgs::MarkerArray hdl_backend::create_marker_array(const ros::Time& stamp) const {
- visualization_msgs::MarkerArray markers;
- markers.markers.resize(4);
-
- visualization_msgs::Marker& traj_marker = markers.markers[0];
- traj_marker.header.frame_id = "map";
- traj_marker.header.stamp = stamp;
- traj_marker.ns = "nodes";
- traj_marker.id = 0;
- traj_marker.type = visualization_msgs::Marker::SPHERE_LIST;
- traj_marker.pose.orientation.w = 1.0;
- traj_marker.scale.x = traj_marker.scale.y = traj_marker.scale.z = 0.5;
- visualization_msgs::Marker& imu_marker = markers.markers[1];
- imu_marker.header = traj_marker.header;
- imu_marker.ns = "imu";
- imu_marker.id = 1;
- imu_marker.type = visualization_msgs::Marker::SPHERE_LIST;
- imu_marker.pose.orientation.w = 1.0;
- imu_marker.scale.x = imu_marker.scale.y = imu_marker.scale.z = 0.75;
- traj_marker.points.resize(keyframes.size());
- traj_marker.colors.resize(keyframes.size());
- for(int i = 0; i < keyframes.size(); i++) {
- Eigen::Vector3d pos = keyframes[i]->node->estimate().translation();
- traj_marker.points[i].x = pos.x();
- traj_marker.points[i].y = pos.y();
- traj_marker.points[i].z = pos.z();
- double p = static_cast<double>(i) / keyframes.size();
- traj_marker.colors[i].r = 1.0 - p;
- traj_marker.colors[i].g = p;
- traj_marker.colors[i].b = 0.0;
- traj_marker.colors[i].a = 1.0;
- if(keyframes[i]->acceleration) {
- Eigen::Vector3d pos = keyframes[i]->node->estimate().translation();
- geometry_msgs::Point point;
- point.x = pos.x();
- point.y = pos.y();
- point.z = pos.z();
- std_msgs::ColorRGBA color;
- color.r = 0.0;
- color.g = 0.0;
- color.b = 1.0;
- color.a = 0.1;
- imu_marker.points.push_back(point);
- imu_marker.colors.push_back(color);
- }
- }
-
- visualization_msgs::Marker& edge_marker = markers.markers[2];
- edge_marker.header.frame_id = "map";
- edge_marker.header.stamp = stamp;
- edge_marker.ns = "edges";
- edge_marker.id = 2;
- edge_marker.type = visualization_msgs::Marker::LINE_LIST;
- edge_marker.pose.orientation.w = 1.0;
- edge_marker.scale.x = 0.05;
- edge_marker.points.resize(graph_slam->graph->edges().size() * 2);
- edge_marker.colors.resize(graph_slam->graph->edges().size() * 2);
- auto edge_itr = graph_slam->graph->edges().begin();
- for(int i = 0; edge_itr != graph_slam->graph->edges().end(); edge_itr++, i++) {
- g2o::HyperGraph::Edge* edge = *edge_itr;
- g2o::EdgeSE3* edge_se3 = dynamic_cast<g2o::EdgeSE3*>(edge);
- if(edge_se3) {
- g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_se3->vertices()[0]);
- g2o::VertexSE3* v2 = dynamic_cast<g2o::VertexSE3*>(edge_se3->vertices()[1]);
- Eigen::Vector3d pt1 = v1->estimate().translation();
- Eigen::Vector3d pt2 = v2->estimate().translation();
- edge_marker.points[i * 2].x = pt1.x();
- edge_marker.points[i * 2].y = pt1.y();
- edge_marker.points[i * 2].z = pt1.z();
- edge_marker.points[i * 2 + 1].x = pt2.x();
- edge_marker.points[i * 2 + 1].y = pt2.y();
- edge_marker.points[i * 2 + 1].z = pt2.z();
- double p1 = static_cast<double>(v1->id()) / graph_slam->graph->vertices().size();
- double p2 = static_cast<double>(v2->id()) / graph_slam->graph->vertices().size();
- edge_marker.colors[i * 2].r = 1.0 - p1;
- edge_marker.colors[i * 2].g = p1;
- edge_marker.colors[i * 2].a = 1.0;
- edge_marker.colors[i * 2 + 1].r = 1.0 - p2;
- edge_marker.colors[i * 2 + 1].g = p2;
- edge_marker.colors[i * 2 + 1].a = 1.0;
- if(std::abs(v1->id() - v2->id()) > 2) {
- edge_marker.points[i * 2].z += 0.5;
- edge_marker.points[i * 2 + 1].z += 0.5;
- }
- continue;
- }
- g2o::EdgeSE3Plane* edge_plane = dynamic_cast<g2o::EdgeSE3Plane*>(edge);
- if(edge_plane) {
- g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_plane->vertices()[0]);
- Eigen::Vector3d pt1 = v1->estimate().translation();
- Eigen::Vector3d pt2(pt1.x(), pt1.y(), 0.0);
- edge_marker.points[i * 2].x = pt1.x();
- edge_marker.points[i * 2].y = pt1.y();
- edge_marker.points[i * 2].z = pt1.z();
- edge_marker.points[i * 2 + 1].x = pt2.x();
- edge_marker.points[i * 2 + 1].y = pt2.y();
- edge_marker.points[i * 2 + 1].z = pt2.z();
- edge_marker.colors[i * 2].b = 1.0;
- edge_marker.colors[i * 2].a = 1.0;
- edge_marker.colors[i * 2 + 1].b = 1.0;
- edge_marker.colors[i * 2 + 1].a = 1.0;
- continue;
- }
- g2o::EdgeSE3PriorXY* edge_priori_xy = dynamic_cast<g2o::EdgeSE3PriorXY*>(edge);
- if(edge_priori_xy) {
- g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_priori_xy->vertices()[0]);
- Eigen::Vector3d pt1 = v1->estimate().translation();
- Eigen::Vector3d pt2 = Eigen::Vector3d::Zero();
- pt2.head<2>() = edge_priori_xy->measurement();
- edge_marker.points[i * 2].x = pt1.x();
- edge_marker.points[i * 2].y = pt1.y();
- edge_marker.points[i * 2].z = pt1.z() + 0.5;
- edge_marker.points[i * 2 + 1].x = pt2.x();
- edge_marker.points[i * 2 + 1].y = pt2.y();
- edge_marker.points[i * 2 + 1].z = pt2.z() + 0.5;
- edge_marker.colors[i * 2].r = 1.0;
- edge_marker.colors[i * 2].a = 1.0;
- edge_marker.colors[i * 2 + 1].r = 1.0;
- edge_marker.colors[i * 2 + 1].a = 1.0;
- continue;
- }
- g2o::EdgeSE3PriorXYZ* edge_priori_xyz = dynamic_cast<g2o::EdgeSE3PriorXYZ*>(edge);
- if(edge_priori_xyz) {
- g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_priori_xyz->vertices()[0]);
- Eigen::Vector3d pt1 = v1->estimate().translation();
- Eigen::Vector3d pt2 = edge_priori_xyz->measurement();
- edge_marker.points[i * 2].x = pt1.x();
- edge_marker.points[i * 2].y = pt1.y();
- edge_marker.points[i * 2].z = pt1.z() + 0.5;
- edge_marker.points[i * 2 + 1].x = pt2.x();
- edge_marker.points[i * 2 + 1].y = pt2.y();
- edge_marker.points[i * 2 + 1].z = pt2.z();
- edge_marker.colors[i * 2].r = 1.0;
- edge_marker.colors[i * 2].a = 1.0;
- edge_marker.colors[i * 2 + 1].r = 1.0;
- edge_marker.colors[i * 2 + 1].a = 1.0;
- continue;
- }
- }
-
- visualization_msgs::Marker& sphere_marker = markers.markers[3];
- sphere_marker.header.frame_id = "map";
- sphere_marker.header.stamp = stamp;
- sphere_marker.ns = "loop_close_radius";
- sphere_marker.id = 3;
- sphere_marker.type = visualization_msgs::Marker::SPHERE;
- if(!keyframes.empty()) {
- Eigen::Vector3d pos = keyframes.back()->node->estimate().translation();
- sphere_marker.pose.position.x = pos.x();
- sphere_marker.pose.position.y = pos.y();
- sphere_marker.pose.position.z = pos.z();
- }
- sphere_marker.pose.orientation.w = 1.0;
- sphere_marker.scale.x = sphere_marker.scale.y = sphere_marker.scale.z = loop_detector->get_distance_thresh() * 2.0;
- sphere_marker.color.r = 1.0;
- sphere_marker.color.a = 0.3;
- return markers;
- }
|