detect_manager.cpp 12 KB

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