detect_manager.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209
  1. //
  2. // Created by zx on 2023/11/24.
  3. //
  4. #include "detect_manager.h"
  5. Error_manager DetectManager::Init() {
  6. #ifdef ENABLE_TENSORRT_DETECT
  7. detector = new TensorrtWheelDetector(ETC_PATH PROJECT_NAME "/model.engine", ETC_PATH PROJECT_NAME "/class.txt");
  8. #else
  9. detector = new TensorrtWheelDetector(ETC_PATH PROJECT_NAME "/model.onnx", ETC_PATH PROJECT_NAME "/class.txt");
  10. #endif
  11. m_thread = new std::thread(&DetectManager::run, this);
  12. m_condit.notify_all(true);
  13. return Error_manager();
  14. }
  15. void DetectManager::run() {
  16. LOG(INFO) << "detect thread running in " << std::this_thread::get_id();
  17. DetectResult m_detect_result_record;
  18. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> vct_wheel_cloud;
  19. for (int i = 0; i < DeviceAzimuth::DEVICE_AZIMUTH_MAX; i++) {
  20. vct_wheel_cloud.emplace_back(new pcl::PointCloud<pcl::PointXYZ>);
  21. }
  22. auto t_start_time = std::chrono::steady_clock::now();
  23. std::chrono::duration<double> cost = std::chrono::steady_clock::now() - t_start_time;
  24. while (m_condit.is_alive()) {
  25. m_condit.wait();
  26. // 参数初始化
  27. cost = std::chrono::steady_clock::now() - t_start_time;
  28. std::this_thread::sleep_for(std::chrono::milliseconds(100 - std::min<int>(99, cost.count() * 1000)));
  29. t_start_time = std::chrono::steady_clock::now();
  30. if (m_condit.is_alive()) {
  31. DetectResult detect_result;
  32. cv::Mat merge_mat = cv::Mat::zeros(480 * 2, 640 * 2, CV_8UC1);
  33. DeviceTof3D::DeviceTof3DSaveInfo t_device_mat[DeviceAzimuth::DEVICE_AZIMUTH_MAX];
  34. for (int device_index = 0; device_index < DeviceAzimuth::DEVICE_AZIMUTH_MAX; device_index++) {
  35. t_device_mat[device_index] = DeviceTof3D::iter()->getDeviceSaveInfo((DeviceAzimuth)device_index);
  36. t_device_mat[device_index].irMat.copyTo(merge_mat(cv::Rect((device_index & 0x1) * 640,
  37. ((device_index & 0x2) >> 1) * 480, 640, 480)));
  38. }
  39. cost = std::chrono::steady_clock::now() - t_start_time;
  40. DLOG(INFO) << "cost time is " << cost.count() * 1000 << " ms";
  41. // 模型识别
  42. std::vector<Object> objs;
  43. cv::cvtColor(merge_mat, merge_mat, cv::COLOR_GRAY2RGB);
  44. detector->detect(merge_mat, objs, merge_mat);
  45. cv::imshow("merge_mat", merge_mat);
  46. cv::waitKey(1);
  47. if (objs.empty()) {
  48. detect_statu = MeasureStatu::Measure_Empty_Clouds;
  49. m_detect_result_record.reset();
  50. continue;
  51. }
  52. cost = std::chrono::steady_clock::now() - t_start_time;
  53. DLOG(INFO) << "cost time is " << cost.count() * 1000 << " ms";
  54. // 标记识别点云
  55. for (auto &obj: objs) {
  56. auto seg_points = detector->getPointsFromObj(obj);
  57. int device_index = (int(seg_points[0].x / 640) * 0x01) | (int(seg_points[0].y / 480) << 1);
  58. detect_result.wheel[device_index].confidence = obj.prob;
  59. if (obj.prob > 0.9) {
  60. detect_result.wheel[device_index].detectOk = true;
  61. vct_wheel_cloud[device_index]->clear();
  62. float d = MAX(obj.rect.height, obj.rect.width) / 2;
  63. pcl::PointXYZ point;
  64. int x_alpha = (device_index & 0x1);
  65. int y_alpha = ((device_index & 0x2) >> 1);
  66. for (auto &pt: seg_points) { // use 7.5~9ms
  67. pt.x -= x_alpha * t_device_mat[device_index].irMat.cols;
  68. pt.y -= y_alpha * t_device_mat[device_index].irMat.rows;
  69. t_device_mat[device_index].pointMat.at<cv::Vec4f>(pt)[3] = obj.prob;
  70. point.x = t_device_mat[device_index].pointMat.at<cv::Vec4f>(pt)[0];
  71. point.y = t_device_mat[device_index].pointMat.at<cv::Vec4f>(pt)[1];
  72. point.z = t_device_mat[device_index].pointMat.at<cv::Vec4f>(pt)[2];
  73. vct_wheel_cloud[device_index]->push_back(point);
  74. }
  75. TransitData::get_instance_pointer()->setMask(seg_points, device_index);
  76. }
  77. }
  78. cost = std::chrono::steady_clock::now() - t_start_time;
  79. DLOG(INFO) << "cost time is " << cost.count() * 1000 << " ms";
  80. // 点云处理
  81. if (!objs.empty()) {
  82. WheelCloudOptimize(vct_wheel_cloud, detect_result);
  83. cost = std::chrono::steady_clock::now() - t_start_time;
  84. DLOG(INFO) << "cost time is " << cost.count() * 1000 << " ms";
  85. bool ceres_detect_ret = false;
  86. auto wheel_detect = detect_wheel_ceres::iter();
  87. // 采用上次测量结果的数据
  88. if (!m_detect_result_time_lock_data.timeout(0.5)) {
  89. detect_result = m_detect_result_time_lock_data();
  90. detect_result.car.wheel_width = MIN(detect_result.car.wheel_width + 0.4, 2.5);
  91. } else {
  92. detect_result.car.wheel_width = 3;
  93. detect_result.car.wheel_base = 2.7;
  94. }
  95. // 根据车轮数采用不同的优化方式
  96. if (m_detect_result_record.car.wheel_width < 1.0 || m_detect_result_record.car.wheel_base < 2.0 ||
  97. objs.size() > 2) {
  98. ceres_detect_ret = wheel_detect->detect_2Step(vct_wheel_cloud[DeviceAzimuth::DEVICE_AZIMUTH_LF], vct_wheel_cloud[DeviceAzimuth::DEVICE_AZIMUTH_RF],
  99. vct_wheel_cloud[DeviceAzimuth::DEVICE_AZIMUTH_LR], vct_wheel_cloud[DeviceAzimuth::DEVICE_AZIMUTH_RR],
  100. detect_result.car.wheels_center_x, detect_result.car.wheels_center_y,
  101. detect_result.car.theta, detect_result.car.wheel_base,
  102. detect_result.car.wheel_width,detect_result.car.front_wheels_theta, detect_result.car.loss);
  103. if ((m_detect_result_record.car.wheel_width < 1.0 && m_detect_result_record.car.wheel_base < 1.0 && objs.size() == 2) || objs.size() < 2) {
  104. detect_result.car.wheel_width = m_detect_result_record.car.wheel_width;
  105. detect_result.car.wheel_base = m_detect_result_record.car.wheel_base;
  106. } else if (objs.size() == 2) {
  107. std::vector<int> have_cloud;
  108. for (int device_index = 0; device_index < DeviceAzimuth::DEVICE_AZIMUTH_MAX; device_index++) {
  109. if (!vct_wheel_cloud[device_index]->empty()) {
  110. have_cloud.push_back(device_index);
  111. }
  112. }
  113. if (have_cloud[0] % 2 == have_cloud[1] %2 ) {
  114. detect_result.car.wheel_width = m_detect_result_record.car.wheel_width;
  115. } else {
  116. detect_result.car.wheel_base = m_detect_result_record.car.wheel_base;
  117. }
  118. }
  119. } else {
  120. ceres_detect_ret = wheel_detect->detect_dynP(vct_wheel_cloud[DeviceAzimuth::DEVICE_AZIMUTH_LF], vct_wheel_cloud[DeviceAzimuth::DEVICE_AZIMUTH_RF],
  121. vct_wheel_cloud[DeviceAzimuth::DEVICE_AZIMUTH_LR], vct_wheel_cloud[DeviceAzimuth::DEVICE_AZIMUTH_RR],
  122. detect_result.car.wheels_center_x, detect_result.car.wheels_center_y,
  123. detect_result.car.theta, m_detect_result_record.car.wheel_base,
  124. m_detect_result_record.car.wheel_width,detect_result.car.front_wheels_theta, detect_result.car.loss);
  125. detect_result.car.wheel_base = m_detect_result_record.car.wheel_base;
  126. detect_result.car.wheel_width = m_detect_result_record.car.wheel_width;
  127. }
  128. // 如果车辆运动,不断刷新运动时间,如果由运动转为静止则刷新运动状态到静止
  129. float move_distance = detect_result.car.wheels_center_y - m_detect_result_record.car.wheels_center_y;
  130. if (fabs(move_distance) > 0.1) {
  131. move_statu = true;
  132. } else if (move_statu()) {
  133. move_statu = false;
  134. }
  135. if (ceres_detect_ret) {
  136. // 记录下测量结果
  137. m_detect_result_record = detect_result;
  138. detect_statu = Measure_OK;
  139. m_detect_result_time_lock_data = m_detect_result_record;
  140. } else {
  141. detect_statu = Measure_Failture;
  142. }
  143. }
  144. cost = std::chrono::steady_clock::now() - t_start_time;
  145. DLOG(INFO) << "cost time is " << cost.count() * 1000 << " ms";
  146. } else {
  147. cv::destroyAllWindows();
  148. }
  149. }
  150. LOG(INFO) << "detect thread " << std::this_thread::get_id() << " closed.";
  151. }
  152. Error_manager DetectManager::WheelCloudOptimize(std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> &vct_wheel_cloud, DetectResult &result) {
  153. //下采样
  154. pcl::VoxelGrid<pcl::PointXYZ> vox; //创建滤波对象
  155. vox.setLeafSize(0.03f, 0.03f, 0.03f); //设置滤波时创建的体素体积为1cm的立方体
  156. pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  157. for (int device_index = 0; device_index < DeviceAzimuth::DEVICE_AZIMUTH_MAX; device_index++) {
  158. if (vct_wheel_cloud[device_index]->empty()) { continue;}
  159. vox.setInputCloud(vct_wheel_cloud[device_index]); //设置需要过滤的点云给滤波对象
  160. vox.filter(*vct_wheel_cloud[device_index]); //执行滤波处理,存储输出
  161. }
  162. return {};
  163. }
  164. MeasureStatu DetectManager::getMeasureResult(DetectManager::DetectResult &result) {
  165. if (detect_statu() != MeasureStatu::Measure_OK) {
  166. return detect_statu();
  167. }
  168. if (m_detect_result_time_lock_data.timeout()) {
  169. return MeasureStatu::Measure_Failture;
  170. }
  171. result = m_detect_result_time_lock_data();
  172. return MeasureStatu::Measure_OK;
  173. }
  174. Error_manager DetectManager::carMoveStatus() {
  175. if (move_statu.timeout(3) && !move_statu()) {
  176. return {FAILED, NORMAL};
  177. }
  178. return {};
  179. }