ground_region.h 2.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263
  1. //
  2. // Created by zx on 2021/5/20.
  3. //
  4. #ifndef LIDARMEASURE__GROUD_REGION_HPP_
  5. #define LIDARMEASURE__GROUD_REGION_HPP_
  6. #include <thread>
  7. #include "../tool/thread_condition.h"
  8. #include "../tool/common_data.h"
  9. #include "../error_code/error_code.h"
  10. #include "match3d/detect_wheel_ceres3d.h"
  11. #include "velodyne_config.pb.h"
  12. #include "message/measure_message.pb.h"
  13. #include <opencv2/opencv.hpp>
  14. #include <glog/logging.h>
  15. #include <pcl/point_types.h>
  16. #include <pcl/point_cloud.h>
  17. class Ground_region
  18. {
  19. public:
  20. Ground_region();
  21. ~Ground_region();
  22. // 区域类初始化
  23. Error_manager init(velodyne::Region region);
  24. // 公有检测函数,根据初始化设置的区域进行裁剪,并识别获得结果
  25. Error_manager detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, detect_wheel_ceres3d::Detect_result &result);
  26. // 公有点云更新函数,传入最新点云获得结果
  27. Error_manager update_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
  28. private:
  29. // 点云分类,z切,3d优化
  30. bool classify_ceres_detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double thresh_z,
  31. detect_wheel_ceres3d::Detect_result &result);
  32. // 自动检测线程函数
  33. void thread_measure_func();
  34. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation(pcl::PointCloud<pcl::PointXYZ>::Ptr sor_cloud);
  35. double distance(cv::Point2f p1, cv::Point2f p2);
  36. bool isRect(std::vector<cv::Point2f> &points);
  37. public:
  38. velodyne::Region m_region;
  39. detect_wheel_ceres3d *m_detector;
  40. private:
  41. // 自动检测线程
  42. std::thread *m_measure_thread;
  43. Thread_condition m_measure_condition;
  44. std::mutex* mp_cloud_collection_mutex; // 点云更新互斥锁, 内存由上级管理
  45. pcl::PointCloud<pcl::PointXYZ>::Ptr mp_cloud_collection; //扫描点的点云集合, 内存由上级管理
  46. Common_data::Car_wheel_information m_car_wheel_information; //车轮的定位结果,
  47. std::chrono::system_clock::time_point m_detect_updata_time; //定位结果的更新时间.
  48. };
  49. #endif //LIDARMEASURE__GROUD_REGION_HPP_