ground_region.h 5.5 KB

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