point_sift_segmentation.h 3.3 KB

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