point_sift_segmentation.h 3.9 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889
  1. #ifndef __POINTSIFT__HH___API
  2. #define __POINTSIFT__HH___API
  3. #include <string>
  4. #include "pointSIFT_API.h"
  5. #include "../error_code/error_code.h"
  6. #include <pcl/point_types.h>
  7. #include <pcl/common/common.h>
  8. #include "../locate/predict_with_network.h"
  9. //Cloud_box,点云的三维方框,
  10. typedef struct Cloud_box
  11. {
  12. double x_min;
  13. double x_max;
  14. double y_min;
  15. double y_max;
  16. double z_min;
  17. double z_max;
  18. }Cloud_box;
  19. /*
  20. * 封装PointSift点云分割网络,输入点云,分割出汽车,检验结果
  21. * 功能包括将pcl点云数据格式转换成原始数据格式float*
  22. * 将识别数据转换成点云数据并用不同颜色区分
  23. */
  24. class Point_sift_segmentation : public PointSifter
  25. {
  26. public:
  27. Point_sift_segmentation(int point_size,int cls,float freq,pcl::PointXYZ minp,pcl::PointXYZ maxp);
  28. Point_sift_segmentation(int point_size,int cls,float freq, Cloud_box cloud_box);
  29. virtual ~Point_sift_segmentation();
  30. //初始化网络, 加载网络权重
  31. virtual Error_manager init(std::string graph,std::string cpkt);
  32. //分割函数,输入点云,输出各类的点云,并保存中间文件方便查看识别结果.
  33. //cloud:输入点云, (有内存)
  34. //cloud_vector:输出分类好的多个点云(附带颜色,红色为杂物,绿色为车,白色为地面)(此时里面没有内存)
  35. virtual Error_manager segmentation(int lidar_id, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud_in,
  36. std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& cloud_vector,
  37. bool save_flag, std::string save_dir);
  38. public://get or set member variable
  39. Predict_with_network& get_predict_with_network();
  40. protected:
  41. //使用体素网格, 抽稀点云, //将点云空间分为小方格,每个小方格只保留一个点.
  42. Error_manager filter_cloud_with_voxel_grid(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud);
  43. //使用box限定点云范围,只保留box范围内部的点, 剔除外部的点云
  44. Error_manager filter_cloud_with_box(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud);
  45. //通过输入点云,更新边界区域范围
  46. Error_manager update_region(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud);
  47. //抽稀点云, //自己写的算法, 重新生成新的点云.
  48. Error_manager filter_cloud_with_my_grid(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud);
  49. //从点云中选出固定数量的随机点, 默认8192个点
  50. //p_cloud_in::输入点云, 有内存,且size>0
  51. //p_cloud_out::输出点云, 需要提前分配内存. size==0
  52. Error_manager filter_cloud_with_select(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud_in, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud_out);
  53. //将点云数据转换到float*
  54. Error_manager translate_cloud_to_float(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud_in, float* p_data_out);
  55. //恢复点云, 将float*转换成点云
  56. //p_data_type:输入点云对应的类别, 大小为 点数*m_cls_num*float
  57. //p_data_point:输入点云数据(xyz)
  58. //cloud_vector::输出带颜色的点云vector
  59. Error_manager recovery_float_to_cloud(float* p_data_type, float* p_data_point, std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& cloud_vector);
  60. //恢复点云, 将float*转换成点云
  61. //p_data_type:输入点云对应的类别(取值 0 ~ m_cls_num-1 ),大小为 点数*int
  62. //p_data_point:输入点云数据(xyz)
  63. //cloud_vector::输出带颜色的点云vector
  64. Error_manager recovery_float_to_cloud(int* p_data_type, float* p_data_point, std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& cloud_vector);
  65. //保存点云数据
  66. Error_manager save_cloud(std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& cloud_vector, std::string save_dir);
  67. protected:
  68. float m_freq; //抽稀的分辨率,
  69. pcl::PointXYZ m_minp; //真实点云的最小值, 区域范围
  70. pcl::PointXYZ m_maxp; //真实点云的最大值, 区域范围
  71. Cloud_box m_cloud_box_limit; //限制点云的方框, 只有在有效区域内的点才能参与计算.
  72. Predict_with_network m_predict_with_network; //从服务器进行点云预测算法的功能模块
  73. };
  74. #endif