deskew_point_cloud.h 4.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123
  1. #ifndef DESKEW_POINT_CLOUD_H
  2. #define DESKEW_POINT_CLOUD_H
  3. #include <ros/ros.h>
  4. #include <sensor_msgs/Imu.h>
  5. #include <pcl_conversions/pcl_conversions.h>
  6. #include <pcl/point_cloud.h>
  7. #include <pcl/point_types.h>
  8. #include <pcl/common/transforms.h>
  9. #include <pcl/filters/voxel_grid.h>
  10. #include <pcl/segmentation/sac_segmentation.h>
  11. #include <pcl/filters/passthrough.h>
  12. #include <pcl/filters/extract_indices.h>
  13. #include <sensor_msgs/PointCloud2.h>
  14. #include <geometry_msgs/PoseWithCovarianceStamped.h>
  15. #include <geometry_msgs/TwistStamped.h>
  16. #include <nav_msgs/Odometry.h>
  17. #include <tf/LinearMath/Quaternion.h>
  18. #include <tf/transform_listener.h>
  19. #include <tf/transform_datatypes.h>
  20. #include <tf/transform_broadcaster.h>
  21. #include <opencv2/opencv.hpp>
  22. #include <mutex>
  23. #include <map>
  24. #include<algorithm>
  25. #include<random>
  26. struct PointXYZIRT {
  27. PCL_ADD_POINT4D
  28. PCL_ADD_INTENSITY;
  29. double time;
  30. uint16_t ring;
  31. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  32. } EIGEN_ALIGN16;
  33. POINT_CLOUD_REGISTER_POINT_STRUCT (PointXYZIRT,
  34. (float, x, x) (float, y, y) (float, z, z) (float, intensity, intensity) (double , time, time)
  35. (uint16_t, ring, ring)
  36. )
  37. class DeskewPointCloud
  38. {
  39. public:
  40. explicit DeskewPointCloud(ros::NodeHandle &iNh,ros::NodeHandle &iNhPrivate);
  41. ~DeskewPointCloud();
  42. private:
  43. float m_fVoxelLeafSize_;
  44. const int m_iQueueLength = 100;
  45. std::mutex imuLock;
  46. bool m_bFirstPointFlag_;
  47. bool m_bImuAvailable_;
  48. bool m_bOdomAvailable_;
  49. bool m_bOdomDeskewFlag_;
  50. double m_dTimeScanCur_, m_dTimeScanEnd_;
  51. double m_dDistanceMax_,m_dDistanceMin_;
  52. int m_nImuPointerFront_;
  53. int m_nImuPointerLast_;
  54. int m_nImuPointerCur_;
  55. int m_nOdomPointerCur_;
  56. std::deque<sensor_msgs::Imu> m_qImu;
  57. std::deque<nav_msgs::Odometry> m_qOdom_;
  58. double *m_pImuTime_;
  59. double *m_pOdomTime_;
  60. double *m_pImuRotX_;
  61. double *m_pImuRotY_;
  62. double *m_pImuRotZ_;
  63. double *m_pOdomTansX_;
  64. double *odomTansY;
  65. int m_dScanRows_,m_dScanCols_;
  66. pcl::PointCloud<PointXYZIRT>::Ptr m_pPointCloudIn_;
  67. pcl::PointCloud<pcl::PointXYZI>::Ptr m_pPointCloudDeskew_;
  68. pcl::PointCloud<pcl::PointXYZI>::Ptr m_pPointCloudFilter_;
  69. cv::Mat m_iMatCloud_;
  70. cv::RNG m_iRng;
  71. std::mt19937 m_iGen;
  72. std::uniform_int_distribution<int> dis;
  73. Eigen::Affine3f transStartInverse;
  74. ros::NodeHandle nh;
  75. ros::Subscriber m_iSubImu_;
  76. ros::Subscriber odom_sub;
  77. ros::Subscriber m_iSubPointCloud_;
  78. ros::Publisher m_iPubDeskewCloud_;
  79. ros::Publisher m_iPubFilterCloud_;
  80. ros::Publisher m_iPubFilterCloud2_;
  81. ros::Publisher m_iPubFilterCloud3_;
  82. ros::Publisher m_iPubCloudGrand_;
  83. ros::Publisher m_iPubCloudNoGrand_;
  84. double PointDistance(pcl::PointXYZI p);
  85. sensor_msgs::Imu __ImuConverter(const sensor_msgs::Imu& imu_in);
  86. void __ImuDataHandle();
  87. void __OdomDataHandle();
  88. bool __DataHandle();
  89. void __FindRotation(double dPointTime, float *pRotXCur, float *pRotYCur, float *pRotZCur);
  90. void __FindPosition(double dPointTime, float *pPosXCur, float *pPosYCur, float *pPosZCur);
  91. pcl::PointXYZI __DeskewPoint(pcl::PointXYZI *pPoint, double dRelTime);
  92. void __ResetParameters();
  93. void __ProjectPointCloud(const sensor_msgs::PointCloud2::ConstPtr &currentCloudMsg);
  94. static void PublishCloud(ros::Publisher *pPubObject, pcl::PointCloud<pcl::PointXYZI>::Ptr pCloud,
  95. ros::Time iStamp, std::string cFrameName);
  96. void __OnCallbackImu(const sensor_msgs::Imu::ConstPtr &pMsgImu);
  97. void __OnCallbackOdom(const nav_msgs::Odometry::ConstPtr &pMsgOdom);
  98. void __OnCallbackLidarCloud(const sensor_msgs::PointCloud2::ConstPtr &pMsgLidarPintCloud);
  99. void VoxelGridFilter(const pcl::PointCloud<pcl::PointXYZI>::Ptr &pCloud, double time, std::string cFrameName);
  100. void __FilterPointCloud( const cv::Mat& mat, pcl::PointCloud<pcl::PointXYZI>::Ptr &cloud);
  101. double __PointDistance(pcl::PointXYZI p1, pcl::PointXYZI p2);
  102. void __CloudClustering(pcl::PointCloud<pcl::PointXYZI>::Ptr pCloudIn, pcl::PointCloud<pcl::PointXYZRGBL>::Ptr pCloudOut);
  103. void __RanSac(pcl::PointCloud<pcl::PointXYZI>::Ptr pCloudIn, pcl::PointCloud<pcl::PointXYZI>::Ptr pCloudOutPlane, pcl::PointCloud<pcl::PointXYZI>::Ptr pCloudOutOther);
  104. };
  105. #endif