hdl_backend.cpp 30 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672
  1. #include <iostream>
  2. #include <ros/ros.h>
  3. #include "hdl_backend.hpp"
  4. // #include <pcl_ros/point_cloud.h>
  5. #include <pcl_ros/point_cloud.h>
  6. #include <hdl_graph_slam/ros_utils.hpp>
  7. #include <functional> // std::bind 和 std::placeholders
  8. #include "hdl_graph_slam/keyframe_updater.hpp"
  9. #include <visualization_msgs/MarkerArray.h>
  10. #include <glog/logging.h>
  11. // #include <vector.h>
  12. #include <geometry_msgs/TransformStamped.h>
  13. #include <geometry_msgs/PoseWithCovarianceStamped.h>
  14. hdl_backend* instance = nullptr; // 初始化静态单例(分配内存, 调用hdl_backend 的默认构造函数)
  15. // hdl_backend& hdl_opt = hdl_backend::getInstance(); // 因为 静态成员变量 instance 是私有的,需要 静态成员函数 getInstance() 拿到 instance, 并且起个别名(引用)
  16. typedef pcl::PointXYZI PointT;
  17. int main(int argc, char* argv[]) {
  18. // 执行 ros 节点初始化
  19. ros::init(argc, argv, "hdl_backend");
  20. std::cout << "hdl backend get in ...===============" << std::endl;
  21. instance = new hdl_backend();
  22. // hdl_backend& hdl_opt = instance->getInstance();
  23. instance->init();
  24. return 0;
  25. }
  26. void hdl_backend::init() {
  27. map_frame_id = "map";
  28. odom_frame_id = "odom";
  29. map_cloud_resolution = 0.01; // 地图点云分辨率
  30. trans_odom2map.setIdentity(); // 设置为单位矩阵
  31. max_keyframes_per_update = 10;
  32. keyframe_updater.reset(new hdl_graph_slam::KeyframeUpdater(nh));
  33. points_topic = "/velodyne_points";
  34. graph_slam.reset(new hdl_graph_slam::GraphSLAM("lm_var_cholmod")); // 智能指针,用reset重新初始化,让它重新指向新分配的对象
  35. // graph_slam.reset(new GraphSLAM(private_nh.param<std::string>("g2o_solver_type", "lm_var"))); // 智能指针,用reset重新初始化,让它重新指向新分配的对象
  36. auto voxelgrid = new pcl::VoxelGrid<PointT>();
  37. voxelgrid->setLeafSize(downsample_resolution, downsample_resolution, downsample_resolution);
  38. downsample_filter.reset(voxelgrid);
  39. inf_calclator.reset(new hdl_graph_slam::InformationMatrixCalculator(nh));
  40. loop_detector.reset(new hdl_graph_slam::LoopDetector(nh));
  41. anchor_node = nullptr;
  42. anchor_edge = nullptr;
  43. odom_sub.reset(new message_filters::Subscriber<nav_msgs::Odometry>(nh, "/laser_odom", 256)); // 创建 message_filters::Subscriber 对象,用于订阅nav_msgs::Odometry类型的消息
  44. // cloud_sub.reset(new message_filters::Subscriber<sensor_msgs::PointCloud2>(nh, "/keyframe_points", 32)); // 创建 message_filters::Subscriber 对象,用于订阅sensor_msgs::PointCloud2类型的消息。
  45. // cloud_sub.reset(new message_filters::Subscriber<sensor_msgs::PointCloud2>(nh, "/velodyne_points", 32)); // 三维
  46. cloud_sub.reset(new message_filters::Subscriber<sensor_msgs::PointCloud2>(nh, "/filtered_points", 32)); // 二维
  47. // 现在的 /filtered_points 是原始点云数据,没有做坐标转换, 滤波, 将采样等
  48. // keyframe_points 在前端做了降采样
  49. sync.reset(new message_filters::Synchronizer<ApproxSyncPolicy>(ApproxSyncPolicy(32), *odom_sub, *cloud_sub)); // 创建 message_filters::Synchronizer 对象,用于同步上面创建的两个订阅者(odom_sub和cloud_sub)的消息。
  50. sync->registerCallback(boost::bind(&hdl_backend::cloud_callback, this, _1, _2)); // 为同步器注册了一个回调函数,当同步条件满足时,会调用HdlGraphSlamNodelet类的cloud_callback成员函数
  51. markers_pub = nh.advertise<visualization_msgs::MarkerArray>("/hdl_graph_slam/markers", 16); // 发布可视化数据(具体是什么还不知道) 这种类型的消息通常用于在RViz等可视化工具中显示标记(markers)
  52. odom2map_pub = nh.advertise<geometry_msgs::TransformStamped>("/hdl_graph_slam/odom2pub", 16); // 发布从里程计到地图的变换
  53. map_points_pub = nh.advertise<sensor_msgs::PointCloud2>("/hdl_graph_slam/map_points", 1, true); // 这个话题会保留以前扫描过的点云!! 扫过的地方的点云就是
  54. map_points_pub2 = nh.advertise<sensor_msgs::PointCloud2>("/hdl_graph_slam/map_points2", 1, true); // 这个话题会保留以前扫描过的点云!! 扫过的地方的点云就是
  55. read_until_pub = nh.advertise<std_msgs::Header>("/hdl_graph_slam/read_until", 32); // 这种类型的消息通常用于指示读取操作应该持续到何时
  56. odom_pub = nh.advertise<geometry_msgs::PoseStamped>("/opt_odom", 32);
  57. save_map_service_server = nh.advertiseService("/hdl_graph_slam/save_map", &hdl_backend::save_map_service, this); // 保存地图
  58. graph_updated = false;
  59. double graph_update_interval = 3; // 表示图优化更新的时间间隔,默认值为3.0秒 interval:间隔
  60. double map_cloud_update_interval = 5; // 地图点云更新的时间间隔,默认值为10.0秒
  61. // optimization_timer = nh.createWallTimer(ros::WallDuration(graph_update_interval), &hdl_backend::optimization_timer_callback, this); // 创建一个定时器,定时器会在每个 graph_update_interval 秒后触发,然后调用 optimization_timer_callback 函数
  62. map_publish_timer = nh.createWallTimer(ros::WallDuration(map_cloud_update_interval), &hdl_backend::map_points_publish_timer_callback, this); // 创建一个定时器,定时器会在每个 map_cloud_update_interval 秒后触发,然后调用 map_points_publish_timer_callback 函数
  63. pcl::RadiusOutlierRemoval<PointT>::Ptr rad(new pcl::RadiusOutlierRemoval<PointT>());
  64. rad->setRadiusSearch(0.8);
  65. rad->setMinNeighborsInRadius(1);
  66. outlier_removal_filter = rad;
  67. std::thread proc_thread(&hdl_backend::optimization_timer_callback, this);
  68. proc_thread.detach();
  69. ros::spin();
  70. }
  71. /**
  72. * @brief 这个函数将队列中的所有数据添加到姿势图中,然后优化姿势图
  73. * @param event // 是ROS提供的定时器时间类,包含信息有:计时器出发的时间戳、上一次出发的时间戳、计时器的周期信息等
  74. */
  75. // void hdl_backend::optimization_timer_callback(const ros::WallTimerEvent& event) {
  76. void hdl_backend::optimization_timer_callback() {
  77. LOG(INFO) << "begin()";
  78. while(ros::ok()) {
  79. std::lock_guard<std::mutex> lock(main_thread_mutex); // 创建了一个锁,用于保护对主线程的访问,确保线程安全
  80. // add keyframes and floor coeffs in the queues to the pose graph 将队列中的关键帧和楼层系数添加到姿势图中
  81. bool keyframe_updated = flush_keyframe_queue(); // 调用 flush_keyframe_queue 函数,将关键帧队列中的数据添加到位姿图中,并返回是否有关键帧被更新
  82. if(!keyframe_updated) { // 如果没有关键帧被更新,则执行大括号内的代码
  83. std_msgs::Header read_until;
  84. read_until.stamp = ros::Time::now() + ros::Duration(30, 0); // 时间戳为什么要加30秒?
  85. read_until.frame_id = points_topic;
  86. read_until_pub.publish(read_until);
  87. read_until.frame_id = "/filtered_points";
  88. read_until_pub.publish(read_until); // 不同的 frame_id 和 话题 发布两次, 是干嘛用的?
  89. }
  90. if(!keyframe_updated) {
  91. // 检查地板、GPS、IMU等队列,分别调用相应的 flush 函数(例如 flush_floor_queue、flush_gps_queue、flush_imu_queue),如果这些数据没有更新,则函数直接返回,不进行后续操作。
  92. // LOG(INFO) << "关键帧没有更新,usleep(30000); & continue;";
  93. // return;
  94. usleep(30000);
  95. continue;
  96. }
  97. // loop detection 闭环检测
  98. std::vector<hdl_graph_slam::Loop::Ptr> loops = loop_detector->detect(keyframes, new_keyframes, *graph_slam);
  99. // 如果检测到闭环,则为闭环关系添加一个新的边到位姿图中,计算相对位姿并生成信息矩阵,确保闭环边的优化权重。
  100. for(const auto& loop : loops) { // 遍历闭环检测结果
  101. Eigen::Isometry3d relpose(loop->relative_pose.cast<double>());
  102. Eigen::MatrixXd information_matrix = inf_calclator->calc_information_matrix(loop->key1->cloud, loop->key2->cloud, relpose);
  103. auto edge = graph_slam->add_se3_edge(loop->key1->node, loop->key2->node, relpose, information_matrix); // 添加边,位姿之间的关系构成边(edge)
  104. graph_slam->add_robust_kernel(edge, "Huber", 2);
  105. // graph_slam->add_robust_kernel(edge, "NONE", 0.01); // Huber Cauchy Tukey None
  106. }
  107. std::copy(new_keyframes.begin(), new_keyframes.end(), std::back_inserter(keyframes)); // 将新关键帧 new_keyframes 合并到已有的关键帧列表 keyframes 中
  108. new_keyframes.clear(); // 清空 new_keyframes
  109. // move the first node anchor position to the current estimate of the first node pose 将第一节点锚点位置移动到第一节点姿态的当前估计值
  110. // so the first node moves freely while trying to stay around the origin 因此 , 第一个节点在试图停留在原点附近的同时可以自由移动
  111. if(anchor_node && true) { // launch文件中,fix_first_node_adaptive 设置为 true // 这个能不能设置为false
  112. Eigen::Isometry3d anchor_target = static_cast<g2o::VertexSE3*>(anchor_edge->vertices()[1])->estimate();
  113. anchor_node->setEstimate(anchor_target);
  114. // 如果启用了自适应固定第一帧的功能(参数 "fix_first_node_adaptive"),则将第一个关键帧的锚点位置更新为当前估计的位置,以允许它自由移动但仍然保持在原点附近。
  115. }
  116. // optimize the pose graph
  117. int num_iterations = 5000; // launch文件中都是设置成512
  118. // for(int i = 0; i < keyframes.size(); i++){
  119. // // std::cout << "before optimize, odom[" << i << "] = \n" << keyframes[i]->odom.matrix() << std::endl;
  120. // std::cout << "before optimize, odom[" << i << "] = \n" << keyframes[i]->node->estimate().matrix() << std::endl;
  121. // }
  122. // if(num_added_keyframe % 5 == 0){
  123. graph_slam->optimize(num_iterations);
  124. // }
  125. num_added_keyframe++;
  126. LOG(INFO) << "完成g2o的图优化==============";
  127. // for(int i = 0; i < keyframes.size(); i++){
  128. // // std::cout << "after optimize, odom[" << i << "] = \n" << keyframes[i]->odom.matrix() << std::endl;
  129. // std::cout << "after optimize, odom[" << i << "] = \n" << keyframes[i]->node->estimate().matrix() << std::endl;
  130. // }
  131. std::vector<hdl_graph_slam::KeyFrameSnapshot::Ptr> snapshot(keyframes.size());
  132. std::transform(keyframes.begin(), keyframes.end(), snapshot.begin(), [=](const hdl_graph_slam::KeyFrame::Ptr& k) { return std::make_shared<hdl_graph_slam::KeyFrameSnapshot>(k); });
  133. keyframes_snapshot_mutex.lock();
  134. keyframes_snapshot.swap(snapshot);
  135. keyframes_snapshot_mutex.unlock();
  136. graph_updated = true;
  137. // publish tf 发布位姿变换
  138. const auto& keyframe = keyframes.back(); // 获取最新的关键帧估计
  139. Eigen::Isometry3d trans = keyframe->node->estimate() * keyframe->odom.inverse();
  140. trans_odom2map_mutex.lock();
  141. trans_odom2map = trans.matrix().cast<float>();
  142. trans_odom2map_mutex.unlock();
  143. // if(odom2map_pub.getNumSubscribers()) {
  144. geometry_msgs::TransformStamped ts = hdl_graph_slam::matrix2transform(keyframe->stamp, trans.matrix().cast<float>(), map_frame_id, odom_frame_id);
  145. // ts.header.stamp = ros::Time::now(); // ?
  146. // odom2map_pub.publish(ts); // 发布odom2map_pub话题中/
  147. // LOG(INFO) << "odom2map TF变换发布完成";
  148. // }
  149. // if(markers_pub.getNumSubscribers()) {
  150. auto markers = create_marker_array(ros::Time::now());
  151. markers_pub.publish(markers);
  152. // LOG(INFO) << "markers_pub 发布完成";
  153. // }
  154. publishMatrixAsPose(odom_pub, keyframes[keyframes.size() - 1]->node->estimate().matrix().cast<float>());
  155. // nav_msgs::Odometry
  156. usleep(30000);
  157. }
  158. LOG(INFO) << "end()";
  159. }
  160. void hdl_backend::publishMatrixAsPose(ros::Publisher& publisher, const Eigen::Matrix4f& matrix) {
  161. // 提取平移部分
  162. Eigen::Vector3f translation = matrix.block<3, 1>(0, 3);
  163. // 提取旋转部分
  164. Eigen::Matrix3f rotation_matrix = matrix.block<3, 3>(0, 0);
  165. Eigen::Quaternionf quaternion(rotation_matrix);
  166. // 创建并填充 PoseStamped 消息
  167. geometry_msgs::PoseStamped pose_msg;
  168. pose_msg.header.stamp = ros::Time ::now();
  169. pose_msg.header.frame_id = "odom"; // 设置坐标系
  170. pose_msg.pose.position.x = translation.x();
  171. pose_msg.pose.position.y = translation.y();
  172. pose_msg.pose.position.z = translation.z();
  173. pose_msg.pose.orientation.x = quaternion.x();
  174. pose_msg.pose.orientation.y = quaternion.y();
  175. pose_msg.pose.orientation.z = quaternion.z();
  176. pose_msg.pose.orientation.w = quaternion.w();
  177. // 发布消息
  178. publisher.publish(pose_msg);
  179. }
  180. /**
  181. * @brief generate map point cloud and publish it
  182. * @param event
  183. */
  184. void hdl_backend::map_points_publish_timer_callback(const ros::WallTimerEvent& event) {
  185. // 源码中,发布是图优化完之后发布才有内容的
  186. // LOG(INFO) << graph_updated;
  187. if(!graph_updated) {
  188. // if(!map_points_pub.getNumSubscribers() || !graph_updated) {
  189. return;
  190. }
  191. // 直接发keyframe试一下?
  192. pcl::PointCloud<PointT>::Ptr trans_cloud;
  193. trans_cloud.reset(new pcl::PointCloud<PointT>());
  194. for(int i = 0; i < keyframes.size(); i++) {
  195. pcl::PointCloud<PointT>::Ptr cloud_i(new pcl::PointCloud<PointT>());
  196. pcl::transformPointCloud(*keyframes[i]->cloud, *cloud_i, keyframes[i]->node->estimate().matrix());
  197. *trans_cloud += *cloud_i;
  198. }
  199. trans_cloud->header.frame_id = map_frame_id;
  200. trans_cloud->header.stamp = keyframes_snapshot.back()->cloud->header.stamp;
  201. // 发布
  202. sensor_msgs::PointCloud2Ptr cloud2_msg(new sensor_msgs::PointCloud2());
  203. pcl::toROSMsg(*trans_cloud, *cloud2_msg);
  204. cloud2_msg->header.frame_id = "map";
  205. // keyframe_points_pub.publish(*cloud2_msg); // 话题名:
  206. map_points_pub2.publish(*cloud2_msg);
  207. // 发布点云数据
  208. std::vector<hdl_graph_slam::KeyFrameSnapshot::Ptr> snapshot;
  209. snapshot = keyframes_snapshot;
  210. // LOG(INFO) << "keyframes_snapshot.size() = " << keyframes_snapshot.size();
  211. auto cloud = map_cloud_generator->generate(snapshot, map_cloud_resolution);
  212. if(!cloud) {
  213. return;
  214. }
  215. cloud->header.frame_id = map_frame_id;
  216. cloud->header.stamp = snapshot.back()->cloud->header.stamp;
  217. sensor_msgs::PointCloud2Ptr cloud_msg(new sensor_msgs::PointCloud2());
  218. pcl::toROSMsg(*cloud, *cloud_msg);
  219. map_points_pub.publish(*cloud_msg);
  220. // LOG(INFO) << "点云数据发布完成";
  221. // LOG(INFO) << "map_points_publish_timer_callback 函数执行完毕";
  222. }
  223. /**
  224. * @brief downsample a point cloud
  225. * @param cloud input cloud
  226. * @return downsampled point cloud
  227. */
  228. pcl::PointCloud<PointT>::ConstPtr hdl_backend::downsample(const pcl::PointCloud<PointT>::ConstPtr& cloud) { // 对点云数据进行向下采样,减少点的数量以提高处理速度
  229. if(!downsample_filter) {
  230. return cloud;
  231. }
  232. pcl::PointCloud<PointT>::Ptr filtered(new pcl::PointCloud<PointT>()); // 创建一个新的点云对象,用来存储下采样后的点云数据
  233. downsample_filter->setInputCloud(cloud);
  234. downsample_filter->filter(*filtered);
  235. return filtered;
  236. }
  237. pcl::PointCloud<PointT>::ConstPtr hdl_backend::outlier_removal(const pcl::PointCloud<PointT>::ConstPtr& cloud) {
  238. if(!outlier_removal_filter) {
  239. return cloud;
  240. }
  241. pcl::PointCloud<PointT>::Ptr filtered(new pcl::PointCloud<PointT>());
  242. outlier_removal_filter->setInputCloud(cloud);
  243. outlier_removal_filter->filter(*filtered);
  244. filtered->header = cloud->header;
  245. return filtered;
  246. }
  247. /**
  248. * @brief 接收点云数据并放到 keyframe_queue 中
  249. * @param odom_msg 前端的激光里程计数据
  250. * @param cloud_msg 前端滤波后的点云数据
  251. */
  252. void hdl_backend::cloud_callback(const nav_msgs::OdometryConstPtr& odom_msg, const sensor_msgs::PointCloud2::ConstPtr& cloud_msg) {
  253. const ros::Time& stamp = cloud_msg->header.stamp; // 获取点云数据的时间戳
  254. Eigen::Isometry3d odom = hdl_graph_slam::odom2isometry(odom_msg); // 将里程计消息转换为Eigen库中的Isometry3d类型,它表示一个3D刚体变换(包括旋转和平移)
  255. pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>()); // 创建一个点云对象的指针
  256. pcl::fromROSMsg(*cloud_msg, *cloud); // 将ROS的点云消息 cloud_msg 转换为PCL(Point Cloud Library)的点云格式
  257. if(base_frame_id.empty()) { // 用类的单例实现应该就ok?
  258. base_frame_id = cloud_msg->header.frame_id; // 将当前点云消息的坐标系 frame_id 设置为基础坐标系 base_frame_id 是整个系统中关键帧数据的参考坐标系
  259. }
  260. auto filtered = downsample(cloud);
  261. filtered = outlier_removal(filtered);
  262. // 更新关键帧判断
  263. double delta_time = 1000;
  264. if(keyframe_queue.size() != 0) delta_time = (stamp - keyframe_queue.back()->stamp).toSec();
  265. if(!keyframe_updater->update(odom, delta_time)) { // 根据当前的里程计信息 odom 判断是否需要生成新的关键帧
  266. // std::lock_guard<std::mutex> lock(keyframe_queue_mutex); // 这行代码的作用是确保线程安全,防止多个线程同时访问或修改 keyframe_queue 队列
  267. if(keyframe_queue.empty()) { // 如果关键帧队列是空的,发布一个 ROS 消息通知系统继续读取点云数据,直到指定时间点(stamp + ros::Duration(10, 0))。这段代码确保在没有关键帧生成时,系统能够继续读取点云数据
  268. // LOG(INFO) << "keyframe_queue.empty()";
  269. std_msgs::Header read_until;
  270. read_until.stamp = stamp + ros::Duration(10, 0);
  271. read_until.frame_id = points_topic;
  272. read_until_pub.publish(read_until);
  273. read_until.frame_id = "/filtered_points";
  274. read_until_pub.publish(read_until);
  275. }
  276. return; //  如果没有关键帧更新,就 return
  277. }
  278. double accum_d = keyframe_updater->get_accum_distance(); // 获取累计的运动距离,用于判断关键帧生成的条件
  279. // std::cout << "============ accum_d ============" << accum_d << std::endl;
  280. hdl_graph_slam::KeyFrame::Ptr keyframe(new hdl_graph_slam::KeyFrame(stamp, odom, accum_d, filtered)); // 创建一个新的关键帧 keyframe,其中包含当前的时间戳 stamp,里程计信息 odom,累计距离 accum_d,以及处理后的点云数据 cloud(这里的处理就是做了个消息类型的转换)
  281. // LOG(INFO) << "get new keyframe!!!";
  282. // std::lock_guard<std::mutex> lock(keyframe_queue_mutex); // 使用 std::lock_guard 加锁,确保对关键帧队列 keyframe_queue 的操作是线程安全的
  283. keyframe_queue.push_back(keyframe); // 将新生成的关键帧 keyframe 推入 keyframe_queue 队列,供后续的处理使用
  284. // LOG(INFO) << "keyframe_queue.push_back(keyframe)";
  285. }
  286. /**
  287. * @brief this method adds all the keyframes in #keyframe_queue to the pose graph (odometry edges) 此方法将#keyframe_queue中的所有关键帧添加到姿势图中(里程计边)
  288. * @return if true, at least one keyframe was added to the pose graph 如果为真,则至少有一个关键帧被添加到姿势图中
  289. * 将队列中的关键帧添加到位姿图中,并返回是否至少有一个关键帧被添加
  290. */
  291. bool hdl_backend::flush_keyframe_queue() {
  292. std::lock_guard<std::mutex> lock(keyframe_queue_mutex); // 多线程锁
  293. // LOG(INFO) << "flush_keyframe_queue";
  294. // keyframe_queue: 存放关键帧队列
  295. if(keyframe_queue.empty()) { // 没有关键帧就返回
  296. return false;
  297. }
  298. trans_odom2map_mutex.lock();
  299. Eigen::Isometry3d odom2map(trans_odom2map.cast<double>()); // odom 到 map 的齐次变换矩阵
  300. trans_odom2map_mutex.unlock();
  301. // std::cout << "flush_keyframe_queue - keyframes len:" << keyframes.size() << std::endl;
  302. int num_processed = 0;
  303. // for(int i = 0; i < std::min<int>(keyframe_queue.size(), max_keyframes_per_update); i++) { // max_keyframes_per_update = 10
  304. // 这里有问题吧? keyframe_queue 是 push_back 的,是加在后面的呀,上面这个for循环不是只处理前10个keyframe?
  305. for(int i = 0; i < keyframe_queue.size(); i++) { // max_keyframes_per_update = 10
  306. num_processed = i;
  307. const auto& keyframe = keyframe_queue[i];
  308. // new_keyframes will be tested later for loop closure
  309. new_keyframes.push_back(keyframe);
  310. // add pose node
  311. Eigen::Isometry3d odom = odom2map * keyframe->odom; // 一个4*4的矩阵,齐次变换矩阵
  312. keyframe->node = graph_slam->add_se3_node(odom); // 添加节点,在graph-based SLAM中,机器人的位姿是一个节点(node)
  313. // fix the first node 固定第一个节点,整段代码只运行一次
  314. if(keyframes.empty() && new_keyframes.size() == 1) {
  315. // if(nh.param<bool>("fix_first_node", false)) { // launch 中是 true
  316. Eigen::MatrixXd inf = Eigen::MatrixXd::Identity(6, 6);
  317. // std::stringstream sst(nh.param<std::string>("fix_first_node_stddev", "1 1 1 1 1 1")); // 这个是什么意思?
  318. std::stringstream sst("10 10 10 1 1 1"); // 这个是什么意思?
  319. for(int i = 0; i < 6; i++) {
  320. double stddev = 1.0;
  321. sst >> stddev;
  322. inf(i, i) = 1.0 / stddev;
  323. }
  324. anchor_node = graph_slam->add_se3_node(Eigen::Isometry3d::Identity()); // 添加节点,在graph-based SLAM中,机器人的位姿是一个节点(node)
  325. anchor_node->setFixed(true);
  326. anchor_edge = graph_slam->add_se3_edge(anchor_node, keyframe->node, Eigen::Isometry3d::Identity(), inf); // 添加边,位姿之间的关系构成边(edge)
  327. // }
  328. }
  329. if(i == 0 && keyframes.empty()) {
  330. continue;
  331. }
  332. // add edge between consecutive keyframes
  333. const auto& prev_keyframe = i == 0 ? keyframes.back() : keyframe_queue[i - 1];
  334. Eigen::Isometry3d relative_pose = keyframe->odom.inverse() * prev_keyframe->odom;
  335. Eigen::MatrixXd information = inf_calclator->calc_information_matrix(keyframe->cloud, prev_keyframe->cloud, relative_pose);
  336. auto edge = graph_slam->add_se3_edge(keyframe->node, prev_keyframe->node, relative_pose, information); // 添加边,位姿之间的关系构成边(edge)
  337. graph_slam->add_robust_kernel(edge, "NONE", 1.0);
  338. // graph_slam->add_robust_kernel(edge, "Tukey", 0.1);
  339. // std::cout << "keyframe->node = \n" << keyframe->node->estimate().matrix() << std::endl;
  340. // std::cout << "prev_keyframe->node = \n" << prev_keyframe->node->estimate().matrix() << std::endl;
  341. }
  342. std_msgs::Header read_until;
  343. read_until.stamp = keyframe_queue[num_processed]->stamp + ros::Duration(10, 0);
  344. read_until.frame_id = points_topic;
  345. read_until_pub.publish(read_until);
  346. read_until.frame_id = "/filtered_points";
  347. read_until_pub.publish(read_until);
  348. keyframe_queue.erase(keyframe_queue.begin(), keyframe_queue.begin() + num_processed + 1); // 这里把keyframe都删了
  349. return true;
  350. }
  351. /**
  352. * @brief save map data as pcd
  353. * @param req
  354. * @param res
  355. * @return
  356. */
  357. bool hdl_backend::save_map_service(hdl_graph_slam::SaveMapRequest& req, hdl_graph_slam::SaveMapResponse& res) {
  358. std::cout << "get in save_map_service !!!" << std::endl;
  359. std::vector<hdl_graph_slam::KeyFrameSnapshot::Ptr> snapshot1;
  360. // keyframes_snapshot_mutex.lock();
  361. snapshot1 = keyframes_snapshot;
  362. // keyframes_snapshot_mutex.unlock();
  363. auto cloud = map_cloud_generator->generate(snapshot1, req.resolution);
  364. if(!cloud) {
  365. res.success = false;
  366. return true;
  367. }
  368. if(zero_utm && req.utm) {
  369. for(auto& pt : cloud->points) {
  370. pt.getVector3fMap() += (*zero_utm).cast<float>();
  371. }
  372. }
  373. cloud->header.frame_id = "map";
  374. cloud->header.stamp = snapshot1.back()->cloud->header.stamp;
  375. if(zero_utm) {
  376. std::ofstream ofs(req.destination + ".utm");
  377. ofs << boost::format("%.6f %.6f %.6f") % zero_utm->x() % zero_utm->y() % zero_utm->z() << std::endl;
  378. }
  379. int ret = pcl::io::savePCDFileBinary(req.destination, *cloud);
  380. res.success = ret == 0;
  381. return true;
  382. }
  383. /**
  384. * @brief create visualization marker
  385. * @param stamp
  386. * @return
  387. */
  388. visualization_msgs::MarkerArray hdl_backend::create_marker_array(const ros::Time& stamp) const {
  389. visualization_msgs::MarkerArray markers;
  390. markers.markers.resize(4);
  391. // node markers
  392. visualization_msgs::Marker& traj_marker = markers.markers[0];
  393. traj_marker.header.frame_id = "map";
  394. traj_marker.header.stamp = stamp;
  395. traj_marker.ns = "nodes";
  396. traj_marker.id = 0;
  397. traj_marker.type = visualization_msgs::Marker::SPHERE_LIST;
  398. traj_marker.pose.orientation.w = 1.0;
  399. traj_marker.scale.x = traj_marker.scale.y = traj_marker.scale.z = 0.5;
  400. visualization_msgs::Marker& imu_marker = markers.markers[1];
  401. imu_marker.header = traj_marker.header;
  402. imu_marker.ns = "imu";
  403. imu_marker.id = 1;
  404. imu_marker.type = visualization_msgs::Marker::SPHERE_LIST;
  405. imu_marker.pose.orientation.w = 1.0;
  406. imu_marker.scale.x = imu_marker.scale.y = imu_marker.scale.z = 0.75;
  407. traj_marker.points.resize(keyframes.size());
  408. traj_marker.colors.resize(keyframes.size());
  409. for(int i = 0; i < keyframes.size(); i++) {
  410. Eigen::Vector3d pos = keyframes[i]->node->estimate().translation();
  411. traj_marker.points[i].x = pos.x();
  412. traj_marker.points[i].y = pos.y();
  413. traj_marker.points[i].z = pos.z();
  414. double p = static_cast<double>(i) / keyframes.size();
  415. traj_marker.colors[i].r = 1.0 - p;
  416. traj_marker.colors[i].g = p;
  417. traj_marker.colors[i].b = 0.0;
  418. traj_marker.colors[i].a = 1.0;
  419. if(keyframes[i]->acceleration) {
  420. Eigen::Vector3d pos = keyframes[i]->node->estimate().translation();
  421. geometry_msgs::Point point;
  422. point.x = pos.x();
  423. point.y = pos.y();
  424. point.z = pos.z();
  425. std_msgs::ColorRGBA color;
  426. color.r = 0.0;
  427. color.g = 0.0;
  428. color.b = 1.0;
  429. color.a = 0.1;
  430. imu_marker.points.push_back(point);
  431. imu_marker.colors.push_back(color);
  432. }
  433. }
  434. // edge markers
  435. visualization_msgs::Marker& edge_marker = markers.markers[2];
  436. edge_marker.header.frame_id = "map";
  437. edge_marker.header.stamp = stamp;
  438. edge_marker.ns = "edges";
  439. edge_marker.id = 2;
  440. edge_marker.type = visualization_msgs::Marker::LINE_LIST;
  441. edge_marker.pose.orientation.w = 1.0;
  442. edge_marker.scale.x = 0.05;
  443. edge_marker.points.resize(graph_slam->graph->edges().size() * 2);
  444. edge_marker.colors.resize(graph_slam->graph->edges().size() * 2);
  445. auto edge_itr = graph_slam->graph->edges().begin();
  446. for(int i = 0; edge_itr != graph_slam->graph->edges().end(); edge_itr++, i++) {
  447. g2o::HyperGraph::Edge* edge = *edge_itr;
  448. g2o::EdgeSE3* edge_se3 = dynamic_cast<g2o::EdgeSE3*>(edge);
  449. if(edge_se3) {
  450. g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_se3->vertices()[0]);
  451. g2o::VertexSE3* v2 = dynamic_cast<g2o::VertexSE3*>(edge_se3->vertices()[1]);
  452. Eigen::Vector3d pt1 = v1->estimate().translation();
  453. Eigen::Vector3d pt2 = v2->estimate().translation();
  454. edge_marker.points[i * 2].x = pt1.x();
  455. edge_marker.points[i * 2].y = pt1.y();
  456. edge_marker.points[i * 2].z = pt1.z();
  457. edge_marker.points[i * 2 + 1].x = pt2.x();
  458. edge_marker.points[i * 2 + 1].y = pt2.y();
  459. edge_marker.points[i * 2 + 1].z = pt2.z();
  460. double p1 = static_cast<double>(v1->id()) / graph_slam->graph->vertices().size();
  461. double p2 = static_cast<double>(v2->id()) / graph_slam->graph->vertices().size();
  462. edge_marker.colors[i * 2].r = 1.0 - p1;
  463. edge_marker.colors[i * 2].g = p1;
  464. edge_marker.colors[i * 2].a = 1.0;
  465. edge_marker.colors[i * 2 + 1].r = 1.0 - p2;
  466. edge_marker.colors[i * 2 + 1].g = p2;
  467. edge_marker.colors[i * 2 + 1].a = 1.0;
  468. if(std::abs(v1->id() - v2->id()) > 2) {
  469. edge_marker.points[i * 2].z += 0.5;
  470. edge_marker.points[i * 2 + 1].z += 0.5;
  471. }
  472. continue;
  473. }
  474. g2o::EdgeSE3Plane* edge_plane = dynamic_cast<g2o::EdgeSE3Plane*>(edge);
  475. if(edge_plane) {
  476. g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_plane->vertices()[0]);
  477. Eigen::Vector3d pt1 = v1->estimate().translation();
  478. Eigen::Vector3d pt2(pt1.x(), pt1.y(), 0.0);
  479. edge_marker.points[i * 2].x = pt1.x();
  480. edge_marker.points[i * 2].y = pt1.y();
  481. edge_marker.points[i * 2].z = pt1.z();
  482. edge_marker.points[i * 2 + 1].x = pt2.x();
  483. edge_marker.points[i * 2 + 1].y = pt2.y();
  484. edge_marker.points[i * 2 + 1].z = pt2.z();
  485. edge_marker.colors[i * 2].b = 1.0;
  486. edge_marker.colors[i * 2].a = 1.0;
  487. edge_marker.colors[i * 2 + 1].b = 1.0;
  488. edge_marker.colors[i * 2 + 1].a = 1.0;
  489. continue;
  490. }
  491. g2o::EdgeSE3PriorXY* edge_priori_xy = dynamic_cast<g2o::EdgeSE3PriorXY*>(edge);
  492. if(edge_priori_xy) {
  493. g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_priori_xy->vertices()[0]);
  494. Eigen::Vector3d pt1 = v1->estimate().translation();
  495. Eigen::Vector3d pt2 = Eigen::Vector3d::Zero();
  496. pt2.head<2>() = edge_priori_xy->measurement();
  497. edge_marker.points[i * 2].x = pt1.x();
  498. edge_marker.points[i * 2].y = pt1.y();
  499. edge_marker.points[i * 2].z = pt1.z() + 0.5;
  500. edge_marker.points[i * 2 + 1].x = pt2.x();
  501. edge_marker.points[i * 2 + 1].y = pt2.y();
  502. edge_marker.points[i * 2 + 1].z = pt2.z() + 0.5;
  503. edge_marker.colors[i * 2].r = 1.0;
  504. edge_marker.colors[i * 2].a = 1.0;
  505. edge_marker.colors[i * 2 + 1].r = 1.0;
  506. edge_marker.colors[i * 2 + 1].a = 1.0;
  507. continue;
  508. }
  509. g2o::EdgeSE3PriorXYZ* edge_priori_xyz = dynamic_cast<g2o::EdgeSE3PriorXYZ*>(edge);
  510. if(edge_priori_xyz) {
  511. g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_priori_xyz->vertices()[0]);
  512. Eigen::Vector3d pt1 = v1->estimate().translation();
  513. Eigen::Vector3d pt2 = edge_priori_xyz->measurement();
  514. edge_marker.points[i * 2].x = pt1.x();
  515. edge_marker.points[i * 2].y = pt1.y();
  516. edge_marker.points[i * 2].z = pt1.z() + 0.5;
  517. edge_marker.points[i * 2 + 1].x = pt2.x();
  518. edge_marker.points[i * 2 + 1].y = pt2.y();
  519. edge_marker.points[i * 2 + 1].z = pt2.z();
  520. edge_marker.colors[i * 2].r = 1.0;
  521. edge_marker.colors[i * 2].a = 1.0;
  522. edge_marker.colors[i * 2 + 1].r = 1.0;
  523. edge_marker.colors[i * 2 + 1].a = 1.0;
  524. continue;
  525. }
  526. }
  527. // sphere
  528. visualization_msgs::Marker& sphere_marker = markers.markers[3];
  529. sphere_marker.header.frame_id = "map";
  530. sphere_marker.header.stamp = stamp;
  531. sphere_marker.ns = "loop_close_radius";
  532. sphere_marker.id = 3;
  533. sphere_marker.type = visualization_msgs::Marker::SPHERE;
  534. if(!keyframes.empty()) {
  535. Eigen::Vector3d pos = keyframes.back()->node->estimate().translation();
  536. sphere_marker.pose.position.x = pos.x();
  537. sphere_marker.pose.position.y = pos.y();
  538. sphere_marker.pose.position.z = pos.z();
  539. }
  540. sphere_marker.pose.orientation.w = 1.0;
  541. sphere_marker.scale.x = sphere_marker.scale.y = sphere_marker.scale.z = loop_detector->get_distance_thresh() * 2.0;
  542. sphere_marker.color.r = 1.0;
  543. sphere_marker.color.a = 0.3;
  544. return markers;
  545. }