ground_region.h 7.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190
  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 "car_pose_detector.h"
  15. #include "chassis_ceres_solver.h"
  16. #include <opencv2/opencv.hpp>
  17. #include <glog/logging.h>
  18. #include <pcl/point_types.h>
  19. #include <pcl/point_cloud.h>
  20. #include <pcl/filters/approximate_voxel_grid.h>
  21. class Ground_region
  22. {
  23. public:
  24. enum Region_cloud_type
  25. {
  26. total = 0,
  27. left_front = 1,
  28. left_back = 2,
  29. right_front = 3,
  30. right_back = 4,
  31. filtered = 5,
  32. detect_z=6,
  33. };
  34. enum Ground_region_status
  35. {
  36. E_UNKNOWN = 0, //未知
  37. E_READY = 1, //准备,待机
  38. E_BUSY = 2, //工作正忙
  39. E_FAULT = 10, //故障
  40. };
  41. enum Range_status
  42. {
  43. Range_correct = 0x0000, // 未超界
  44. Range_front = 0x0001, //前超界
  45. Range_back = 0x0002, //后超界
  46. Range_left = 0x0004, // 左超界
  47. Range_right = 0x0008, // 右超界
  48. Range_bottom = 0x0010, //底盘超界
  49. Range_top = 0x0020, // 车顶超界
  50. Range_car_width = 0x0040, // 车宽超界
  51. Range_car_wheelbase = 0x0080, // 轴距超界
  52. Range_angle_anti_clock = 0x0100, // 左(逆时针)旋转超界
  53. Range_angle_clock = 0x0200, // 右(顺时针)旋转超界
  54. Range_steering_wheel_nozero = 0x0400, // 方向盘未回正
  55. Range_car_moving = 0x0800, // 车辆移动为1,静止为0
  56. };
  57. #define GROUND_REGION_DETECT_CYCLE_MS 150
  58. Ground_region();
  59. ~Ground_region();
  60. // 区域类初始化
  61. Error_manager init(velodyne::Region region, pcl::PointCloud<pcl::PointXYZ>::Ptr left_model, pcl::PointCloud<pcl::PointXYZ>::Ptr right_model);
  62. // 公有检测函数,根据初始化设置的区域进行裁剪,并识别获得结果
  63. Error_manager detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, detect_wheel_ceres3d::Detect_result &result);
  64. // 公有点云更新函数,传入最新点云获得结果
  65. Error_manager update_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
  66. //外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待
  67. Error_manager get_current_wheel_information(Common_data::Car_wheel_information* p_car_wheel_information,
  68. std::chrono::system_clock::time_point command_time);
  69. //外部调用获取最新的车轮定位信息, 获取指令时间往前一个周期内的车轮定位信息, 如果没有就会报错, 不会等待
  70. Error_manager get_last_wheel_information(Common_data::Car_wheel_information* p_car_wheel_information,
  71. std::chrono::system_clock::time_point command_time);
  72. void get_region_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &out_cloud, Region_cloud_type type)
  73. {
  74. out_cloud->clear();
  75. if(m_detector==nullptr)
  76. return;
  77. switch (type)
  78. {
  79. case Region_cloud_type::total:
  80. m_cloud_collection_mutex.lock();
  81. out_cloud->operator+=(*mp_cloud_collection);
  82. m_cloud_collection_mutex.unlock();
  83. // LOG(WARNING) << "region cloud size: " << mp_cloud_collection->size();
  84. break;
  85. case Region_cloud_type::left_front:
  86. out_cloud->operator+=(m_detector->m_left_front_cloud);
  87. break;
  88. case Region_cloud_type::left_back:
  89. out_cloud->operator+=(m_detector->m_left_rear_cloud);
  90. break;
  91. case Region_cloud_type::right_front:
  92. out_cloud->operator+=(m_detector->m_right_front_cloud);
  93. break;
  94. case Region_cloud_type::right_back:
  95. out_cloud->operator+=(m_detector->m_right_rear_cloud);
  96. break;
  97. case Region_cloud_type::filtered:
  98. m_filtered_cloud_mutex.lock();
  99. out_cloud->operator+=(*mp_cloud_filtered);
  100. m_filtered_cloud_mutex.unlock();
  101. break;
  102. case Region_cloud_type::detect_z:
  103. m_detect_z_cloud_mutex.lock();
  104. out_cloud->operator+=(*mp_cloud_detect_z);
  105. m_detect_z_cloud_mutex.unlock();
  106. break;
  107. }
  108. }
  109. // 获取区域终端号, 注意!未初始化调用将返回-1
  110. int get_terminal_id()
  111. {
  112. if(m_region_status == E_UNKNOWN)
  113. return -1;
  114. else
  115. return m_region.region_id();
  116. }
  117. // 获取区域状态
  118. Ground_region_status get_status() { return m_region_status; }
  119. // 获取更新时间
  120. std::chrono::system_clock::time_point get_detect_update_time() { return m_detect_update_time; }
  121. // 获取配置参数
  122. velodyne::Region get_param() { return m_region; }
  123. // 检查激光是否在区域中
  124. bool check_lidar_inside(int lidar_id)
  125. {
  126. for (size_t i = 0; i < m_region.lidar_exts_size(); i++)
  127. {
  128. if(m_region.lidar_exts(i).lidar_id() == lidar_id)
  129. return true;
  130. }
  131. return false;
  132. }
  133. private:
  134. // 点云分类,z切,3d优化
  135. bool classify_ceres_detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double thresh_z,
  136. detect_wheel_ceres3d::Detect_result &result);
  137. // 自动检测线程函数,频率由外部更新点云频率控制
  138. void thread_measure_func();
  139. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation(pcl::PointCloud<pcl::PointXYZ>::Ptr sor_cloud);
  140. // double distance(cv::Point2f p1, cv::Point2f p2);
  141. bool isRect(std::vector<cv::Point2f> &points);
  142. // 超界判断,旋转单位(deg),默认无旋转
  143. // 主要判断左右超界
  144. int outOfRangeDetection(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double plate_cx=0.0, double plate_cy=0.0, double theta=0.0);
  145. // 超界判断,增加对后轮的判断,对轴距、车宽、角度超界的判断
  146. int outOfRangeDetection(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, Common_data::Car_wheel_information measure_result, double plate_cx=0.0, double plate_cy=0.0, double theta=0.0);
  147. private:
  148. velodyne::Region m_region; // 区域配置
  149. detect_wheel_ceres3d *m_detector; // 检测器
  150. Ground_region_status m_region_status; // 区域状态
  151. // 自动检测线程
  152. std::thread *m_measure_thread;
  153. Thread_condition m_measure_condition;
  154. std::mutex m_cloud_collection_mutex; // 点云更新互斥锁, 内存由上级管理
  155. pcl::PointCloud<pcl::PointXYZ>::Ptr mp_cloud_collection; //扫描点的点云集合, 内存由上级管理
  156. std::chrono::system_clock::time_point m_cloud_collection_time; // 点云更新时间
  157. std::mutex m_filtered_cloud_mutex; // 点云更新互斥锁, 内存由上级管理
  158. pcl::PointCloud<pcl::PointXYZ>::Ptr mp_cloud_filtered; // 区域切除后的点
  159. std::mutex m_detect_z_cloud_mutex; // 点云更新互斥锁, 内存由上级管理
  160. pcl::PointCloud<pcl::PointXYZ>::Ptr mp_cloud_detect_z; // 底盘切除后的点
  161. Common_data::Car_wheel_information m_car_wheel_information; //车轮的定位结果,
  162. std::chrono::system_clock::time_point m_detect_update_time; //定位结果的更新时间.
  163. std::mutex m_car_result_mutex; // 测量结果互斥锁
  164. };
  165. #endif //LIDARMEASURE__GROUD_REGION_HPP_