hdl_graph_slam_nodelet.cpp 48 KB

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