mapLoader.h 1.8 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950
  1. #ifndef _MAP_LOADER_H_
  2. #define _MAP_LOADER_H_
  3. #include <pcl/point_cloud.h>
  4. #include <pcl/point_types.h>
  5. #include <pcl/filters/voxel_grid.h>
  6. #include <pcl_conversions/pcl_conversions.h>
  7. #include <pcl/filters/statistical_outlier_removal.h>
  8. #include <ros/ros.h>
  9. #include <sensor_msgs/Imu.h>
  10. #include <sensor_msgs/PointCloud2.h>
  11. #include <vector>
  12. #include <pcl_ros/transforms.h>
  13. #include "rapidjson/document.h"
  14. #include "rapidjson/writer.h"
  15. #include "rapidjson/reader.h"
  16. #include "rapidjson/ostreamwrapper.h"
  17. class MapLoader{
  18. public:
  19. MapLoader(ros::NodeHandle &iNh, ros::NodeHandle &iNhPrivate);
  20. private:
  21. ros::Publisher m_iPubCloudMap_;
  22. ros::Publisher m_iPubCloudTrajectory_;
  23. std::vector<std::string> m_vMapFileName_;
  24. std::string pcd_path_trajectory_;
  25. std::string m_cSaveTransformPointCloudPath_;
  26. float tf_x_{}, tf_y_{}, tf_z_{}, tf_roll_{}, tf_pitch_{}, tf_yaw_{};
  27. sensor_msgs::PointCloud2 CreatePcd();
  28. pcl::PointCloud<pcl::PointXYZI>::Ptr __LoadPointCloudFromPcd();
  29. pcl::PointCloud<pcl::PointXYZI>::Ptr __LoadPointCloudFromJson();
  30. void __DeletPoint(pcl::PointCloud<pcl::PointXYZI>::Ptr pointCloud);
  31. sensor_msgs::PointCloud2 LoadPcd(std::string pcdPath);
  32. sensor_msgs::PointCloud2 __TransformMap(sensor_msgs::PointCloud2 & iMsgIn) const;
  33. sensor_msgs::PointCloud2 __TransformMap(pcl::PointCloud<pcl::PointXYZI>::Ptr in) const;
  34. static int functionSave(std::string cFileName, const pcl::PointCloud<pcl::PointXYZI>::Ptr& pCloudMap);
  35. template<typename PointT>
  36. inline int loadJson(const std::string &file_name, pcl::PointCloud<PointT> &cloud);
  37. double __Distance(pcl::PointXYZI p1, pcl::PointXYZI p2){
  38. std::sqrt(std::pow(p1.x - p2.x,2) + std::pow(p1.y - p2.y,2) + std::pow(p1.z - p2.z,2));
  39. }
  40. std::string __ReadFile(std::string cFileName);
  41. }; //MapLoader
  42. #endif