hdl_backend.hpp 1.8 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243
  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. typedef message_filters::sync_policies::ApproximateTime<nav_msgs::Odometry, sensor_msgs::PointCloud2> ApproxSyncPolicy;
  11. typedef pcl::PointXYZI PointT;
  12. class hdl_backend {
  13. private:
  14. ros::NodeHandle nh; // ros 的节点句柄
  15. ros::Publisher map_points_pub; // 话题通常包含了所有之前扫描过的点云,随着机器人在环境中移动,新的点云数据会被不断添加到这个地图中,从而提供一个逐步完善的环境表示
  16. // std::string published_odom_topic;
  17. std::string map_frame_id;
  18. // std::string odom_frame_id;
  19. std::string map_cloud_resolution; // 地图分辨率
  20. Eigen::Matrix4f trans_odom2map; // 表示从 里程计坐标系(odom frame)到地图坐标系(map frame)的变换矩阵 这个变换矩阵是跟机械臂变换矩阵类似的 齐次变换矩阵
  21. int max_keyframes_per_update; // 限制每次更新中可以处理的最大关键帧数量
  22. std::string points_topic; // 点云数据的ROS话题名称,SLAM系统将订阅这个话题来获取点云数据
  23. std::unique_ptr<message_filters::Subscriber<nav_msgs::Odometry>> odom_sub;
  24. std::unique_ptr<message_filters::Subscriber<sensor_msgs::PointCloud2>> cloud_sub;
  25. std::unique_ptr<message_filters::Synchronizer<ApproxSyncPolicy>> sync;
  26. void cloud_callback(const nav_msgs::OdometryConstPtr& odom_msg, const sensor_msgs::PointCloud2::ConstPtr& cloud_msg){};
  27. public:
  28. hdl_backend(){}; // 构造函数
  29. ~hdl_backend(){}; // 析构函数
  30. void init(); // 初始化函数
  31. std::string base_frame_id;
  32. };