hdl_backend.hpp 8.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214
  1. #include <ros/ros.h>
  2. #include <string>
  3. #include <Eigen/Dense>
  4. #include <memory>
  5. #include <message_filters/subscriber.h>
  6. #include <nav_msgs/Odometry.h>
  7. #include <sensor_msgs/PointCloud2.h>
  8. #include <message_filters/sync_policies/approximate_time.h>
  9. #include <message_filters/synchronizer.h>
  10. // #include "hdl_graph_slam/keyframe_updater.hpp"
  11. #include <hdl_graph_slam/keyframe_updater.hpp>
  12. #include <hdl_graph_slam/keyframe.hpp>
  13. #include <hdl_graph_slam/SaveMap.h>
  14. #include <hdl_graph_slam/map_cloud_generator.hpp>
  15. #include <boost/format.hpp>
  16. #include <hdl_graph_slam/graph_slam.hpp>
  17. #include <hdl_graph_slam/ros_time_hash.hpp>
  18. #include <g2o/types/slam3d/vertex_se3.h>
  19. #include <hdl_graph_slam/information_matrix_calculator.hpp>
  20. // 直接把头文件都复制过来
  21. #include <ctime>
  22. #include <mutex>
  23. #include <atomic>
  24. #include <memory>
  25. #include <iomanip>
  26. #include <iostream>
  27. #include <unordered_map>
  28. #include <boost/format.hpp>
  29. #include <boost/thread.hpp>
  30. #include <boost/filesystem.hpp>
  31. #include <boost/algorithm/string.hpp>
  32. #include <Eigen/Dense>
  33. #include <pcl/io/pcd_io.h>
  34. #include <ros/ros.h>
  35. #include <geodesy/utm.h>
  36. #include <geodesy/wgs84.h>
  37. #include <pcl_ros/point_cloud.h>
  38. #include <message_filters/subscriber.h>
  39. #include <message_filters/time_synchronizer.h>
  40. #include <message_filters/sync_policies/approximate_time.h>
  41. #include <tf_conversions/tf_eigen.h>
  42. #include <tf/transform_listener.h>
  43. #include <std_msgs/Time.h>
  44. #include <nav_msgs/Odometry.h>
  45. #include <nmea_msgs/Sentence.h>
  46. #include <sensor_msgs/Imu.h>
  47. #include <sensor_msgs/NavSatFix.h>
  48. #include <sensor_msgs/PointCloud2.h>
  49. #include <geographic_msgs/GeoPointStamped.h>
  50. #include <visualization_msgs/MarkerArray.h>
  51. #include <hdl_graph_slam/FloorCoeffs.h>
  52. #include <hdl_graph_slam/SaveMap.h>
  53. #include <hdl_graph_slam/LoadGraph.h>
  54. #include <hdl_graph_slam/DumpGraph.h>
  55. #include <nodelet/nodelet.h>
  56. #include <pluginlib/class_list_macros.h>
  57. #include <hdl_graph_slam/ros_utils.hpp>
  58. #include <hdl_graph_slam/ros_time_hash.hpp>
  59. #include <hdl_graph_slam/graph_slam.hpp>
  60. #include <hdl_graph_slam/keyframe.hpp>
  61. #include <hdl_graph_slam/keyframe_updater.hpp>
  62. #include <hdl_graph_slam/loop_detector.hpp>
  63. #include <hdl_graph_slam/information_matrix_calculator.hpp>
  64. #include <hdl_graph_slam/map_cloud_generator.hpp>
  65. #include <hdl_graph_slam/nmea_sentence_parser.hpp>
  66. #include <g2o/types/slam3d/edge_se3.h>
  67. #include <g2o/types/slam3d/vertex_se3.h>
  68. #include <g2o/edge_se3_plane.hpp>
  69. #include <g2o/edge_se3_priorxy.hpp>
  70. #include <g2o/edge_se3_priorxyz.hpp>
  71. #include <g2o/edge_se3_priorvec.hpp>
  72. #include <g2o/edge_se3_priorquat.hpp>
  73. #include <thread> // 多线程
  74. #include <pcl/filters/voxel_grid.h>
  75. #include <pcl/filters/passthrough.h>
  76. #include <pcl/filters/approximate_voxel_grid.h>
  77. #include <pcl/filters/radius_outlier_removal.h>
  78. #include <pcl/filters/statistical_outlier_removal.h>
  79. typedef message_filters::sync_policies::ApproximateTime<nav_msgs::Odometry, sensor_msgs::PointCloud2> ApproxSyncPolicy;
  80. typedef pcl::PointXYZI PointT;
  81. class hdl_backend {
  82. private:
  83. ros::NodeHandle nh; // ros 的节点句柄
  84. // std::string published_odom_topic;
  85. int max_keyframes_per_update; // 限制每次更新中可以处理的最大关键帧数量
  86. std::unique_ptr<message_filters::Subscriber<nav_msgs::Odometry>> odom_sub;
  87. std::unique_ptr<message_filters::Subscriber<sensor_msgs::PointCloud2>> cloud_sub;
  88. std::unique_ptr<message_filters::Synchronizer<ApproxSyncPolicy>> sync;
  89. void cloud_callback(const nav_msgs::OdometryConstPtr& odom_msg, const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
  90. void map_points_publish_timer_callback(const ros::WallTimerEvent& event) ;
  91. static hdl_backend instance; // 静态实例, 保证唯一
  92. // 静态成员变量与类的所有实例共享,而不仅仅属于某个对象实例。因为它是私有的,所以外部不能直接访问或修改这个变量
  93. // 该声明并不会分配内存空间。静态变量的定义和初始化必须在类的外部进行,因为类的声明不会为静态成员分配内存,只有类外定义才会分配空间。 仅是声明,没有分配内存
  94. // 静态成员变量的生命周期与类的生命周期一致,而不是与对象的生命周期一致
  95. // C++ 语言允许在类外部对静态成员变量进行定义和初始化,这是因为静态成员变量的存储空间在全局内存中分配,而不是在对象实例中。
  96. ros::ServiceServer save_map_service_server; // 一个 ROS 服务服务器,用于保存地图
  97. bool save_map_service(hdl_graph_slam::SaveMapRequest& req, hdl_graph_slam::SaveMapResponse& res);
  98. boost::optional<Eigen::Vector3d> zero_utm;
  99. ros::WallTimer optimization_timer;
  100. ros::WallTimer map_publish_timer;
  101. // int max_keyframes_per_update; // 限制每次更新中可以处理的最大关键帧数量
  102. // g2o::VertexPlane* floor_plane_node; // 用于表示地面平面节点的指针。
  103. // std::vector<hdl_graph_slam::KeyFrame::Ptr> keyframes; // 存储当前系统中的所有关键帧。
  104. std::unordered_map<ros::Time, hdl_graph_slam::KeyFrame::Ptr, RosTimeHash> keyframe_hash; // 用于快速查找关键帧的哈希表
  105. public:
  106. hdl_backend(){}; // 构造函数
  107. ~hdl_backend(){}; // 析构函数
  108. void init(); // 初始化函数
  109. std::string base_frame_id;
  110. std::unique_ptr<hdl_graph_slam::KeyframeUpdater> keyframe_updater;
  111. std::mutex keyframe_queue_mutex; // std::mutex 是一种独占式互斥量
  112. std::deque<hdl_graph_slam::KeyFrame::Ptr> keyframe_queue; // 关键帧队列
  113. // static hdl_backend& getInstance() {
  114. // return instance;
  115. // }
  116. std::string points_topic; // 点云数据的ROS话题名称,SLAM系统将订阅这个话题来获取点云数据 这个不要?
  117. ros::Publisher read_until_pub;
  118. std::mutex main_thread_mutex; // 互斥量
  119. bool flush_keyframe_queue();
  120. std::unique_ptr<hdl_graph_slam::LoopDetector> loop_detector;
  121. std::vector<hdl_graph_slam::KeyFrame::Ptr> keyframes; // 存储当前系统中的所有关键帧。
  122. std::deque<hdl_graph_slam::KeyFrame::Ptr> new_keyframes; // 存储新生成的关键帧指针
  123. std::unique_ptr<hdl_graph_slam::GraphSLAM> graph_slam; // 声明一个指向GraphSLAM 类型的智能指针 graph_slam
  124. g2o::VertexSE3* anchor_node; // 一个指向 g2o::VertexSE3 类型的指针,表示位姿图中的一个特定节点(锚点节点)。锚点节点通常是用来约束图的某个部分,使得图优化时可以保持稳定。
  125. g2o::EdgeSE3* anchor_edge; // 一个指向 g2o::EdgeSE3 类型的指针,表示连接锚点节点和其他节点的边。这条边用于描述锚点与其他位姿节点之间的相对约束关系。
  126. std::unique_ptr<hdl_graph_slam::InformationMatrixCalculator> inf_calclator;
  127. std::mutex trans_odom2map_mutex;
  128. Eigen::Matrix4f trans_odom2map; // 表示从 里程计坐标系(odom frame)到地图坐标系(map frame)的变换矩阵 这个变换矩阵是跟机械臂变换矩阵类似的 齐次变换矩阵
  129. std::mutex keyframes_snapshot_mutex; // 互斥量
  130. std::vector<hdl_graph_slam::KeyFrameSnapshot::Ptr> keyframes_snapshot; // 用来存储关键帧的快照。这个变量很重要,发布 map_point 和 保存 pcd 地图都是用这个变量!!
  131. std::atomic_bool graph_updated; // 用于标识 位资图(pose graph)是否更新,确保多线程环境下的线程安全
  132. ros::Publisher odom2map_pub;
  133. ros::Publisher markers_pub;
  134. visualization_msgs::MarkerArray create_marker_array(const ros::Time& stamp) const;
  135. std::string map_frame_id;
  136. std::string odom_frame_id;
  137. ros::Publisher map_points_pub; // 话题通常包含了所有之前扫描过的点云,随着机器人在环境中移动,新的点云数据会被不断添加到这个地图中,从而提供一个逐步完善的环境表示
  138. ros::Publisher map_points_pub2; // 话题通常包含了所有之前扫描过的点云,随着机器人在环境中移动,新的点云数据会被不断添加到这个地图中,从而提供一个逐步完善的环境表示
  139. double map_cloud_resolution;
  140. std::unique_ptr<hdl_graph_slam::MapCloudGenerator> map_cloud_generator; // 生成点云地图的对象指针
  141. // int loop_count = 0;
  142. // void optimization_timer_callback(const ros::WallTimerEvent& event);
  143. void optimization_timer_callback();
  144. long long num_added_keyframe = 0;
  145. pcl::PointCloud<PointT>::ConstPtr downsample(const pcl::PointCloud<PointT>::ConstPtr& cloud);
  146. pcl::Filter<PointT>::Ptr downsample_filter;
  147. double downsample_resolution = 0.1;
  148. pcl::PointCloud<PointT>::ConstPtr outlier_removal(const pcl::PointCloud<PointT>::ConstPtr& cloud);
  149. // pcl::PointCloud<PointT>::ConstPtr hdl_backend::outlier_removal(const pcl::PointCloud<PointT>::ConstPtr& cloud) const {
  150. pcl::Filter<PointT>::Ptr outlier_removal_filter;
  151. };