ground_region.h 5.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141
  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 "../verify/Verify_result.h"
  14. #include <opencv2/opencv.hpp>
  15. #include <glog/logging.h>
  16. #include <pcl/point_types.h>
  17. #include <pcl/point_cloud.h>
  18. class Ground_region
  19. {
  20. public:
  21. enum Region_cloud_type
  22. {
  23. total = 0,
  24. left_front = 1,
  25. left_back = 2,
  26. right_front = 3,
  27. right_back = 4,
  28. };
  29. enum Ground_region_status
  30. {
  31. E_UNKNOWN = 0, //未知
  32. E_READY = 1, //准备,待机
  33. E_BUSY = 2, //工作正忙
  34. E_FAULT = 10, //故障
  35. };
  36. #define GROUND_REGION_DETECT_CYCLE_MS 150
  37. Ground_region();
  38. ~Ground_region();
  39. // 区域类初始化
  40. Error_manager init(velodyne::Region region, pcl::PointCloud<pcl::PointXYZ>::Ptr left_model, pcl::PointCloud<pcl::PointXYZ>::Ptr right_model);
  41. // 公有检测函数,根据初始化设置的区域进行裁剪,并识别获得结果
  42. Error_manager detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, detect_wheel_ceres3d::Detect_result &result);
  43. // 公有点云更新函数,传入最新点云获得结果
  44. Error_manager update_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
  45. //外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待
  46. Error_manager get_current_wheel_information(Common_data::Car_wheel_information* p_car_wheel_information,
  47. std::chrono::system_clock::time_point command_time);
  48. //外部调用获取最新的车轮定位信息, 获取指令时间往前一个周期内的车轮定位信息, 如果没有就会报错, 不会等待
  49. Error_manager get_last_wheel_information(Common_data::Car_wheel_information* p_car_wheel_information,
  50. std::chrono::system_clock::time_point command_time);
  51. void get_region_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &out_cloud, Region_cloud_type type)
  52. {
  53. std::lock_guard<std::mutex> lck(m_cloud_collection_mutex);
  54. out_cloud->clear();
  55. if(m_detector==nullptr)
  56. return;
  57. switch (type)
  58. {
  59. case Region_cloud_type::total:
  60. out_cloud->operator+=(*mp_cloud_collection);
  61. break;
  62. case Region_cloud_type::left_front:
  63. out_cloud->operator+=(m_detector->m_left_front_cloud);
  64. break;
  65. case Region_cloud_type::left_back:
  66. out_cloud->operator+=(m_detector->m_left_rear_cloud);
  67. break;
  68. case Region_cloud_type::right_front:
  69. out_cloud->operator+=(m_detector->m_right_front_cloud);
  70. break;
  71. case Region_cloud_type::right_back:
  72. out_cloud->operator+=(m_detector->m_right_rear_cloud);
  73. break;
  74. }
  75. }
  76. // 获取区域终端号, 注意!未初始化调用将返回-1
  77. int get_terminal_id()
  78. {
  79. if(m_region_status == E_UNKNOWN)
  80. return -1;
  81. else
  82. return m_region.region_id();
  83. }
  84. // 获取区域状态
  85. Ground_region_status get_status() { return m_region_status; }
  86. // 获取更新时间
  87. std::chrono::system_clock::time_point get_detect_update_time() { return m_detect_update_time; }
  88. // 获取配置参数
  89. velodyne::Region get_param() { return m_region; }
  90. // 检查激光是否在区域中
  91. bool check_lidar_inside(int lidar_id)
  92. {
  93. for (size_t i = 0; i < m_region.lidar_exts_size(); i++)
  94. {
  95. if(m_region.lidar_exts(i).lidar_id() == lidar_id)
  96. return true;
  97. }
  98. return false;
  99. }
  100. private:
  101. // 点云分类,z切,3d优化
  102. bool classify_ceres_detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double thresh_z,
  103. detect_wheel_ceres3d::Detect_result &result);
  104. // 自动检测线程函数,频率由外部更新点云频率控制
  105. void thread_measure_func();
  106. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation(pcl::PointCloud<pcl::PointXYZ>::Ptr sor_cloud);
  107. double distance(cv::Point2f p1, cv::Point2f p2);
  108. bool isRect(std::vector<cv::Point2f> &points);
  109. private:
  110. velodyne::Region m_region; // 区域配置
  111. detect_wheel_ceres3d *m_detector; // 检测器
  112. Ground_region_status m_region_status; // 区域状态
  113. // 自动检测线程
  114. std::thread *m_measure_thread;
  115. Thread_condition m_measure_condition;
  116. std::mutex m_cloud_collection_mutex; // 点云更新互斥锁, 内存由上级管理
  117. pcl::PointCloud<pcl::PointXYZ>::Ptr mp_cloud_collection; //扫描点的点云集合, 内存由上级管理
  118. std::chrono::system_clock::time_point m_cloud_collection_time; // 点云更新时间
  119. Common_data::Car_wheel_information m_car_wheel_information; //车轮的定位结果,
  120. std::chrono::system_clock::time_point m_detect_update_time; //定位结果的更新时间.
  121. };
  122. #endif //LIDARMEASURE__GROUD_REGION_HPP_