hdl_graph_slam_nodelet.cpp 58 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192
  1. // SPDX-License-Identifier: BSD-2-Clause
  2. #include <ctime>
  3. #include <mutex>
  4. #include <atomic>
  5. #include <memory>
  6. #include <iomanip>
  7. #include <iostream>
  8. #include <unordered_map>
  9. #include <boost/format.hpp>
  10. #include <boost/thread.hpp>
  11. #include <boost/filesystem.hpp>
  12. #include <boost/algorithm/string.hpp>
  13. #include <Eigen/Dense>
  14. #include <pcl/io/pcd_io.h>
  15. #include <ros/ros.h>
  16. #include <geodesy/utm.h>
  17. #include <geodesy/wgs84.h>
  18. #include <pcl_ros/point_cloud.h>
  19. #include <message_filters/subscriber.h>
  20. #include <message_filters/time_synchronizer.h>
  21. #include <message_filters/sync_policies/approximate_time.h>
  22. #include <tf_conversions/tf_eigen.h>
  23. #include <tf/transform_listener.h>
  24. #include <std_msgs/Time.h>
  25. #include <nav_msgs/Odometry.h>
  26. #include <nmea_msgs/Sentence.h>
  27. #include <sensor_msgs/Imu.h>
  28. #include <sensor_msgs/NavSatFix.h>
  29. #include <sensor_msgs/PointCloud2.h>
  30. #include <geographic_msgs/GeoPointStamped.h>
  31. #include <visualization_msgs/MarkerArray.h>
  32. #include <hdl_graph_slam/FloorCoeffs.h>
  33. #include <hdl_graph_slam/SaveMap.h>
  34. #include <hdl_graph_slam/LoadGraph.h>
  35. #include <hdl_graph_slam/DumpGraph.h>
  36. #include <nodelet/nodelet.h>
  37. #include <pluginlib/class_list_macros.h>
  38. #include <hdl_graph_slam/ros_utils.hpp>
  39. #include <hdl_graph_slam/ros_time_hash.hpp>
  40. #include <hdl_graph_slam/graph_slam.hpp>
  41. #include <hdl_graph_slam/keyframe.hpp>
  42. #include <hdl_graph_slam/keyframe_updater.hpp>
  43. #include <hdl_graph_slam/loop_detector.hpp>
  44. #include <hdl_graph_slam/information_matrix_calculator.hpp>
  45. #include <hdl_graph_slam/map_cloud_generator.hpp>
  46. #include <hdl_graph_slam/nmea_sentence_parser.hpp>
  47. #include <g2o/types/slam3d/edge_se3.h>
  48. #include <g2o/types/slam3d/vertex_se3.h>
  49. #include <g2o/edge_se3_plane.hpp>
  50. #include <g2o/edge_se3_priorxy.hpp>
  51. #include <g2o/edge_se3_priorxyz.hpp>
  52. #include <g2o/edge_se3_priorvec.hpp>
  53. #include <g2o/edge_se3_priorquat.hpp>
  54. /*
  55. 后端的作用(GPT):
  56. 1. 构建位资图:
  57. 后端根据前端生成的关键帧位姿和相对位姿变换,构建位姿图(Pose Graph),每个关键帧对应图中的一个节点,节点之间的相对运动构成边。
  58. 2. 闭环检测
  59. 后端通过检测闭环(即机器人经过某个已经访问过的地方)来减少累积误差。闭环检测通过计算当前帧和之前帧之间的相似度来发现闭环位置,并将其加入位姿图中,形成闭环约束边。
  60. 3. 图优化
  61. 利用优化算法(如g2o或Ceres)对整个位姿图进行优化。目标是调整位姿图中所有关键帧的位姿,
  62. 使之符合所有的约束(包括相邻关键帧的相对位姿约束以及闭环检测生成的约束),从而减少传感器噪声和漂移,生成全局一致的地图
  63. */
  64. namespace hdl_graph_slam {
  65. class HdlGraphSlamNodelet : public nodelet::Nodelet {
  66. public:
  67. typedef pcl::PointXYZI PointT;
  68. typedef message_filters::sync_policies::ApproximateTime<nav_msgs::Odometry, sensor_msgs::PointCloud2> ApproxSyncPolicy;
  69. HdlGraphSlamNodelet() {}
  70. virtual ~HdlGraphSlamNodelet() {}
  71. virtual void onInit() { // 初始化函数
  72. // 申请节点句柄
  73. nh = getNodeHandle();
  74. mt_nh = getMTNodeHandle();
  75. private_nh = getPrivateNodeHandle();
  76. // init parameters 初始化参数
  77. published_odom_topic = private_nh.param<std::string>("published_odom_topic", "/odom");
  78. map_frame_id = private_nh.param<std::string>("map_frame_id", "map");
  79. odom_frame_id = private_nh.param<std::string>("odom_frame_id", "odom");
  80. map_cloud_resolution = private_nh.param<double>("map_cloud_resolution", 0.05);
  81. trans_odom2map.setIdentity();
  82. max_keyframes_per_update = private_nh.param<int>("max_keyframes_per_update", 10);
  83. // 一些指针的初始化
  84. anchor_node = nullptr; // 普通指针,直接给 nullptr
  85. anchor_edge = nullptr;
  86. floor_plane_node = nullptr;
  87. graph_slam.reset(new GraphSLAM(private_nh.param<std::string>("g2o_solver_type", "lm_var"))); // 智能指针,用reset重新初始化,让它重新指向新分配的对象
  88. keyframe_updater.reset(new KeyframeUpdater(private_nh));
  89. loop_detector.reset(new LoopDetector(private_nh));
  90. map_cloud_generator.reset(new MapCloudGenerator());
  91. inf_calclator.reset(new InformationMatrixCalculator(private_nh));
  92. nmea_parser.reset(new NmeaSentenceParser());
  93. // 从参数服务器中读取参数
  94. // 第一个参数是参数服务器中的变量名,第二个参数是如果参数服务器中没有这个变量的默认取值
  95. gps_time_offset = private_nh.param<double>("gps_time_offset", 0.0); // GPS时间戳与SLAM系统内部时间戳之间的偏移量,用于同步GPS数据和SLAM系统的时间
  96. gps_edge_stddev_xy = private_nh.param<double>("gps_edge_stddev_xy", 10000.0); // GPS测量在XY平面(水平方向)的标准差,用于量化GPS测量的不确定性,通常用于优化算法中权重的计算
  97. gps_edge_stddev_z = private_nh.param<double>("gps_edge_stddev_z", 10.0); // GPS测量在Z轴(垂直方向)的标准差,用于量化GPS测量的不确定性
  98. floor_edge_stddev = private_nh.param<double>("floor_edge_stddev", 10.0); // 与地面相关的测量或估计的标准差,例如在检测到地面时用于优化算法
  99. imu_time_offset = private_nh.param<double>("imu_time_offset", 0.0); // IMU(惯性测量单元)时间戳与SLAM系统内部时间戳之间的偏移量,用于同步IMU数据和SLAM系统的时间
  100. enable_imu_orientation = private_nh.param<bool>("enable_imu_orientation", false); // 指示是否启用IMU的方位数据
  101. enable_imu_acceleration = private_nh.param<bool>("enable_imu_acceleration", false); // 指示是否启用IMU的加速度数据
  102. imu_orientation_edge_stddev = private_nh.param<double>("imu_orientation_edge_stddev", 0.1); // IMU方位测量的标准差,用于量化IMU方位测量的不确定性
  103. imu_acceleration_edge_stddev = private_nh.param<double>("imu_acceleration_edge_stddev", 3.0); // IMU加速度测量的标准差,用于量化IMU加速度测量的不确定性
  104. points_topic = private_nh.param<std::string>("points_topic", "/velodyne_points"); // 点云数据的ROS话题名称,SLAM系统将订阅这个话题来获取点云数据
  105. // 这个话题的info是:
  106. /*
  107. (slam_env) mj@mj-Lenovo-Legion-R9000P2021H:~$ rostopic info /velodyne_points
  108. Type: sensor_msgs/PointCloud2
  109. Publishers:
  110. * /player (http://mj-Lenovo-Legion-R9000P2021H:35735/)
  111. 这个发布方是 rosbag 呀,是没处理过的点云信息,后端怎么会订阅没处理过的点云数据?
  112. 也不是用来订阅的,这个文件是用这个话题来发布的,但是发布的内容又只有时间戳和frameid? 为什么这么奇怪?
  113. 结合 read_until_pub 的解释来看,似乎是用来指示操作应该持续到何时,所以这个应该不用管
  114. Subscribers:
  115. * /velodyne_nodelet_manager (http://mj-Lenovo-Legion-R9000P2021H:39235/)
  116. * /rviz_1729770290778318983 (http://mj-Lenovo-Legion-R9000P2021H:34629/)
  117. */
  118. // subscribers
  119. // 话题通信的接受方
  120. odom_sub.reset(new message_filters::Subscriber<nav_msgs::Odometry>(mt_nh, published_odom_topic, 256)); // 创建一个新的message_filters::Subscriber对象,用于订阅nav_msgs::Odometry类型的消息
  121. cloud_sub.reset(new message_filters::Subscriber<sensor_msgs::PointCloud2>(mt_nh, "/filtered_points", 32)); // 创建一个新的message_filters::Subscriber对象,用于订阅sensor_msgs::PointCloud2类型的消息。
  122. // ApproxSyncPolicy 是一个同步策略,允许在一定时间窗口内的消息进行同步,这里设置的窗口大小为32
  123. sync.reset(new message_filters::Synchronizer<ApproxSyncPolicy>(ApproxSyncPolicy(32), *odom_sub, *cloud_sub)); // 创建一个新的message_filters::Synchronizer对象,用于同步上面创建的两个订阅者(odom_sub和cloud_sub)的消息。
  124. sync->registerCallback(boost::bind(&HdlGraphSlamNodelet::cloud_callback, this, _1, _2)); // 为同步器注册了一个回调函数,当同步条件满足时,会调用HdlGraphSlamNodelet类的cloud_callback成员函数
  125. // 调用 cloud_callback 函数的条件:
  126. // 消息同步:odom_sub 和 cloud_sub 两个订阅者各自收到消息后,sync 会根据 ApproximateTime 策略尝试同步它们的时间戳。
  127. // 时间戳接近:两个消息的时间戳不需要完全一致,只要在一定范围内(由 ApproximateTime 策略自动决定),就会被认为是同步的。
  128. // 队列不为空:odom_sub 和 cloud_sub 的消息队列必须都各自至少包含一条消息,以便同步器能进行匹配。
  129. // 队列中找到匹配的消息对:当订阅者的队列中找到符合同步条件的消息对(即时间戳接近的 Odometry 和 PointCloud2 消息),就会触发 cloud_callback。
  130. imu_sub = nh.subscribe("/gpsimu_driver/imu_data", 1024, &HdlGraphSlamNodelet::imu_callback, this); // 接受并处理 imu 数据(小车没有imu,所以这个回调函数可以不看)
  131. floor_sub = nh.subscribe("/floor_detection/floor_coeffs", 1024, &HdlGraphSlamNodelet::floor_coeffs_callback, this); // 接受并处理 地板检测 数据(小车没有地板检测,所以这个回调函数可以不看)
  132. if(private_nh.param<bool>("enable_gps", true)) { // !!!因为我们的小车没有GPS,所以这几个 callback 函数可以不看 !!!
  133. gps_sub = mt_nh.subscribe("/gps/geopoint", 1024, &HdlGraphSlamNodelet::gps_callback, this); // 接受并处理 GPS 数据
  134. nmea_sub = mt_nh.subscribe("/gpsimu_driver/nmea_sentence", 1024, &HdlGraphSlamNodelet::nmea_callback, this); //
  135. navsat_sub = mt_nh.subscribe("/gps/navsat", 1024, &HdlGraphSlamNodelet::navsat_callback, this); //
  136. }
  137. // publishers
  138. // 话题通信的发布方
  139. markers_pub = mt_nh.advertise<visualization_msgs::MarkerArray>("/hdl_graph_slam/markers", 16); // 发布可视化数据(具体是什么还不知道) 这种类型的消息通常用于在RViz等可视化工具中显示标记(markers)
  140. odom2map_pub = mt_nh.advertise<geometry_msgs::TransformStamped>("/hdl_graph_slam/odom2pub", 16); // 发布从里程计到地图的变换
  141. map_points_pub = mt_nh.advertise<sensor_msgs::PointCloud2>("/hdl_graph_slam/map_points", 1, true); // 这个话题会保留以前扫描过的点云!! 扫过的地方的点云就是
  142. read_until_pub = mt_nh.advertise<std_msgs::Header>("/hdl_graph_slam/read_until", 32); // 这种类型的消息通常用于指示读取操作应该持续到何时
  143. // 服务通信:一个节点(客户端)发送一个服务请求给服务服务器,服务服务器处理这个请求并返回一个响应。这是一种同步的、请求/响应模式的通信方式。
  144. load_service_server = mt_nh.advertiseService("/hdl_graph_slam/load", &HdlGraphSlamNodelet::load_service, this); // 加载系统数据或状态 创建了一个服务服务器load_service_server,用于处理名为"/hdl_graph_slam/load"的服务请求,服务的处理函数是HdlGraphSlamNodelet类的load_service成员函数
  145. dump_service_server = mt_nh.advertiseService("/hdl_graph_slam/dump", &HdlGraphSlamNodelet::dump_service, this); // 转储系统当前的状态或数据 创建了一个服务服务器dump_service_server,用于处理名为"/hdl_graph_slam/dump"的服务请求,服务的处理函数是HdlGraphSlamNodelet类的dump_service成员函数
  146. save_map_service_server = mt_nh.advertiseService("/hdl_graph_slam/save_map", &HdlGraphSlamNodelet::save_map_service, this); // 保存地图
  147. graph_updated = false; // 用于跟踪图优化是否已经更新
  148. double graph_update_interval = private_nh.param<double>("graph_update_interval", 3.0); // 表示图优化更新的时间间隔,默认值为3.0秒 interval:间隔
  149. double map_cloud_update_interval = private_nh.param<double>("map_cloud_update_interval", 10.0); // 地图点云更新的时间间隔,默认值为10.0秒
  150. // 主要是这个回调函数!!!
  151. optimization_timer = mt_nh.createWallTimer(ros::WallDuration(graph_update_interval), &HdlGraphSlamNodelet::optimization_timer_callback, this); // 创建一个定时器,定时器会在每个 graph_update_interval 秒后触发,然后调用 optimization_timer_callback 函数
  152. map_publish_timer = mt_nh.createWallTimer(ros::WallDuration(map_cloud_update_interval), &HdlGraphSlamNodelet::map_points_publish_timer_callback, this); // 创建一个定时器,定时器会在每个 map_cloud_update_interval 秒后触发,然后调用 map_points_publish_timer_callback 函数
  153. // 函数入口都是 callback 函数,也即三个: cloud_callback 、 optimization_timer_callback 、 map_points_publish_timer_callback
  154. }
  155. private:
  156. /**
  157. * @brief received point clouds are pushed to #keyframe_queue
  158. * @param odom_msg // 前端的激光里程计数据
  159. * @param cloud_msg // 前端滤波后的点云数据
  160. */
  161. void cloud_callback(const nav_msgs::OdometryConstPtr& odom_msg, const sensor_msgs::PointCloud2::ConstPtr& cloud_msg) {
  162. // 接收并处理激光里程计数据和滤波后的点云数据,并判断是否生成关键帧,然后将新生成的关键帧推送到 keyframe_queue 队列中
  163. // 处理点云信息主要是:格式转换、设置frame_id
  164. const ros::Time& stamp = cloud_msg->header.stamp; // 获取点云数据的时间戳
  165. Eigen::Isometry3d odom = odom2isometry(odom_msg); // 将里程计消息转换为Eigen库中的Isometry3d类型,它表示一个3D刚体变换(包括旋转和平移)
  166. pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>()); // 创建一个点云对象的指针
  167. pcl::fromROSMsg(*cloud_msg, *cloud); // 将ROS的点云消息 cloud_msg 转换为PCL(Point Cloud Library)的点云格式
  168. if(base_frame_id.empty()) {
  169. base_frame_id = cloud_msg->header.frame_id; // 将当前点云消息的坐标系 frame_id 设置为基础坐标系 base_frame_id 是整个系统中关键帧数据的参考坐标系
  170. }
  171. // 更新关键帧判断
  172. if(!keyframe_updater->update(odom)) { // 根据当前的里程计信息 odom 判断是否需要生成新的关键帧
  173. std::lock_guard<std::mutex> lock(keyframe_queue_mutex); // 这行代码的作用是确保线程安全,防止多个线程同时访问或修改 keyframe_queue 队列
  174. // std::lock_guard<std::mutex> 是 C++ 标准库中的一个类,用来简化互斥锁(std::mutex)的使用。它的作用是在其作用域内自动对给定的互斥量加锁,并在作用域结束时自动解锁
  175. // keyframe_queue_mutex 是一个互斥量(std::mutex),用于保护关键帧队列 keyframe_queue。当多个线程试图同时访问或修改 keyframe_queue 时,互斥量确保只有一个线程能够访问该资源,避免数据竞争和并发问题
  176. // 工作原理:当这行代码执行时,lock_guard 会锁住 keyframe_queue_mutex,使其他线程无法访问与之关联的资源(即 keyframe_queue) 当程序执行离开该作用域时,lock_guard 会自动释放锁,无需显式调用 unlock() 函数
  177. // 为什么需要锁? 在多线程环境中(比如 ROS 回调函数可能被不同线程调用),如果多个线程同时读取或写入 keyframe_queue,可能导致数据不一致或崩溃。使用互斥量确保对 keyframe_queue 的操作是原子性的,即一个线程在操作时,其他线程必须等待
  178. if(keyframe_queue.empty()) { // 如果关键帧队列是空的,发布一个 ROS 消息通知系统继续读取点云数据,直到指定时间点(stamp + ros::Duration(10, 0))。这段代码确保在没有关键帧生成时,系统能够继续读取点云数据
  179. std_msgs::Header read_until;
  180. read_until.stamp = stamp + ros::Duration(10, 0);
  181. read_until.frame_id = points_topic;
  182. read_until_pub.publish(read_until);
  183. read_until.frame_id = "/filtered_points";
  184. read_until_pub.publish(read_until);
  185. }
  186. return;
  187. }
  188. double accum_d = keyframe_updater->get_accum_distance(); // 获取累计的运动距离,用于判断关键帧生成的条件
  189. KeyFrame::Ptr keyframe(new KeyFrame(stamp, odom, accum_d, cloud)); // 创建一个新的关键帧 keyframe,其中包含当前的时间戳 stamp,里程计信息 odom,累计距离 accum_d,以及处理后的点云数据 cloud(这里的处理就是做了个消息类型的转换)
  190. std::lock_guard<std::mutex> lock(keyframe_queue_mutex); // 使用 std::lock_guard 加锁,确保对关键帧队列 keyframe_queue 的操作是线程安全的
  191. keyframe_queue.push_back(keyframe); // 将新生成的关键帧 keyframe 推入 keyframe_queue 队列,供后续的处理使用
  192. }
  193. /**
  194. * @brief this method adds all the keyframes in #keyframe_queue to the pose graph (odometry edges) 此方法将#keyframe_queue中的所有关键帧添加到姿势图中(里程计边)
  195. * @return if true, at least one keyframe was added to the pose graph 如果为真,则至少有一个关键帧被添加到姿势图中
  196. * 将队列中的关键帧添加到位姿图中,并返回是否至少有一个关键帧被添加
  197. *
  198. * pose graph 是什么?
  199. */
  200. bool flush_keyframe_queue() {
  201. std::lock_guard<std::mutex> lock(keyframe_queue_mutex); // 多线程锁
  202. if(keyframe_queue.empty()) { // 没有关键帧就返回
  203. return false;
  204. }
  205. trans_odom2map_mutex.lock();
  206. Eigen::Isometry3d odom2map(trans_odom2map.cast<double>());
  207. trans_odom2map_mutex.unlock();
  208. std::cout << "flush_keyframe_queue - keyframes len:" << keyframes.size() << std::endl;
  209. int num_processed = 0;
  210. for(int i = 0; i < std::min<int>(keyframe_queue.size(), max_keyframes_per_update); i++) {
  211. num_processed = i;
  212. const auto& keyframe = keyframe_queue[i];
  213. // new_keyframes will be tested later for loop closure
  214. new_keyframes.push_back(keyframe);
  215. // add pose node
  216. Eigen::Isometry3d odom = odom2map * keyframe->odom;
  217. keyframe->node = graph_slam->add_se3_node(odom);
  218. keyframe_hash[keyframe->stamp] = keyframe;
  219. // fix the first node
  220. if(keyframes.empty() && new_keyframes.size() == 1) {
  221. if(private_nh.param<bool>("fix_first_node", false)) {
  222. Eigen::MatrixXd inf = Eigen::MatrixXd::Identity(6, 6);
  223. std::stringstream sst(private_nh.param<std::string>("fix_first_node_stddev", "1 1 1 1 1 1"));
  224. for(int i = 0; i < 6; i++) {
  225. double stddev = 1.0;
  226. sst >> stddev;
  227. inf(i, i) = 1.0 / stddev;
  228. }
  229. anchor_node = graph_slam->add_se3_node(Eigen::Isometry3d::Identity());
  230. anchor_node->setFixed(true);
  231. anchor_edge = graph_slam->add_se3_edge(anchor_node, keyframe->node, Eigen::Isometry3d::Identity(), inf);
  232. }
  233. }
  234. if(i == 0 && keyframes.empty()) {
  235. continue;
  236. }
  237. // add edge between consecutive keyframes
  238. const auto& prev_keyframe = i == 0 ? keyframes.back() : keyframe_queue[i - 1];
  239. Eigen::Isometry3d relative_pose = keyframe->odom.inverse() * prev_keyframe->odom;
  240. Eigen::MatrixXd information = inf_calclator->calc_information_matrix(keyframe->cloud, prev_keyframe->cloud, relative_pose);
  241. auto edge = graph_slam->add_se3_edge(keyframe->node, prev_keyframe->node, relative_pose, information);
  242. graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("odometry_edge_robust_kernel", "NONE"), private_nh.param<double>("odometry_edge_robust_kernel_size", 1.0));
  243. }
  244. std_msgs::Header read_until;
  245. read_until.stamp = keyframe_queue[num_processed]->stamp + ros::Duration(10, 0);
  246. read_until.frame_id = points_topic;
  247. read_until_pub.publish(read_until);
  248. read_until.frame_id = "/filtered_points";
  249. read_until_pub.publish(read_until);
  250. keyframe_queue.erase(keyframe_queue.begin(), keyframe_queue.begin() + num_processed + 1);
  251. return true;
  252. }
  253. void nmea_callback(const nmea_msgs::SentenceConstPtr& nmea_msg) {
  254. GPRMC grmc = nmea_parser->parse(nmea_msg->sentence);
  255. if(grmc.status != 'A') {
  256. return;
  257. }
  258. geographic_msgs::GeoPointStampedPtr gps_msg(new geographic_msgs::GeoPointStamped());
  259. gps_msg->header = nmea_msg->header;
  260. gps_msg->position.latitude = grmc.latitude;
  261. gps_msg->position.longitude = grmc.longitude;
  262. gps_msg->position.altitude = NAN;
  263. gps_callback(gps_msg);
  264. }
  265. void navsat_callback(const sensor_msgs::NavSatFixConstPtr& navsat_msg) {
  266. geographic_msgs::GeoPointStampedPtr gps_msg(new geographic_msgs::GeoPointStamped());
  267. gps_msg->header = navsat_msg->header;
  268. gps_msg->position.latitude = navsat_msg->latitude;
  269. gps_msg->position.longitude = navsat_msg->longitude;
  270. gps_msg->position.altitude = navsat_msg->altitude;
  271. gps_callback(gps_msg);
  272. }
  273. /**
  274. * @brief received gps data is added to #gps_queue
  275. * @param gps_msg
  276. */
  277. void gps_callback(const geographic_msgs::GeoPointStampedPtr& gps_msg) {
  278. std::lock_guard<std::mutex> lock(gps_queue_mutex);
  279. gps_msg->header.stamp += ros::Duration(gps_time_offset);
  280. gps_queue.push_back(gps_msg);
  281. }
  282. /**
  283. * @brief
  284. * @return
  285. */
  286. bool flush_gps_queue() {
  287. std::lock_guard<std::mutex> lock(gps_queue_mutex);
  288. if(keyframes.empty() || gps_queue.empty()) {
  289. return false;
  290. }
  291. bool updated = false;
  292. auto gps_cursor = gps_queue.begin();
  293. for(auto& keyframe : keyframes) {
  294. if(keyframe->stamp > gps_queue.back()->header.stamp) {
  295. break;
  296. }
  297. if(keyframe->stamp < (*gps_cursor)->header.stamp || keyframe->utm_coord) {
  298. continue;
  299. }
  300. // find the gps data which is closest to the keyframe
  301. auto closest_gps = gps_cursor;
  302. for(auto gps = gps_cursor; gps != gps_queue.end(); gps++) {
  303. auto dt = ((*closest_gps)->header.stamp - keyframe->stamp).toSec();
  304. auto dt2 = ((*gps)->header.stamp - keyframe->stamp).toSec();
  305. if(std::abs(dt) < std::abs(dt2)) {
  306. break;
  307. }
  308. closest_gps = gps;
  309. }
  310. // if the time residual between the gps and keyframe is too large, skip it
  311. gps_cursor = closest_gps;
  312. if(0.2 < std::abs(((*closest_gps)->header.stamp - keyframe->stamp).toSec())) {
  313. continue;
  314. }
  315. // convert (latitude, longitude, altitude) -> (easting, northing, altitude) in UTM coordinate
  316. geodesy::UTMPoint utm;
  317. geodesy::fromMsg((*closest_gps)->position, utm);
  318. Eigen::Vector3d xyz(utm.easting, utm.northing, utm.altitude);
  319. // the first gps data position will be the origin of the map
  320. if(!zero_utm) {
  321. zero_utm = xyz;
  322. }
  323. xyz -= (*zero_utm);
  324. keyframe->utm_coord = xyz;
  325. g2o::OptimizableGraph::Edge* edge;
  326. if(std::isnan(xyz.z())) {
  327. Eigen::Matrix2d information_matrix = Eigen::Matrix2d::Identity() / gps_edge_stddev_xy;
  328. edge = graph_slam->add_se3_prior_xy_edge(keyframe->node, xyz.head<2>(), information_matrix);
  329. } else {
  330. Eigen::Matrix3d information_matrix = Eigen::Matrix3d::Identity();
  331. information_matrix.block<2, 2>(0, 0) /= gps_edge_stddev_xy;
  332. information_matrix(2, 2) /= gps_edge_stddev_z;
  333. edge = graph_slam->add_se3_prior_xyz_edge(keyframe->node, xyz, information_matrix);
  334. }
  335. graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("gps_edge_robust_kernel", "NONE"), private_nh.param<double>("gps_edge_robust_kernel_size", 1.0));
  336. updated = true;
  337. }
  338. auto remove_loc = std::upper_bound(gps_queue.begin(), gps_queue.end(), keyframes.back()->stamp, [=](const ros::Time& stamp, const geographic_msgs::GeoPointStampedConstPtr& geopoint) { return stamp < geopoint->header.stamp; });
  339. gps_queue.erase(gps_queue.begin(), remove_loc);
  340. return updated;
  341. }
  342. void imu_callback(const sensor_msgs::ImuPtr& imu_msg) {
  343. if(!enable_imu_orientation && !enable_imu_acceleration) {
  344. return;
  345. }
  346. std::lock_guard<std::mutex> lock(imu_queue_mutex);
  347. imu_msg->header.stamp += ros::Duration(imu_time_offset);
  348. imu_queue.push_back(imu_msg);
  349. }
  350. bool flush_imu_queue() {
  351. std::lock_guard<std::mutex> lock(imu_queue_mutex);
  352. if(keyframes.empty() || imu_queue.empty() || base_frame_id.empty()) {
  353. return false;
  354. }
  355. bool updated = false;
  356. auto imu_cursor = imu_queue.begin();
  357. for(auto& keyframe : keyframes) {
  358. if(keyframe->stamp > imu_queue.back()->header.stamp) {
  359. break;
  360. }
  361. if(keyframe->stamp < (*imu_cursor)->header.stamp || keyframe->acceleration) {
  362. continue;
  363. }
  364. // find imu data which is closest to the keyframe
  365. auto closest_imu = imu_cursor;
  366. for(auto imu = imu_cursor; imu != imu_queue.end(); imu++) {
  367. auto dt = ((*closest_imu)->header.stamp - keyframe->stamp).toSec();
  368. auto dt2 = ((*imu)->header.stamp - keyframe->stamp).toSec();
  369. if(std::abs(dt) < std::abs(dt2)) {
  370. break;
  371. }
  372. closest_imu = imu;
  373. }
  374. imu_cursor = closest_imu;
  375. if(0.2 < std::abs(((*closest_imu)->header.stamp - keyframe->stamp).toSec())) {
  376. continue;
  377. }
  378. const auto& imu_ori = (*closest_imu)->orientation;
  379. const auto& imu_acc = (*closest_imu)->linear_acceleration;
  380. geometry_msgs::Vector3Stamped acc_imu;
  381. geometry_msgs::Vector3Stamped acc_base;
  382. geometry_msgs::QuaternionStamped quat_imu;
  383. geometry_msgs::QuaternionStamped quat_base;
  384. quat_imu.header.frame_id = acc_imu.header.frame_id = (*closest_imu)->header.frame_id;
  385. quat_imu.header.stamp = acc_imu.header.stamp = ros::Time(0);
  386. acc_imu.vector = (*closest_imu)->linear_acceleration;
  387. quat_imu.quaternion = (*closest_imu)->orientation;
  388. try {
  389. tf_listener.transformVector(base_frame_id, acc_imu, acc_base);
  390. tf_listener.transformQuaternion(base_frame_id, quat_imu, quat_base);
  391. } catch(std::exception& e) {
  392. std::cerr << "failed to find transform!!" << std::endl;
  393. return false;
  394. }
  395. keyframe->acceleration = Eigen::Vector3d(acc_base.vector.x, acc_base.vector.y, acc_base.vector.z);
  396. keyframe->orientation = Eigen::Quaterniond(quat_base.quaternion.w, quat_base.quaternion.x, quat_base.quaternion.y, quat_base.quaternion.z);
  397. keyframe->orientation = keyframe->orientation;
  398. if(keyframe->orientation->w() < 0.0) {
  399. keyframe->orientation->coeffs() = -keyframe->orientation->coeffs();
  400. }
  401. if(enable_imu_orientation) {
  402. Eigen::MatrixXd info = Eigen::MatrixXd::Identity(3, 3) / imu_orientation_edge_stddev;
  403. auto edge = graph_slam->add_se3_prior_quat_edge(keyframe->node, *keyframe->orientation, info);
  404. graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("imu_orientation_edge_robust_kernel", "NONE"), private_nh.param<double>("imu_orientation_edge_robust_kernel_size", 1.0));
  405. }
  406. if(enable_imu_acceleration) {
  407. Eigen::MatrixXd info = Eigen::MatrixXd::Identity(3, 3) / imu_acceleration_edge_stddev;
  408. g2o::OptimizableGraph::Edge* edge = graph_slam->add_se3_prior_vec_edge(keyframe->node, -Eigen::Vector3d::UnitZ(), *keyframe->acceleration, info);
  409. graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("imu_acceleration_edge_robust_kernel", "NONE"), private_nh.param<double>("imu_acceleration_edge_robust_kernel_size", 1.0));
  410. }
  411. updated = true;
  412. }
  413. auto remove_loc = std::upper_bound(imu_queue.begin(), imu_queue.end(), keyframes.back()->stamp, [=](const ros::Time& stamp, const sensor_msgs::ImuConstPtr& imu) { return stamp < imu->header.stamp; });
  414. imu_queue.erase(imu_queue.begin(), remove_loc);
  415. return updated;
  416. }
  417. /** 不做地板检测,这个函数不用看
  418. * @brief received floor coefficients are added to #floor_coeffs_queue
  419. * @param floor_coeffs_msg
  420. */
  421. void floor_coeffs_callback(const hdl_graph_slam::FloorCoeffsConstPtr& floor_coeffs_msg) {
  422. if(floor_coeffs_msg->coeffs.empty()) {
  423. return;
  424. }
  425. std::lock_guard<std::mutex> lock(floor_coeffs_queue_mutex);
  426. floor_coeffs_queue.push_back(floor_coeffs_msg);
  427. }
  428. /** 不做地板检测,这个函数不用看
  429. * @brief this methods associates floor coefficients messages with registered keyframes, and then adds the associated coeffs to the pose graph
  430. * @brief 该方法将地板系数消息与注册的关键帧相关联,然后将关联的系数添加到姿势图中。
  431. * @return if true, at least one floor plane edge is added to the pose graph
  432. * @return 如果为真,则至少有一个地板平面边被添加到姿势图中
  433. */
  434. bool flush_floor_queue() {
  435. std::lock_guard<std::mutex> lock(floor_coeffs_queue_mutex);
  436. if(keyframes.empty()) {
  437. return false;
  438. }
  439. const auto& latest_keyframe_stamp = keyframes.back()->stamp;
  440. bool updated = false;
  441. for(const auto& floor_coeffs : floor_coeffs_queue) {
  442. if(floor_coeffs->header.stamp > latest_keyframe_stamp) {
  443. break;
  444. }
  445. auto found = keyframe_hash.find(floor_coeffs->header.stamp);
  446. if(found == keyframe_hash.end()) {
  447. continue;
  448. }
  449. if(!floor_plane_node) {
  450. floor_plane_node = graph_slam->add_plane_node(Eigen::Vector4d(0.0, 0.0, 1.0, 0.0));
  451. floor_plane_node->setFixed(true);
  452. }
  453. const auto& keyframe = found->second;
  454. Eigen::Vector4d coeffs(floor_coeffs->coeffs[0], floor_coeffs->coeffs[1], floor_coeffs->coeffs[2], floor_coeffs->coeffs[3]);
  455. Eigen::Matrix3d information = Eigen::Matrix3d::Identity() * (1.0 / floor_edge_stddev);
  456. auto edge = graph_slam->add_se3_plane_edge(keyframe->node, floor_plane_node, coeffs, information);
  457. graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("floor_edge_robust_kernel", "NONE"), private_nh.param<double>("floor_edge_robust_kernel_size", 1.0));
  458. keyframe->floor_coeffs = coeffs;
  459. updated = true;
  460. }
  461. auto remove_loc = std::upper_bound(floor_coeffs_queue.begin(), floor_coeffs_queue.end(), latest_keyframe_stamp, [=](const ros::Time& stamp, const hdl_graph_slam::FloorCoeffsConstPtr& coeffs) { return stamp < coeffs->header.stamp; });
  462. floor_coeffs_queue.erase(floor_coeffs_queue.begin(), remove_loc);
  463. return updated;
  464. }
  465. /**
  466. * @brief generate map point cloud and publish it
  467. * @param event
  468. */
  469. void map_points_publish_timer_callback(const ros::WallTimerEvent& event) {
  470. if(!map_points_pub.getNumSubscribers() || !graph_updated) {
  471. return;
  472. }
  473. std::vector<KeyFrameSnapshot::Ptr> snapshot;
  474. keyframes_snapshot_mutex.lock();
  475. snapshot = keyframes_snapshot;
  476. keyframes_snapshot_mutex.unlock();
  477. auto cloud = map_cloud_generator->generate(snapshot, map_cloud_resolution);
  478. if(!cloud) {
  479. return;
  480. }
  481. cloud->header.frame_id = map_frame_id;
  482. cloud->header.stamp = snapshot.back()->cloud->header.stamp;
  483. sensor_msgs::PointCloud2Ptr cloud_msg(new sensor_msgs::PointCloud2());
  484. pcl::toROSMsg(*cloud, *cloud_msg);
  485. map_points_pub.publish(cloud_msg);
  486. }
  487. /**
  488. * @brief this methods adds all the data in the queues to the pose graph, and then optimizes the pose graph
  489. * @brief 此方法将队列中的所有数据添加到姿势图中,然后优化姿势图
  490. * @param event // 是ROS提供的定时器时间类,包含信息有:计时器出发的时间戳、上一次出发的时间戳、计时器的周期信息等
  491. */
  492. void optimization_timer_callback(const ros::WallTimerEvent& event) {
  493. std::lock_guard<std::mutex> lock(main_thread_mutex); // 创建了一个锁,用于保护对主线程的访问,确保线程安全
  494. // add keyframes and floor coeffs in the queues to the pose graph 将队列中的关键帧和楼层系数添加到姿势图中
  495. bool keyframe_updated = flush_keyframe_queue(); // 调用 flush_keyframe_queue 函数,将关键帧队列中的数据添加到位姿图中,并返回是否有关键帧被更新
  496. if(!keyframe_updated) { // 如果没有关键帧被更新,则执行大括号内的代码
  497. std_msgs::Header read_until;
  498. read_until.stamp = ros::Time::now() + ros::Duration(30, 0); // 时间戳为什么要加30秒?
  499. read_until.frame_id = points_topic;
  500. read_until_pub.publish(read_until);
  501. read_until.frame_id = "/filtered_points";
  502. read_until_pub.publish(read_until); // 不同的 frame_id 和 话题 发布两次, 是干嘛用的?
  503. }
  504. if(!keyframe_updated & !flush_floor_queue() & !flush_gps_queue() & !flush_imu_queue()) {
  505. // 检查地板、GPS、IMU等队列,分别调用相应的 flush 函数(例如 flush_floor_queue、flush_gps_queue、flush_imu_queue),如果这些数据没有更新,则函数直接返回,不进行后续操作。
  506. return;
  507. }
  508. // loop detection 闭环检测
  509. std::vector<Loop::Ptr> loops = loop_detector->detect(keyframes, new_keyframes, *graph_slam);
  510. // 使用 loop_detector->detect 检测关键帧之间的闭环。闭环检测用于检测机器人是否回到了之前的某个位置,这在位姿图优化中起到约束作用。 (这部分都是GPT解释)
  511. // keyframes: 包含所有历史关键帧的容器
  512. // new_keyframes: 当前生成的最新的关键帧
  513. // *graph_slam: 一个图优化的实例,用来存储闭环检测的结果,可能包括相对位资信息,图结构,以及优化过程中所需要的数据
  514. // 相对位资信息: new_keyframes 与 keyframes 中所有帧的相对位资
  515. // 图结构: 一种数学表达,用来描述机器人在环境中的位资及其与环境中特征(如地标和其他关键帧)的关系. 具体而言,包括下面几个基本要素:
  516. // 节点: 每个节点代表一个特定的位资或状态 例如slam中,一个节点可以表示机器人在某个点的位置信息,也可以表示环境中的特征点
  517. // 边: 表示节点之间的约束关系, 这些约束可以是基于传感器测量的数据(例如激光里程计)或者闭环检测结果. 边通常回代有权重,表示约束的可信度和不确定性
  518. // 优化目标: 通过最小化节点之间的约束误差,图结构可以通过图优化算法进行优化. 常见的方法包括最小二乘法, 梯度下降法等等. 优化的目标是使得地图和机器人轨迹尽可能一致, 提高整体的定位和建图精度
  519. // 闭环检测: 在闭环检测过程中, 图结构会被更新,以反映新的闭环约束.这意味着新的边被添加到图中, 链接当前节点和历史节点,改善整体地图的一致性
  520. // 数据关联: 通过匹配特征和关键帧, 确定节点之间的关联性,从而形成合理的地图和路径
  521. // 检测不到闭环的情况: 没有足够的关键帧、环境发生显著变化、特征匹配失败(发生错误或特征点数量不足)、定位精度不足、参数设置不当、移动机器人的运动太快、内存或计算资源不够
  522. // 如果检测到闭环,则为闭环关系添加一个新的边到位姿图中,计算相对位姿并生成信息矩阵,确保闭环边的优化权重。
  523. for(const auto& loop : loops) { // 遍历闭环检测结果
  524. Eigen::Isometry3d relpose(loop->relative_pose.cast<double>());
  525. Eigen::MatrixXd information_matrix = inf_calclator->calc_information_matrix(loop->key1->cloud, loop->key2->cloud, relpose);
  526. auto edge = graph_slam->add_se3_edge(loop->key1->node, loop->key2->node, relpose, information_matrix);
  527. graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("loop_closure_edge_robust_kernel", "NONE"), private_nh.param<double>("loop_closure_edge_robust_kernel_size", 1.0));
  528. }
  529. std::copy(new_keyframes.begin(), new_keyframes.end(), std::back_inserter(keyframes)); // 将新关键帧 new_keyframes 合并到已有的关键帧列表 keyframes 中
  530. new_keyframes.clear(); // 清空 new_keyframes
  531. // move the first node anchor position to the current estimate of the first node pose 将第一节点锚点位置移动到第一节点姿态的当前估计值
  532. // so the first node moves freely while trying to stay around the origin 因此,第一个节点在试图停留在原点附近的同时可以自由移动
  533. if(anchor_node && private_nh.param<bool>("fix_first_node_adaptive", true)) { // launch文件中,fix_first_node_adaptive 设置为 true
  534. Eigen::Isometry3d anchor_target = static_cast<g2o::VertexSE3*>(anchor_edge->vertices()[1])->estimate();
  535. anchor_node->setEstimate(anchor_target);
  536. // 如果启用了自适应固定第一帧的功能(参数 "fix_first_node_adaptive"),则将第一个关键帧的锚点位置更新为当前估计的位置,以允许它自由移动但仍然保持在原点附近。
  537. }
  538. // optimize the pose graph
  539. int num_iterations = private_nh.param<int>("g2o_solver_num_iterations", 1024); // launch文件中都是设置成512
  540. graph_slam->optimize(num_iterations); // 使用 g2o 优化器对位姿图进行优化,优化的迭代次数由参数 "g2o_solver_num_iterations" 控制
  541. // publish tf 发布位姿变换
  542. const auto& keyframe = keyframes.back(); // 获取最新的关键帧估计
  543. Eigen::Isometry3d trans = keyframe->node->estimate() * keyframe->odom.inverse();
  544. trans_odom2map_mutex.lock();
  545. trans_odom2map = trans.matrix().cast<float>();
  546. trans_odom2map_mutex.unlock();
  547. std::vector<KeyFrameSnapshot::Ptr> snapshot(keyframes.size());
  548. std::transform(keyframes.begin(), keyframes.end(), snapshot.begin(), [=](const KeyFrame::Ptr& k) { return std::make_shared<KeyFrameSnapshot>(k); });
  549. keyframes_snapshot_mutex.lock();
  550. keyframes_snapshot.swap(snapshot);
  551. keyframes_snapshot_mutex.unlock();
  552. graph_updated = true;
  553. if(odom2map_pub.getNumSubscribers()) {
  554. geometry_msgs::TransformStamped ts = matrix2transform(keyframe->stamp, trans.matrix().cast<float>(), map_frame_id, odom_frame_id);
  555. odom2map_pub.publish(ts); // 发布odom2map_pub话题中
  556. }
  557. if(markers_pub.getNumSubscribers()) {
  558. auto markers = create_marker_array(ros::Time::now());
  559. markers_pub.publish(markers);
  560. }
  561. }
  562. /**
  563. * @brief create visualization marker
  564. * @param stamp
  565. * @return
  566. */
  567. visualization_msgs::MarkerArray create_marker_array(const ros::Time& stamp) const {
  568. visualization_msgs::MarkerArray markers;
  569. markers.markers.resize(4);
  570. // node markers
  571. visualization_msgs::Marker& traj_marker = markers.markers[0];
  572. traj_marker.header.frame_id = "map";
  573. traj_marker.header.stamp = stamp;
  574. traj_marker.ns = "nodes";
  575. traj_marker.id = 0;
  576. traj_marker.type = visualization_msgs::Marker::SPHERE_LIST;
  577. traj_marker.pose.orientation.w = 1.0;
  578. traj_marker.scale.x = traj_marker.scale.y = traj_marker.scale.z = 0.5;
  579. visualization_msgs::Marker& imu_marker = markers.markers[1];
  580. imu_marker.header = traj_marker.header;
  581. imu_marker.ns = "imu";
  582. imu_marker.id = 1;
  583. imu_marker.type = visualization_msgs::Marker::SPHERE_LIST;
  584. imu_marker.pose.orientation.w = 1.0;
  585. imu_marker.scale.x = imu_marker.scale.y = imu_marker.scale.z = 0.75;
  586. traj_marker.points.resize(keyframes.size());
  587. traj_marker.colors.resize(keyframes.size());
  588. for(int i = 0; i < keyframes.size(); i++) {
  589. Eigen::Vector3d pos = keyframes[i]->node->estimate().translation();
  590. traj_marker.points[i].x = pos.x();
  591. traj_marker.points[i].y = pos.y();
  592. traj_marker.points[i].z = pos.z();
  593. double p = static_cast<double>(i) / keyframes.size();
  594. traj_marker.colors[i].r = 1.0 - p;
  595. traj_marker.colors[i].g = p;
  596. traj_marker.colors[i].b = 0.0;
  597. traj_marker.colors[i].a = 1.0;
  598. if(keyframes[i]->acceleration) {
  599. Eigen::Vector3d pos = keyframes[i]->node->estimate().translation();
  600. geometry_msgs::Point point;
  601. point.x = pos.x();
  602. point.y = pos.y();
  603. point.z = pos.z();
  604. std_msgs::ColorRGBA color;
  605. color.r = 0.0;
  606. color.g = 0.0;
  607. color.b = 1.0;
  608. color.a = 0.1;
  609. imu_marker.points.push_back(point);
  610. imu_marker.colors.push_back(color);
  611. }
  612. }
  613. // edge markers
  614. visualization_msgs::Marker& edge_marker = markers.markers[2];
  615. edge_marker.header.frame_id = "map";
  616. edge_marker.header.stamp = stamp;
  617. edge_marker.ns = "edges";
  618. edge_marker.id = 2;
  619. edge_marker.type = visualization_msgs::Marker::LINE_LIST;
  620. edge_marker.pose.orientation.w = 1.0;
  621. edge_marker.scale.x = 0.05;
  622. edge_marker.points.resize(graph_slam->graph->edges().size() * 2);
  623. edge_marker.colors.resize(graph_slam->graph->edges().size() * 2);
  624. auto edge_itr = graph_slam->graph->edges().begin();
  625. for(int i = 0; edge_itr != graph_slam->graph->edges().end(); edge_itr++, i++) {
  626. g2o::HyperGraph::Edge* edge = *edge_itr;
  627. g2o::EdgeSE3* edge_se3 = dynamic_cast<g2o::EdgeSE3*>(edge);
  628. if(edge_se3) {
  629. g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_se3->vertices()[0]);
  630. g2o::VertexSE3* v2 = dynamic_cast<g2o::VertexSE3*>(edge_se3->vertices()[1]);
  631. Eigen::Vector3d pt1 = v1->estimate().translation();
  632. Eigen::Vector3d pt2 = v2->estimate().translation();
  633. edge_marker.points[i * 2].x = pt1.x();
  634. edge_marker.points[i * 2].y = pt1.y();
  635. edge_marker.points[i * 2].z = pt1.z();
  636. edge_marker.points[i * 2 + 1].x = pt2.x();
  637. edge_marker.points[i * 2 + 1].y = pt2.y();
  638. edge_marker.points[i * 2 + 1].z = pt2.z();
  639. double p1 = static_cast<double>(v1->id()) / graph_slam->graph->vertices().size();
  640. double p2 = static_cast<double>(v2->id()) / graph_slam->graph->vertices().size();
  641. edge_marker.colors[i * 2].r = 1.0 - p1;
  642. edge_marker.colors[i * 2].g = p1;
  643. edge_marker.colors[i * 2].a = 1.0;
  644. edge_marker.colors[i * 2 + 1].r = 1.0 - p2;
  645. edge_marker.colors[i * 2 + 1].g = p2;
  646. edge_marker.colors[i * 2 + 1].a = 1.0;
  647. if(std::abs(v1->id() - v2->id()) > 2) {
  648. edge_marker.points[i * 2].z += 0.5;
  649. edge_marker.points[i * 2 + 1].z += 0.5;
  650. }
  651. continue;
  652. }
  653. g2o::EdgeSE3Plane* edge_plane = dynamic_cast<g2o::EdgeSE3Plane*>(edge);
  654. if(edge_plane) {
  655. g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_plane->vertices()[0]);
  656. Eigen::Vector3d pt1 = v1->estimate().translation();
  657. Eigen::Vector3d pt2(pt1.x(), pt1.y(), 0.0);
  658. edge_marker.points[i * 2].x = pt1.x();
  659. edge_marker.points[i * 2].y = pt1.y();
  660. edge_marker.points[i * 2].z = pt1.z();
  661. edge_marker.points[i * 2 + 1].x = pt2.x();
  662. edge_marker.points[i * 2 + 1].y = pt2.y();
  663. edge_marker.points[i * 2 + 1].z = pt2.z();
  664. edge_marker.colors[i * 2].b = 1.0;
  665. edge_marker.colors[i * 2].a = 1.0;
  666. edge_marker.colors[i * 2 + 1].b = 1.0;
  667. edge_marker.colors[i * 2 + 1].a = 1.0;
  668. continue;
  669. }
  670. g2o::EdgeSE3PriorXY* edge_priori_xy = dynamic_cast<g2o::EdgeSE3PriorXY*>(edge);
  671. if(edge_priori_xy) {
  672. g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_priori_xy->vertices()[0]);
  673. Eigen::Vector3d pt1 = v1->estimate().translation();
  674. Eigen::Vector3d pt2 = Eigen::Vector3d::Zero();
  675. pt2.head<2>() = edge_priori_xy->measurement();
  676. edge_marker.points[i * 2].x = pt1.x();
  677. edge_marker.points[i * 2].y = pt1.y();
  678. edge_marker.points[i * 2].z = pt1.z() + 0.5;
  679. edge_marker.points[i * 2 + 1].x = pt2.x();
  680. edge_marker.points[i * 2 + 1].y = pt2.y();
  681. edge_marker.points[i * 2 + 1].z = pt2.z() + 0.5;
  682. edge_marker.colors[i * 2].r = 1.0;
  683. edge_marker.colors[i * 2].a = 1.0;
  684. edge_marker.colors[i * 2 + 1].r = 1.0;
  685. edge_marker.colors[i * 2 + 1].a = 1.0;
  686. continue;
  687. }
  688. g2o::EdgeSE3PriorXYZ* edge_priori_xyz = dynamic_cast<g2o::EdgeSE3PriorXYZ*>(edge);
  689. if(edge_priori_xyz) {
  690. g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_priori_xyz->vertices()[0]);
  691. Eigen::Vector3d pt1 = v1->estimate().translation();
  692. Eigen::Vector3d pt2 = edge_priori_xyz->measurement();
  693. edge_marker.points[i * 2].x = pt1.x();
  694. edge_marker.points[i * 2].y = pt1.y();
  695. edge_marker.points[i * 2].z = pt1.z() + 0.5;
  696. edge_marker.points[i * 2 + 1].x = pt2.x();
  697. edge_marker.points[i * 2 + 1].y = pt2.y();
  698. edge_marker.points[i * 2 + 1].z = pt2.z();
  699. edge_marker.colors[i * 2].r = 1.0;
  700. edge_marker.colors[i * 2].a = 1.0;
  701. edge_marker.colors[i * 2 + 1].r = 1.0;
  702. edge_marker.colors[i * 2 + 1].a = 1.0;
  703. continue;
  704. }
  705. }
  706. // sphere
  707. visualization_msgs::Marker& sphere_marker = markers.markers[3];
  708. sphere_marker.header.frame_id = "map";
  709. sphere_marker.header.stamp = stamp;
  710. sphere_marker.ns = "loop_close_radius";
  711. sphere_marker.id = 3;
  712. sphere_marker.type = visualization_msgs::Marker::SPHERE;
  713. if(!keyframes.empty()) {
  714. Eigen::Vector3d pos = keyframes.back()->node->estimate().translation();
  715. sphere_marker.pose.position.x = pos.x();
  716. sphere_marker.pose.position.y = pos.y();
  717. sphere_marker.pose.position.z = pos.z();
  718. }
  719. sphere_marker.pose.orientation.w = 1.0;
  720. sphere_marker.scale.x = sphere_marker.scale.y = sphere_marker.scale.z = loop_detector->get_distance_thresh() * 2.0;
  721. sphere_marker.color.r = 1.0;
  722. sphere_marker.color.a = 0.3;
  723. return markers;
  724. }
  725. /**
  726. * @brief load all data from a directory
  727. * @param req
  728. * @param res
  729. * @return
  730. */
  731. bool load_service(hdl_graph_slam::LoadGraphRequest& req, hdl_graph_slam::LoadGraphResponse& res) {
  732. std::lock_guard<std::mutex> lock(main_thread_mutex);
  733. std::string directory = req.path;
  734. std::cout << "loading data from:" << directory << std::endl;
  735. // Load graph.
  736. graph_slam->load(directory + "/graph.g2o");
  737. // Iterate over the items in this directory and count how many sub directories there are.
  738. // This will give an upper limit on how many keyframe indexes we can expect to find.
  739. boost::filesystem::directory_iterator begin(directory), end;
  740. int max_directory_count = std::count_if(begin, end, [](const boost::filesystem::directory_entry& d) {
  741. return boost::filesystem::is_directory(d.path()); // only return true if a direcotry
  742. });
  743. // Load keyframes by looping through key frame indexes that we expect to see.
  744. for(int i = 0; i < max_directory_count; i++) {
  745. std::stringstream sst;
  746. sst << boost::format("%s/%06d") % directory % i;
  747. std::string key_frame_directory = sst.str();
  748. // If key_frame_directory doesnt exist, then we have run out so lets stop looking.
  749. if(!boost::filesystem::is_directory(key_frame_directory)) {
  750. break;
  751. }
  752. KeyFrame::Ptr keyframe(new KeyFrame(key_frame_directory, graph_slam->graph.get()));
  753. keyframes.push_back(keyframe);
  754. }
  755. std::cout << "loaded " << keyframes.size() << " keyframes" << std::endl;
  756. // Load special nodes.
  757. std::ifstream ifs(directory + "/special_nodes.csv");
  758. if(!ifs) {
  759. return false;
  760. }
  761. while(!ifs.eof()) {
  762. std::string token;
  763. ifs >> token;
  764. if(token == "anchor_node") {
  765. int id = 0;
  766. ifs >> id;
  767. anchor_node = static_cast<g2o::VertexSE3*>(graph_slam->graph->vertex(id));
  768. } else if(token == "anchor_edge") {
  769. int id = 0;
  770. ifs >> id;
  771. // We have no way of directly pulling the edge based on the edge ID that we have just read in.
  772. // Fortunatly anchor edges are always attached to the anchor node so we can iterate over
  773. // the edges that listed against the node untill we find the one that matches our ID.
  774. if(anchor_node) {
  775. auto edges = anchor_node->edges();
  776. for(auto e : edges) {
  777. int edgeID = e->id();
  778. if(edgeID == id) {
  779. anchor_edge = static_cast<g2o::EdgeSE3*>(e);
  780. break;
  781. }
  782. }
  783. }
  784. } else if(token == "floor_node") {
  785. int id = 0;
  786. ifs >> id;
  787. floor_plane_node = static_cast<g2o::VertexPlane*>(graph_slam->graph->vertex(id));
  788. }
  789. }
  790. // check if we have any non null special nodes, if all are null then lets not bother.
  791. if(anchor_node->id() || anchor_edge->id() || floor_plane_node->id()) {
  792. std::cout << "loaded special nodes - ";
  793. // check exists before printing information about each special node
  794. if(anchor_node->id()) {
  795. std::cout << " anchor_node: " << anchor_node->id();
  796. }
  797. if(anchor_edge->id()) {
  798. std::cout << " anchor_edge: " << anchor_edge->id();
  799. }
  800. if(floor_plane_node->id()) {
  801. std::cout << " floor_node: " << floor_plane_node->id();
  802. }
  803. // finish with a new line
  804. std::cout << std::endl;
  805. }
  806. // Update our keyframe snapshot so we can publish a map update, trigger update with graph_updated = true.
  807. std::vector<KeyFrameSnapshot::Ptr> snapshot(keyframes.size());
  808. std::transform(keyframes.begin(), keyframes.end(), snapshot.begin(), [=](const KeyFrame::Ptr& k) { return std::make_shared<KeyFrameSnapshot>(k); });
  809. keyframes_snapshot_mutex.lock();
  810. keyframes_snapshot.swap(snapshot);
  811. keyframes_snapshot_mutex.unlock();
  812. graph_updated = true;
  813. res.success = true;
  814. std::cout << "snapshot updated" << std::endl << "loading successful" << std::endl;
  815. return true;
  816. }
  817. /**
  818. * @brief dump all data to the current directory
  819. * @param req
  820. * @param res
  821. * @return
  822. */
  823. bool dump_service(hdl_graph_slam::DumpGraphRequest& req, hdl_graph_slam::DumpGraphResponse& res) {
  824. std::lock_guard<std::mutex> lock(main_thread_mutex);
  825. std::string directory = req.destination;
  826. if(directory.empty()) {
  827. std::array<char, 64> buffer;
  828. buffer.fill(0);
  829. time_t rawtime;
  830. time(&rawtime);
  831. const auto timeinfo = localtime(&rawtime);
  832. strftime(buffer.data(), sizeof(buffer), "%d-%m-%Y %H:%M:%S", timeinfo);
  833. }
  834. if(!boost::filesystem::is_directory(directory)) {
  835. boost::filesystem::create_directory(directory);
  836. }
  837. std::cout << "dumping data to:" << directory << std::endl;
  838. // save graph
  839. graph_slam->save(directory + "/graph.g2o");
  840. // save keyframes
  841. for(int i = 0; i < keyframes.size(); i++) {
  842. std::stringstream sst;
  843. sst << boost::format("%s/%06d") % directory % i;
  844. keyframes[i]->save(sst.str());
  845. }
  846. if(zero_utm) {
  847. std::ofstream zero_utm_ofs(directory + "/zero_utm");
  848. zero_utm_ofs << boost::format("%.6f %.6f %.6f") % zero_utm->x() % zero_utm->y() % zero_utm->z() << std::endl;
  849. }
  850. std::ofstream ofs(directory + "/special_nodes.csv");
  851. ofs << "anchor_node " << (anchor_node == nullptr ? -1 : anchor_node->id()) << std::endl;
  852. ofs << "anchor_edge " << (anchor_edge == nullptr ? -1 : anchor_edge->id()) << std::endl;
  853. ofs << "floor_node " << (floor_plane_node == nullptr ? -1 : floor_plane_node->id()) << std::endl;
  854. res.success = true;
  855. return true;
  856. }
  857. /**
  858. * @brief save map data as pcd
  859. * @param req
  860. * @param res
  861. * @return
  862. */
  863. bool save_map_service(hdl_graph_slam::SaveMapRequest& req, hdl_graph_slam::SaveMapResponse& res) {
  864. std::vector<KeyFrameSnapshot::Ptr> snapshot;
  865. keyframes_snapshot_mutex.lock();
  866. snapshot = keyframes_snapshot;
  867. keyframes_snapshot_mutex.unlock();
  868. auto cloud = map_cloud_generator->generate(snapshot, req.resolution);
  869. if(!cloud) {
  870. res.success = false;
  871. return true;
  872. }
  873. if(zero_utm && req.utm) {
  874. for(auto& pt : cloud->points) {
  875. pt.getVector3fMap() += (*zero_utm).cast<float>();
  876. }
  877. }
  878. cloud->header.frame_id = map_frame_id;
  879. cloud->header.stamp = snapshot.back()->cloud->header.stamp;
  880. if(zero_utm) {
  881. std::ofstream ofs(req.destination + ".utm");
  882. ofs << boost::format("%.6f %.6f %.6f") % zero_utm->x() % zero_utm->y() % zero_utm->z() << std::endl;
  883. }
  884. int ret = pcl::io::savePCDFileBinary(req.destination, *cloud);
  885. res.success = ret == 0;
  886. return true;
  887. }
  888. private: // 一些参数的定义
  889. // ROS
  890. ros::NodeHandle nh; // 节点句柄
  891. ros::NodeHandle mt_nh; //
  892. ros::NodeHandle private_nh; // 私有节点句柄 申请多几个节点句柄主要是为了:命名空间隔离、参数隔离、代码组织、责任分离、调试和测试、灵活性和扩展性、并行处理(kimi解释)
  893. ros::WallTimer optimization_timer;
  894. ros::WallTimer map_publish_timer;
  895. std::unique_ptr<message_filters::Subscriber<nav_msgs::Odometry>> odom_sub;
  896. std::unique_ptr<message_filters::Subscriber<sensor_msgs::PointCloud2>> cloud_sub;
  897. std::unique_ptr<message_filters::Synchronizer<ApproxSyncPolicy>> sync;
  898. ros::Subscriber gps_sub;
  899. ros::Subscriber nmea_sub;
  900. ros::Subscriber navsat_sub;
  901. ros::Subscriber imu_sub;
  902. ros::Subscriber floor_sub;
  903. ros::Publisher markers_pub;
  904. std::string published_odom_topic;
  905. std::string map_frame_id;
  906. std::string odom_frame_id;
  907. std::mutex trans_odom2map_mutex; // 一个互斥量,用来确保在多线程环境中对 trans_odom2map 变量的访问是线程安全的。
  908. Eigen::Matrix4f trans_odom2map; // 表示从 里程计坐标系(odom frame)到地图坐标系(map frame)的变换矩阵 这个变换矩阵是跟机械臂变换矩阵类似的 齐次变换矩阵
  909. ros::Publisher odom2map_pub; // 发布里程计到地图的变换信息
  910. std::string points_topic; // 点云数据的ROS话题名称,SLAM系统将订阅这个话题来获取点云数据
  911. ros::Publisher read_until_pub;
  912. ros::Publisher map_points_pub;
  913. tf::TransformListener tf_listener; // ROS的一个类,用来监听和查询不同坐标系之间的变换关系
  914. ros::ServiceServer load_service_server; // 一个 ROS 服务服务器,用于加载系统数据或状态
  915. ros::ServiceServer dump_service_server; // 一个 ROS 服务服务器,用于转储(dump)系统当前的状态或数据
  916. ros::ServiceServer save_map_service_server; // 一个 ROS 服务服务器,用于保存地图
  917. // keyframe queue
  918. std::string base_frame_id;
  919. std::mutex keyframe_queue_mutex; // std::mutex 是一种独占式互斥量
  920. std::deque<KeyFrame::Ptr> keyframe_queue; // 关键帧队列
  921. // gps queue
  922. double gps_time_offset;
  923. double gps_edge_stddev_xy;
  924. double gps_edge_stddev_z;
  925. boost::optional<Eigen::Vector3d> zero_utm;
  926. std::mutex gps_queue_mutex;
  927. std::deque<geographic_msgs::GeoPointStampedConstPtr> gps_queue;
  928. // imu queue
  929. double imu_time_offset; // 用于对IMU数据时间戳进行校正或偏移
  930. bool enable_imu_orientation; // 控制是否启用IMU提供姿态信息
  931. double imu_orientation_edge_stddev; // 用于指定IMU姿态数据的不确定性(标准差)
  932. bool enable_imu_acceleration; // 控制是否启用IMU提供的加速信息
  933. double imu_acceleration_edge_stddev; // 指定IMU加速度信息的不确定性(标准差)
  934. std::mutex imu_queue_mutex; // 互斥量
  935. std::deque<sensor_msgs::ImuConstPtr> imu_queue; // IMU队列
  936. // floor_coeffs queue
  937. double floor_edge_stddev;
  938. std::mutex floor_coeffs_queue_mutex;
  939. std::deque<hdl_graph_slam::FloorCoeffsConstPtr> floor_coeffs_queue;
  940. // for map cloud generation
  941. std::atomic_bool graph_updated; // 用于标识 位资图(pose graph)是否更新,确保多线程环境下的线程安全
  942. double map_cloud_resolution; // 控制生成的地图点云的分辨率
  943. std::mutex keyframes_snapshot_mutex; // 互斥量
  944. std::vector<KeyFrameSnapshot::Ptr> keyframes_snapshot; // 用来存储关键帧的快照。这个变量很重要,发布 map_point 和 保存 pcd 地图都是用这个变量!!
  945. std::unique_ptr<MapCloudGenerator> map_cloud_generator; // 生成点云地图的对象指针
  946. // graph slam
  947. // all the below members must be accessed after locking main_thread_mutex
  948. std::mutex main_thread_mutex; // 互斥量
  949. int max_keyframes_per_update; // 限制每次更新中可以处理的最大关键帧数量
  950. std::deque<KeyFrame::Ptr> new_keyframes; // 存储新生成的关键帧指针
  951. g2o::VertexSE3* anchor_node; // 一个指向 g2o::VertexSE3 类型的指针,表示位姿图中的一个特定节点(锚点节点)。锚点节点通常是用来约束图的某个部分,使得图优化时可以保持稳定。
  952. // 锚点的引入可以帮助优化算法更好地收敛到一个合理的解,特别是在 SLAM 系统中,锚点可以用于固定某个已知的位置(如起始位置或特征点)。
  953. g2o::EdgeSE3* anchor_edge; // 一个指向 g2o::EdgeSE3 类型的指针,表示连接锚点节点和其他节点的边。这条边用于描述锚点与其他位姿节点之间的相对约束关系。
  954. // 在图优化中,这种约束有助于保持图的稳定性,并确保锚点的影响在优化过程中得以体现。
  955. g2o::VertexPlane* floor_plane_node; // 用于表示地面平面节点的指针。
  956. std::vector<KeyFrame::Ptr> keyframes; // 存储当前系统中的所有关键帧。
  957. std::unordered_map<ros::Time, KeyFrame::Ptr, RosTimeHash> keyframe_hash; // 用于快速查找关键帧的哈希表
  958. // keyframe_hash 是一个无序映射,使用 ros::Time 作为键,以关键帧指针为值。此哈希表用于存储每个关键帧的时间戳与其对应的指针,便于快速查找特定时间的关键帧。
  959. // 这种数据结构可以加速对关键帧的查找过程,提高 SLAM 系统在处理数据时的效率,尤其是在需要频繁检索关键帧时。
  960. // std::unique_ptr:一种独占所有权的智能指针,意味着同一时间内只能有一个std::unique_ptr指向某个对象
  961. // 智能指针是一种自动管理动态分配内存的类,它们在对象不再使用时自动释放内存,从而帮助防止内存泄漏
  962. std::unique_ptr<GraphSLAM> graph_slam; // 声明一个指向GraphSLAM 类型的智能指针 graph_slam
  963. std::unique_ptr<LoopDetector> loop_detector;
  964. std::unique_ptr<KeyframeUpdater> keyframe_updater;
  965. std::unique_ptr<NmeaSentenceParser> nmea_parser;
  966. std::unique_ptr<InformationMatrixCalculator> inf_calclator;
  967. };
  968. } // namespace hdl_graph_slam
  969. PLUGINLIB_EXPORT_CLASS(hdl_graph_slam::HdlGraphSlamNodelet, nodelet::Nodelet)