ground_region.h 3.7 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798
  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. enum Ground_region_status
  21. {
  22. E_UNKNOWN = 0, //未知
  23. E_READY = 1, //准备,待机
  24. E_BUSY = 2, //工作正忙
  25. E_FAULT = 10, //故障
  26. };
  27. #define GROUND_REGION_DETECT_CYCLE_MS 200
  28. Ground_region();
  29. ~Ground_region();
  30. // 区域类初始化
  31. Error_manager init(velodyne::Region region, pcl::PointCloud<pcl::PointXYZ>::Ptr left_model, pcl::PointCloud<pcl::PointXYZ>::Ptr right_model);
  32. // 公有检测函数,根据初始化设置的区域进行裁剪,并识别获得结果
  33. Error_manager detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, detect_wheel_ceres3d::Detect_result &result);
  34. // 公有点云更新函数,传入最新点云获得结果
  35. Error_manager update_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
  36. //外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待
  37. Error_manager get_current_wheel_information(Common_data::Car_wheel_information* p_car_wheel_information,
  38. std::chrono::system_clock::time_point command_time);
  39. //外部调用获取最新的车轮定位信息, 获取指令时间往前一个周期内的车轮定位信息, 如果没有就会报错, 不会等待
  40. Error_manager get_last_wheel_information(Common_data::Car_wheel_information* p_car_wheel_information,
  41. std::chrono::system_clock::time_point command_time);
  42. // 获取区域终端号, 注意!未初始化调用将返回-1
  43. int get_terminal_id()
  44. {
  45. if(m_region_status == E_UNKNOWN)
  46. return -1;
  47. else
  48. return m_region.region_id();
  49. }
  50. // 获取区域状态
  51. Ground_region_status get_status() { return m_region_status; }
  52. // 获取更新时间
  53. std::chrono::system_clock::time_point get_detect_update_time() { return m_detect_update_time; }
  54. // 获取配置参数
  55. velodyne::Region get_param() { return m_region; }
  56. private:
  57. // 点云分类,z切,3d优化
  58. bool classify_ceres_detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double thresh_z,
  59. detect_wheel_ceres3d::Detect_result &result);
  60. // 自动检测线程函数,频率由外部更新点云频率控制
  61. void thread_measure_func();
  62. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation(pcl::PointCloud<pcl::PointXYZ>::Ptr sor_cloud);
  63. double distance(cv::Point2f p1, cv::Point2f p2);
  64. bool isRect(std::vector<cv::Point2f> &points);
  65. private:
  66. velodyne::Region m_region; // 区域配置
  67. detect_wheel_ceres3d *m_detector; // 检测器
  68. Ground_region_status m_region_status; // 区域状态
  69. // 自动检测线程
  70. std::thread *m_measure_thread;
  71. Thread_condition m_measure_condition;
  72. std::mutex m_cloud_collection_mutex; // 点云更新互斥锁, 内存由上级管理
  73. pcl::PointCloud<pcl::PointXYZ>::Ptr mp_cloud_collection; //扫描点的点云集合, 内存由上级管理
  74. std::chrono::system_clock::time_point m_cloud_collection_time; // 点云更新时间
  75. Common_data::Car_wheel_information m_car_wheel_information; //车轮的定位结果,
  76. std::chrono::system_clock::time_point m_detect_update_time; //定位结果的更新时间.
  77. };
  78. #endif //LIDARMEASURE__GROUD_REGION_HPP_