// // Created by zx on 2021/5/20. // #ifndef LIDARMEASURE__GROUD_REGION_HPP_ #define LIDARMEASURE__GROUD_REGION_HPP_ #include #include "../tool/thread_condition.h" #include "../tool/common_data.h" #include "../error_code/error_code.h" #include "match3d/detect_wheel_ceres3d.h" #include "velodyne_config.pb.h" #include "message/measure_message.pb.h" #include #include #include #include class Ground_region { public: Ground_region(); ~Ground_region(); // 区域类初始化 Error_manager init(velodyne::Region region); // 公有检测函数,根据初始化设置的区域进行裁剪,并识别获得结果 Error_manager detect(pcl::PointCloud::Ptr cloud, detect_wheel_ceres3d::Detect_result &result); // 公有点云更新函数,传入最新点云获得结果 Error_manager update_cloud(pcl::PointCloud::Ptr cloud); private: // 点云分类,z切,3d优化 bool classify_ceres_detect(pcl::PointCloud::Ptr cloud, double thresh_z, detect_wheel_ceres3d::Detect_result &result); // 自动检测线程函数 void thread_measure_func(); std::vector::Ptr> segmentation(pcl::PointCloud::Ptr sor_cloud); double distance(cv::Point2f p1, cv::Point2f p2); bool isRect(std::vector &points); public: velodyne::Region m_region; detect_wheel_ceres3d *m_detector; private: // 自动检测线程 std::thread *m_measure_thread; Thread_condition m_measure_condition; std::mutex* mp_cloud_collection_mutex; // 点云更新互斥锁, 内存由上级管理 pcl::PointCloud::Ptr mp_cloud_collection; //扫描点的点云集合, 内存由上级管理 Common_data::Car_wheel_information m_car_wheel_information; //车轮的定位结果, std::chrono::system_clock::time_point m_detect_updata_time; //定位结果的更新时间. }; #endif //LIDARMEASURE__GROUD_REGION_HPP_