laser_odom copy.hpp 3.0 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889
  1. #include <memory>
  2. #include <iostream>
  3. #include <ros/ros.h>
  4. #include <ros/time.h>
  5. #include <ros/duration.h>
  6. #include <pcl_ros/point_cloud.h>
  7. #include <tf_conversions/tf_eigen.h>
  8. #include <tf/transform_listener.h>
  9. #include <tf/transform_broadcaster.h>
  10. #include <std_msgs/Time.h>
  11. #include <nav_msgs/Odometry.h>
  12. #include <sensor_msgs/PointCloud2.h>
  13. #include <geometry_msgs/TransformStamped.h>
  14. #include <geometry_msgs/PoseWithCovarianceStamped.h>
  15. #include <nodelet/nodelet.h>
  16. #include <pluginlib/class_list_macros.h>
  17. #include <pcl/filters/voxel_grid.h>
  18. #include <pcl/filters/passthrough.h>
  19. #include <pcl/filters/approximate_voxel_grid.h>
  20. #include <hdl_graph_slam/ros_utils.hpp>
  21. #include <hdl_graph_slam/registrations.hpp>
  22. #include <hdl_graph_slam/ScanMatchingStatus.h>
  23. #include <laser_geometry/laser_geometry.h>
  24. #include <fast_gicp/gicp/fast_gicp.hpp>
  25. #include <glog/logging.h>
  26. #include <new>
  27. #undef new
  28. // namespace laser_odom_ns {
  29. typedef pcl::PointXYZI PointT;
  30. class Laser_Odom {
  31. private:
  32. laser_geometry::LaserProjection projector;
  33. sensor_msgs::PointCloud2 cloud2; // 点云数据类型转换的中间变量
  34. pcl::PointCloud<PointT>::Ptr cloud; // 点云数据
  35. pcl::PointCloud<PointT>::ConstPtr keyframe; // 关键帧
  36. ros::Time prev_time;
  37. Eigen::Matrix4f prev_trans; // 地图起点到当前 帧 的放射变换
  38. Eigen::Matrix4f keyframe_pose; // 地图起点到当前 关键帧 的仿射变换
  39. ros::Time keyframe_stamp; // 关键帧的时间戳
  40. pcl::Registration<PointT, PointT>::Ptr registration;
  41. // fast_gicp::FastGICP<PointT, PointT>::Ptr registration;
  42. pcl::Filter<PointT>::Ptr downsample_filter;
  43. double keyframe_delta_trans = 0.5;
  44. double keyframe_delta_angle = 0.5;
  45. double keyframe_delta_time = 10.0;
  46. // std::string odom_frame_id = "odom";
  47. tf::TransformBroadcaster keyframe_broadcaster;
  48. tf::TransformBroadcaster odom_broadcaster;
  49. ros::NodeHandle nh;
  50. ros::Publisher odom_pub; // 里程计发布
  51. ros::Publisher path_pub;
  52. // ros::Publisher read_until_pub; //
  53. ros::Publisher source_points_pub;
  54. ros::Publisher map_points_pub;
  55. static Laser_Odom* laser_odom;
  56. Eigen::Matrix4f odom;
  57. double downsample_resolution = 0.1; // 下采样分辨率
  58. ros::NodeHandle private_nh;
  59. pcl::PointCloud<PointT>::Ptr trans_cloud;
  60. public:
  61. Laser_Odom();
  62. ~Laser_Odom();
  63. void init();
  64. static void cloud_callback(const sensor_msgs::LaserScan::ConstPtr& laser_scan_msg);
  65. Eigen::Matrix4f matching(const ros::Time& stamp, const pcl::PointCloud<PointT>::ConstPtr& cloud);
  66. pcl::PointCloud<PointT>::ConstPtr downsample(const pcl::PointCloud<PointT>::ConstPtr& cloud);
  67. geometry_msgs::TransformStamped matrix2transform(const ros::Time& stamp, const Eigen::Matrix4f& pose, const std::string& frame_id, const std::string& child_frame_id);
  68. void publish_odometry(const ros::Time& stamp, const std::string& base_frame_id, const Eigen::Matrix4f& pose);
  69. void publish_keyfrrame(const ros::Time& stamp, const std::string& base_frame_id, const Eigen::Matrix4f& pose); // 发布里程计数据
  70. };
  71. // }; // namespace laser_odom_ns