alg.cpp 31 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704
  1. //
  2. // Created by zx on 2023/10/24.
  3. //
  4. #include "alg.h"
  5. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr>
  6. GroundRegion::segmentation(pcl::PointCloud<pcl::PointXYZ>::Ptr &sor_cloud, const float &tolerance) {
  7. std::vector<pcl::PointIndices> ece_inlier;
  8. pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>);
  9. pcl::EuclideanClusterExtraction<pcl::PointXYZ> ece;
  10. ece.setInputCloud(sor_cloud);
  11. ece.setClusterTolerance(tolerance);
  12. ece.setMinClusterSize(20);
  13. ece.setMaxClusterSize(sor_cloud->size());
  14. ece.setSearchMethod(tree);
  15. ece.extract(ece_inlier);
  16. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation_clouds;
  17. for (int i = 0; i < ece_inlier.size(); i++) {
  18. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_copy(new pcl::PointCloud<pcl::PointXYZ>);
  19. std::vector<int> ece_inlier_ext = ece_inlier[i].indices;
  20. copyPointCloud(*sor_cloud, ece_inlier_ext, *cloud_copy); //按照索引提取点云数据
  21. segmentation_clouds.push_back(cloud_copy);
  22. }
  23. return segmentation_clouds;
  24. }
  25. bool GroundRegion::isRect(std::vector<cv::Point2f> &points) {
  26. if (points.size() == 4) {
  27. double L[3] = {0.0};
  28. L[0] = distance(points[0], points[1]);
  29. L[1] = distance(points[1], points[2]);
  30. L[2] = distance(points[0], points[2]);
  31. double max_l = L[0];
  32. double l1 = L[1];
  33. double l2 = L[2];
  34. cv::Point2f ps = points[0], pt = points[1];
  35. cv::Point2f pc = points[2];
  36. for (int i = 1; i < 3; ++i) {
  37. if (L[i] > max_l) {
  38. max_l = L[i];
  39. l1 = L[abs(i + 1) % 3];
  40. l2 = L[abs(i + 2) % 3];
  41. ps = points[i % 3];
  42. pt = points[(i + 1) % 3];
  43. pc = points[(i + 2) % 3];
  44. }
  45. }
  46. //直角边与坐标轴的夹角 <20°
  47. float thresh = 20.0 * M_PI / 180.0;
  48. cv::Point2f vct(pt.x - pc.x, pt.y - pc.y);
  49. float angle = atan2(vct.y, vct.x);
  50. if (!(fabs(angle) < thresh || (M_PI_2 - fabs(angle) < thresh))) {
  51. //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
  52. return false;
  53. }
  54. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  55. if (fabs(cosa) >= 0.15) {
  56. return false;
  57. }
  58. float width = std::min(l1, l2);
  59. float length = std::max(l1, l2);
  60. if (width < 1.400 || width > 1.900 || length > 3.300 || length < 2.200) {
  61. return false;
  62. }
  63. double d = distance(pc, points[3]);
  64. cv::Point2f center1 = (ps + pt) * 0.5;
  65. cv::Point2f center2 = (pc + points[3]) * 0.5;
  66. if (fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150) {
  67. return false;
  68. }
  69. return true;
  70. } else if (points.size() == 3) {
  71. double L[3] = {0.0};
  72. L[0] = distance(points[0], points[1]);
  73. L[1] = distance(points[1], points[2]);
  74. L[2] = distance(points[0], points[2]);
  75. double max_l = L[0];
  76. double l1 = L[1];
  77. double l2 = L[2];
  78. int max_index = 0;
  79. cv::Point2f ps = points[0], pt = points[1];
  80. cv::Point2f pc = points[2];
  81. for (int i = 1; i < 3; ++i) {
  82. if (L[i] > max_l) {
  83. max_index = i;
  84. max_l = L[i];
  85. l1 = L[abs(i + 1) % 3];
  86. l2 = L[abs(i + 2) % 3];
  87. ps = points[i % 3];
  88. pt = points[(i + 1) % 3];
  89. pc = points[(i + 2) % 3];
  90. }
  91. }
  92. //直角边与坐标轴的夹角 <20°
  93. float thresh = 20.0 * M_PI / 180.0;
  94. cv::Point2f vct(pt.x - pc.x, pt.y - pc.y);
  95. float angle = atan2(vct.y, vct.x);
  96. if (!(fabs(angle) < thresh || (M_PI_2 - fabs(angle) < thresh))) {
  97. return false;
  98. }
  99. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  100. if (fabs(cosa) >= 0.15) {
  101. return false;
  102. }
  103. double l = std::max(l1, l2);
  104. double w = std::min(l1, l2);
  105. if (l > 2.100 && l < 3.300 && w > 1.400 && w < 2.100) {
  106. //生成第四个点
  107. cv::Point2f vec1 = ps - pc;
  108. cv::Point2f vec2 = pt - pc;
  109. cv::Point2f point4 = (vec1 + vec2) + pc;
  110. points.push_back(point4);
  111. return true;
  112. } else {
  113. return false;
  114. }
  115. }
  116. return false;
  117. }
  118. GroundRegion::GroundRegion() {
  119. m_region_status = E_UNKNOWN;
  120. m_detector = nullptr;
  121. m_measure_thread = nullptr;
  122. }
  123. GroundRegion::~GroundRegion() {
  124. // LOG(WARNING) << "start deconstruct ground region";
  125. if (m_measure_thread) {
  126. m_measure_condition.kill_all();
  127. // Close Capturte Thread
  128. if (m_measure_thread->joinable()) {
  129. m_measure_thread->join();
  130. delete m_measure_thread;
  131. m_measure_thread = nullptr;
  132. }
  133. }
  134. // LOG(WARNING) << "thread released";
  135. // 将创建的检测器析构
  136. if (m_detector) {
  137. delete m_detector;
  138. m_detector = nullptr;
  139. }
  140. Region_status_checker::get_instance_references().Region_status_checker_uninit();
  141. // LOG(WARNING) << "detector released";
  142. }
  143. Error_manager GroundRegion::init(velodyne::Region region, pcl::PointCloud<pcl::PointXYZ>::Ptr left_model,
  144. pcl::PointCloud<pcl::PointXYZ>::Ptr right_model) {
  145. Region_status_checker::get_instance_references().Region_status_checker_init();
  146. m_region = region;
  147. m_detector = new detect_wheel_ceres3d(left_model, right_model);
  148. mp_cloud_collection = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  149. mp_detect_failture_cloud_collection = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  150. mp_cloud_filtered = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  151. mp_cloud_detect_z = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  152. m_surface_hull = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  153. m_pose_record.cy = -1e8;
  154. m_cut_line = m_region.minz() + 0.07;
  155. // 创建多边形区域指针,用于裁剪点云
  156. pcl::PointCloud<pcl::PointXYZ>::Ptr boundingbox_ptr(new pcl::PointCloud<pcl::PointXYZ>);
  157. printf("%d\n", m_region.cut_box().cut_points_size());
  158. for (auto &point: m_region.cut_box().cut_points()) {
  159. boundingbox_ptr->push_back(pcl::PointXYZ(point.x(), point.y(), point.z()));
  160. }
  161. pcl::ConvexHull<pcl::PointXYZ> hull; //建立一个凸包对象
  162. hull.setInputCloud(boundingbox_ptr); //设置凸包的维度
  163. hull.reconstruct(*m_surface_hull, m_polygons); //计算凸包结果
  164. // 启动测量线程
  165. m_measure_thread = new std::thread(&GroundRegion::thread_measure_func, this);
  166. m_measure_condition.reset();
  167. m_region_status = E_READY;
  168. m_measure_condition.notify_all(true);
  169. return SUCCESS;
  170. }
  171. bool GroundRegion::classify_ceres_detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double thresh_z,
  172. detect_wheel_ceres3d::Detect_result &result, std::string &error) {
  173. if (m_detector == nullptr || cloud->empty()) {
  174. return false;
  175. }
  176. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  177. copyPointCloud(*cloud, *cloud_filtered);
  178. // 滤波
  179. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor; //创建滤波器对象
  180. sor.setInputCloud(cloud_filtered); //设置待滤波的点云
  181. sor.setMeanK(5); //设置在进行统计时考虑的临近点个数
  182. sor.setStddevMulThresh(3.0); //设置判断是否为离群点的阀值,用来倍乘标准差,也就是上面的std_mul
  183. sor.filter(*cloud_filtered); //滤波结果存储到cloud_filtered
  184. if (cloud_filtered->empty()) {
  185. return false;
  186. }
  187. // 欧式聚类
  188. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> seg_clouds;
  189. seg_clouds = segmentation(cloud_filtered, 0.3);
  190. // if (!(seg_clouds.size() == 4 || seg_clouds.size() == 3)) {
  191. // return false;
  192. // }
  193. if (seg_clouds.size() != 4) {
  194. error.append("seg_clouds not is 4, it's " + std::to_string(seg_clouds.size()));
  195. return false;
  196. }
  197. std::vector<cv::Point2f> centers;
  198. cv::Point2f temp_centers(0, 0);
  199. // 矩形判断
  200. for (int i = 0; i < seg_clouds.size(); ++i) {
  201. Eigen::Vector4f centroid;
  202. // WriteTxtCloud(ETC_PATH"MeasureNodeAlgTest/data/" + std::to_string(m_region.region_id()) + "/seg_clouds" + std::to_string(i) + ".txt", seg_clouds[i]);
  203. pcl::compute3DCentroid(*seg_clouds[i], centroid);
  204. centers.push_back(cv::Point2f(centroid[0], centroid[1]));
  205. temp_centers += cv::Point2f(centroid[0], centroid[1]);
  206. }
  207. temp_centers /= 4.0f;
  208. bool ret = isRect(centers);
  209. // ceres库寻优
  210. if (ret) {
  211. std::string error_str;
  212. if (m_detector->detect(seg_clouds, result, error_str)) {
  213. return true;
  214. } else {
  215. error.append(error_str);
  216. return false;
  217. }
  218. } else {
  219. error.append("not is rect.");
  220. }
  221. return ret;
  222. }
  223. Error_manager GroundRegion::ClippingAndFilterCloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered) {
  224. // 2.*********点云预处理*********
  225. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  226. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cut(new pcl::PointCloud<pcl::PointXYZ>);
  227. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_clean(new pcl::PointCloud<pcl::PointXYZ>);
  228. pcl::CropHull<pcl::PointXYZ> bb_filter; //创建CropHull对象
  229. bb_filter.setDim(2); //设置维度
  230. bb_filter.setInputCloud(cloud); //设置输入点云
  231. bb_filter.setHullIndices(m_polygons); //输入封闭多边形的顶点
  232. bb_filter.setHullCloud(m_surface_hull); //输入封闭多边形的形状
  233. bb_filter.filter(*cloud_cut);
  234. pcl::PassThrough<pcl::PointXYZ> cut_pass;
  235. cut_pass.setInputCloud(cloud_cut);
  236. cut_pass.setFilterFieldName("z");
  237. cut_pass.setFilterLimits(m_region.minz(), m_region.maxz());
  238. cut_pass.setFilterLimitsNegative(false);
  239. cut_pass.filter(*cloud_cut);
  240. if (cloud_cut->size() <= 0) {
  241. // 更新过滤点
  242. m_filtered_cloud_mutex.lock();
  243. mp_cloud_filtered->clear();
  244. m_filtered_cloud_mutex.unlock();
  245. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "cut no point");
  246. }
  247. // WriteTxtCloud(ETC_PATH"MeasureNodeAlgTest/data/" + std::to_string(m_region.region_id()) + "/cloud_cut.txt", cloud_cut);
  248. //下采样
  249. pcl::VoxelGrid<pcl::PointXYZ> vox; //创建滤波对象
  250. vox.setInputCloud(cloud_cut); //设置需要过滤的点云给滤波对象
  251. vox.setLeafSize(0.02f, 0.02f, 0.02f); //设置滤波时创建的体素体积为1cm的立方体
  252. vox.filter(*cloud_clean); //执行滤波处理,存储输出
  253. if (cloud_clean->size() == 0) {
  254. // 更新过滤点
  255. m_filtered_cloud_mutex.lock();
  256. mp_cloud_filtered->clear();
  257. m_filtered_cloud_mutex.unlock();
  258. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "ApproximateVoxelGrid no point");
  259. }
  260. //离群点过滤
  261. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
  262. sor.setInputCloud(cloud_clean);
  263. sor.setMeanK(5); //K近邻搜索点个数
  264. sor.setStddevMulThresh(3.0); //标准差倍数
  265. sor.setNegative(false); //保留未滤波点(内点)
  266. sor.filter(*cloud_filtered); //保存滤波结果到cloud_filter
  267. if (cloud_filtered->size() <= 100) {
  268. // 更新过滤点
  269. m_filtered_cloud_mutex.lock();
  270. mp_cloud_filtered->clear();
  271. m_filtered_cloud_mutex.unlock();
  272. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "StatisticalOutlierRemoval no point");
  273. }
  274. // WriteTxtCloud(ETC_PATH"MeasureNodeAlgTest/data/" + std::to_string(m_region.region_id()) + "/cloud_filtered.txt", cloud_filtered);
  275. return {};
  276. }
  277. Error_manager GroundRegion::CalculateInitialPose(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered, detect_wheel_ceres3d::Detect_result &pose, pcl::PointCloud<pcl::PointXYZ>::Ptr car_clean_cloud) {
  278. if (cloud_filtered->empty()) {
  279. return {VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "StatisticalOutlierRemoval no point"};
  280. }
  281. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_detect_z(new pcl::PointCloud<pcl::PointXYZ>);
  282. if (!Car_pose_detector::get_instance_references().detect_pose_mat(cloud_filtered, cloud_detect_z, pose.cx,
  283. pose.cy, pose.theta, false)) {
  284. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR,
  285. "find general car pose value failed.");
  286. }
  287. if (fabs(pose.theta * 180.0 / M_PI) > 8) {
  288. return Error_manager(VELODYNE_REGION_ANGLE_PRECHECK_FAILED, NEGLIGIBLE_ERROR,
  289. "find general car pose value failed.");
  290. }
  291. pose.theta += M_PI_2;
  292. pose.theta = -pose.theta;
  293. // WriteTxtCloud(ETC_PATH"MeasureNodeAlgTest/data/" + std::to_string(m_region.region_id()) + "/cloud_detect_z.txt", cloud_detect_z);
  294. // double rough_width, rough_length, extract_width, extract_length;
  295. pcl::PointXYZ t_rough_min_p, t_rough_max_p, t_body_min_p, t_body_max_p;
  296. pcl::PointCloud<pcl::PointXYZ>::Ptr car_body_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  297. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_for_width_upwheel(new pcl::PointCloud<pcl::PointXYZ>);
  298. for (auto &point: cloud_detect_z->points) {
  299. cloud_for_width_upwheel->push_back(pcl::PointXYZ(point.x, point.y, 0));
  300. }
  301. // WriteTxtCloud(ETC_PATH"MeasureNodeAlgTest/data/" + std::to_string(m_region.region_id()) + "/cloud_for_width_upwheel.txt", cloud_for_width_upwheel);
  302. {
  303. pcl::getMinMax3D(*cloud_for_width_upwheel, t_rough_min_p, t_rough_max_p);
  304. pose.length = t_rough_max_p.y - t_rough_min_p.y;
  305. pcl::PassThrough<pcl::PointXYZ> cut_pass;
  306. cut_pass.setInputCloud(cloud_for_width_upwheel);
  307. cut_pass.setFilterFieldName("y");
  308. cut_pass.setFilterLimits(t_rough_min_p.y + pose.length * 0.25, t_rough_max_p.y - pose.length * 0.25);
  309. cut_pass.setFilterLimitsNegative(false);
  310. cut_pass.filter(*car_body_cloud);
  311. // 车宽重计算,并赋值到当前车宽
  312. pcl::getMinMax3D(*car_body_cloud, t_body_min_p, t_body_max_p);
  313. pose.width = t_body_max_p.x - t_body_min_p.x;
  314. }
  315. // 根据车身剔除左右两侧数据
  316. cv::Point2f car_body_rect_vertex[4];
  317. cv::Point2f lf_p, lr_p, rf_p, rr_p;
  318. cv::RotatedRect car_body_rect;
  319. Point3D_tool::getMinRect(car_body_rect, car_body_cloud);
  320. car_body_rect.points(car_body_rect_vertex);
  321. if (car_body_rect.angle < -70) {
  322. lf_p = car_body_rect_vertex[2];
  323. lr_p = car_body_rect_vertex[1];
  324. rf_p = car_body_rect_vertex[3];
  325. rr_p = car_body_rect_vertex[0];
  326. } else if (car_body_rect.angle > -20) {
  327. lf_p = car_body_rect_vertex[1];
  328. lr_p = car_body_rect_vertex[0];
  329. rf_p = car_body_rect_vertex[2];
  330. rr_p = car_body_rect_vertex[3];
  331. }
  332. pose.width = distance(lf_p, rf_p) + 0.03; // 0.03车宽补偿,部分车辆会底部窄,顶部宽,导致车宽比实际小
  333. DLOG(INFO) << pose.width;
  334. for (auto &point: cloud_filtered->points) {
  335. double x_min, x_max;
  336. x_max = (point.y - rf_p.y) * (rr_p.x - rf_p.x) / (rr_p.y - rf_p.y) + rf_p.x + 0.05;
  337. x_min = (point.y - lf_p.y) * (lr_p.x - lf_p.x) / (lr_p.y - lf_p.y) + lf_p.x - 0.05;
  338. if (point.x < x_min - 0.02 && point.x > x_min - 0.10) {
  339. continue;
  340. }
  341. if (point.x < x_max + 0.10 && point.x > x_max + 0.02) {
  342. continue;
  343. }
  344. car_clean_cloud->emplace_back(point);
  345. }
  346. // WriteTxtCloud(ETC_PATH"MeasureNodeAlgTest/data/" + std::to_string(m_region.region_id()) + "/car_clean_cloud.txt", car_clean_cloud);
  347. return {};
  348. }
  349. Error_manager
  350. GroundRegion::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, detect_wheel_ceres3d::Detect_result &last_result) {
  351. Error_manager ret;
  352. std::chrono::steady_clock::time_point t = std::chrono::steady_clock::now();
  353. std::chrono::duration<double> coast_t = std::chrono::steady_clock::now() - t;
  354. // 1.********* 点云合法性检验 *********
  355. if (cloud->size() == 0) {
  356. // 更新过滤点
  357. m_filtered_cloud_mutex.lock();
  358. mp_cloud_filtered->clear();
  359. m_filtered_cloud_mutex.unlock();
  360. m_cut_line = m_region.minz() + 0.07;
  361. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "no input point");
  362. }
  363. #if OPTION_ENABLE_DATA_FROM_LOCAL
  364. // WriteTxtCloud(ETC_PATH"MeasureNodeAlgTest/data/" + std::to_string(m_region.region_id()) + "/cloud.txt", cloud);
  365. #endif
  366. // 2.********* 点云裁剪过滤 *********
  367. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  368. ret = ClippingAndFilterCloud(cloud, cloud_filtered);
  369. if (ret != SUCCESS) {
  370. m_cut_line = m_region.minz() + 0.07;
  371. return ret;
  372. }
  373. // coast_t = std::chrono::steady_clock::now() - t;
  374. // LOG(INFO) << "get cloud_filtered coast time: " << coast_t.count() * 1000 << "ms";
  375. // 更新过滤点
  376. m_filtered_cloud_mutex.lock();
  377. mp_cloud_filtered->clear();
  378. mp_cloud_filtered->operator+=(*cloud_filtered);
  379. m_filtered_cloud_mutex.unlock();
  380. // 2.********* 点云初始位姿获取 *********
  381. pcl::PointCloud<pcl::PointXYZ>::Ptr car_clean_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  382. detect_wheel_ceres3d::Detect_result roughly_pose;
  383. ret = CalculateInitialPose(cloud_filtered, roughly_pose, car_clean_cloud);
  384. if (ret != SUCCESS) {
  385. // LOG(WARNING) << ret.to_string();
  386. return ret;
  387. }
  388. // LOG(INFO) << "m_pose_record.cy " << m_pose_record.cy << ", roughly_pose.cy " << roughly_pose.cy;
  389. // LOG(INFO) << fabs(m_pose_record.cy - roughly_pose.cy) << " " << m_cut_line;
  390. if (m_pose_record.success) {
  391. // cut line 调整
  392. m_cut_line < m_region.minz() + 0.04 ? m_cut_line += 0.05 : false;
  393. m_pose_record.loss.total_avg_loss > 0.03 ? m_cut_line -= 0.01 : false;
  394. m_pose_record.loss.total_avg_loss > 0.02 ? m_cut_line -= 0.01 : false;
  395. m_pose_record.loss.total_avg_loss < 0.005 ? m_cut_line += 0.01 : false;
  396. m_pose_record.loss.total_avg_loss < 0.003 ? m_cut_line += 0.01 : false;
  397. } else {
  398. m_cut_line += 0.07;
  399. }
  400. m_cut_line = MIN(m_cut_line, m_region.minz() + 0.2);
  401. m_cut_line = MAX(m_cut_line, m_region.minz());
  402. // coast_t = std::chrono::steady_clock::now() - t;
  403. // LOG(INFO) << "get car_clean_cloud coast time: " << coast_t.count() * 1000 << "ms";
  404. // 3.********* 算法检测 *********
  405. std::vector<detect_wheel_ceres3d::Detect_result> results;
  406. int index_z_detect = 0;
  407. std::vector<std::string> detect_error_v;
  408. while (m_cut_line > m_region.minz() + 0.03) {
  409. detect_wheel_ceres3d::Detect_result result = roughly_pose;
  410. pcl::PassThrough<pcl::PointXYZ> cut_pass;
  411. cut_pass.setInputCloud(car_clean_cloud);
  412. cut_pass.setFilterFieldName("z");
  413. cut_pass.setFilterLimits(m_region.minz(), m_cut_line);
  414. cut_pass.setFilterLimitsNegative(false);
  415. cut_pass.filter(*car_clean_cloud);
  416. // coast_t = std::chrono::steady_clock::now() - t;
  417. // LOG(INFO) << "before classify_ceres_detect coast time: " << coast_t.count() * 1000 << "ms";
  418. std::string detect_error;
  419. detect_error.append("index: " + std::to_string(index_z_detect) + " "+ result.to_string());
  420. bool ret = classify_ceres_detect(car_clean_cloud, m_cut_line, result, detect_error);
  421. LOG(INFO) << m_region.region_id() << " " << index_z_detect << " " << m_cut_line << " " << result.to_string()
  422. << " loss:" << result.loss.total_avg_loss;
  423. detect_error_v.emplace_back(detect_error);
  424. // coast_t = std::chrono::steady_clock::now() - t;
  425. // LOG(INFO) << "after classify_ceres_detect coast time: " << coast_t.count() * 1000 << "ms";
  426. if (ret) {
  427. if (!results.empty()/* && CompareCeresResult(results.back(), result)*/) {
  428. last_result = results.back().loss.total_avg_loss < result.loss.total_avg_loss ? results.back() : result;
  429. results.push_back(result);
  430. m_cut_line -= 0.01; // 为了抵消只成功一次导致cut line的削减,这里也削减一次
  431. break;
  432. }
  433. results.push_back(result);
  434. }
  435. index_z_detect++;
  436. m_cut_line -= 0.01;
  437. }
  438. m_cut_line += 0.01; // 抵消cut line 未检测过的削减
  439. if (results.size() == 1) {
  440. last_result = results.back();
  441. }
  442. // coast_t = std::chrono::steady_clock::now() - t;
  443. // LOG(INFO) << "get detect result coast time: " << coast_t.count() * 1000 << "ms";
  444. // 4.********* 算法结果校验 *********
  445. pcl::PointCloud<pcl::PointXYZ>::Ptr t_width_extract_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(
  446. new pcl::PointCloud<pcl::PointXYZ>);
  447. t_width_extract_cloud->operator+=(m_detector->m_left_front_cloud);
  448. t_width_extract_cloud->operator+=(m_detector->m_left_rear_cloud);
  449. t_width_extract_cloud->operator+=(m_detector->m_right_front_cloud);
  450. t_width_extract_cloud->operator+=(m_detector->m_right_rear_cloud);
  451. WheelsPredictor::PreResult pre_result;
  452. if (results.empty()) {
  453. for (auto &error: detect_error_v) {
  454. // LOG(ERROR) << error;
  455. }
  456. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, "3d wheel detect failed: ");
  457. }
  458. // 获取车轮精确长宽
  459. {
  460. //离群点过滤
  461. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
  462. sor.setInputCloud(t_width_extract_cloud);
  463. sor.setMeanK(5); //K近邻搜索点个数
  464. sor.setStddevMulThresh(1.0); //标准差倍数
  465. sor.setNegative(false); //保留未滤波点(内点)
  466. sor.filter(*t_width_extract_cloud); //保存滤波结果到cloud_filter
  467. Eigen::Affine3d t_affine = Eigen::Affine3d::Identity();
  468. t_affine.prerotate(Eigen::AngleAxisd((90 - last_result.theta) * M_PI / 180.0, Eigen::Vector3d::UnitZ()));
  469. pcl::transformPointCloud(*t_width_extract_cloud, *t_width_extract_cloud, t_affine.matrix());
  470. // 车宽重计算,并赋值到当前车宽
  471. pcl::PointXYZ t_min_p, t_max_p;
  472. pcl::getMinMax3D(*t_width_extract_cloud, t_min_p, t_max_p);
  473. last_result.width = t_max_p.x - t_min_p.x;
  474. last_result.length = t_max_p.y - t_min_p.y;
  475. // LOG(INFO) << "extract_width: " << last_result.width << " extract_length: " << last_result.length;
  476. }
  477. last_result.wheel_width = last_result.width;
  478. // coast_t = std::chrono::steady_clock::now() - t;
  479. // LOG(INFO) << "detect all coast time: " << coast_t.count() * 1000 << "ms";
  480. return SUCCESS;
  481. }
  482. int GroundRegion::outOfRangeDetection(Common_data::Car_wheel_information &measure_result, const velodyne::outOfRangeInfo &out_info, detect_wheel_ceres3d::Detect_result &result) {
  483. // 车位位于y负方向, 判断后轮超界情况, 4.80是搬运器大Y的运动极限, 2.7是同侧两个小y夹持杆中心距离
  484. int last_range_statu = Range_status::Range_correct;
  485. // 判断车辆轴距超界情况
  486. if (measure_result.car_wheel_base < out_info.car_min_wheelbase() - 0.010 || // 轴距过小
  487. measure_result.car_wheel_base > out_info.car_max_wheelbase() + 0.010) { // 轴距过长
  488. return last_range_statu |= Range_status::Range_car_wheelbase; // 车辆前后轴距不合法
  489. }
  490. // 判断车辆宽度超界情况
  491. if (measure_result.car_wheel_width < out_info.car_min_width() - 0.010 || // 车宽过窄
  492. measure_result.car_wheel_width > out_info.car_max_width() + 0.010) { // 车宽过宽
  493. return last_range_statu |= Range_status::Range_car_width; // 车辆超宽
  494. }
  495. // 判断车辆旋转角超界情况
  496. double t_dtheta = measure_result.car_angle;
  497. if (measure_result.car_angle < out_info.turnplate_angle_limit_min_clockwise()) {
  498. return last_range_statu |= Range_status::Range_angle_clock;
  499. } else if (measure_result.car_angle > out_info.turnplate_angle_limit_max_clockwise()) {
  500. return last_range_statu |= Range_status::Range_angle_anti_clock;
  501. }
  502. // 方向盘调正
  503. if (fabs(measure_result.car_front_theta) > 10) {
  504. return last_range_statu |= Range_status::Range_steering_wheel_nozero;
  505. }
  506. // 左右超界
  507. if (measure_result.uniform_car_x < out_info.border_minx()) {
  508. return last_range_statu |= Range_status::Range_left;
  509. } else if (measure_result.uniform_car_x > out_info.border_maxx()) {
  510. return last_range_statu |= Range_status::Range_right;
  511. }
  512. // 前超界(前轮胎超出转盘)
  513. double lf_wheel_x = result.cx - measure_result.car_wheel_width * 0.5;
  514. double rf_wheel_x = result.cx + measure_result.car_wheel_width * 0.5;
  515. double f_wheel_y = result.cy + measure_result.car_wheel_base * 0.5;
  516. double angle = (90 - result.theta) * M_PI / 180.0;
  517. double lf_uniform_wheel_x = ( lf_wheel_x - result.cx) * cos(angle) - (f_wheel_y - result.cy) * sin(angle) + result.cx;
  518. double lf_uniform_wheel_y = (lf_wheel_x - result.cx) * sin(angle) + (f_wheel_y - result.cy) * cos(angle) + result.cy;
  519. double rf_uniform_wheel_x = ( rf_wheel_x - result.cx) * cos(angle) - (f_wheel_y - result.cy) * sin(angle) + result.cx;
  520. double rf_uniform_wheel_y = (rf_wheel_x - result.cx) * sin(angle) + (f_wheel_y - result.cy) * cos(angle) + result.cy;
  521. double lf_tur_dis = (lf_uniform_wheel_x - m_region.turnplate_cx()) * (lf_uniform_wheel_x - m_region.turnplate_cx()) + (lf_uniform_wheel_y - m_region.turnplate_cy()) * (lf_uniform_wheel_y - m_region.turnplate_cy());
  522. double rf_tur_dis = (rf_uniform_wheel_x - m_region.turnplate_cx()) * (rf_uniform_wheel_x - m_region.turnplate_cx()) + (rf_uniform_wheel_y - m_region.turnplate_cy()) * (rf_uniform_wheel_y - m_region.turnplate_cy());
  523. auto max_dis = MAX(lf_tur_dis, rf_tur_dis);
  524. if (sqrt(max_dis) > (4.2 * 0.5 - 0.1)) { // 4.2 转盘直径LOG(INFO) << m_region.region_id() << " 前超界!!!!!!!! " << sqrt(max_dis);
  525. return last_range_statu |= Range_status::Range_front; // 后超界
  526. }
  527. // 后超界
  528. double t_center_y = fabs(measure_result.uniform_car_y);
  529. DLOG(INFO) << t_center_y - 4.80 + 0.5 * (measure_result.car_wheel_base - 2.7) << " " << out_info.plc_border_maxy();
  530. DLOG(INFO) << t_center_y - 4.80 - 0.5 * (measure_result.car_wheel_base - 2.7) << " " << out_info.plc_border_miny();
  531. if (t_center_y - 4.80 + 0.5 * (measure_result.car_wheel_base - 2.7) > out_info.plc_border_maxy() - 0.010 || // 前轮无法抱到
  532. t_center_y - 4.80 - 0.5 * (measure_result.car_wheel_base - 2.7) > out_info.plc_border_miny() - 0.010) { // 后轮无法抱到
  533. last_range_statu |= Range_status::Range_back; // 后超界
  534. }
  535. // 前进距离
  536. measure_result.forward_dis = MAX((t_center_y - 4.80 + 0.5 * (measure_result.car_wheel_base - 2.7) - (out_info.plc_border_maxy() - 0.010)),
  537. (t_center_y - 4.80 - 0.5 * (measure_result.car_wheel_base - 2.7) - (out_info.plc_border_miny() - 0.010)));
  538. return last_range_statu;
  539. }
  540. Error_manager GroundRegion::update_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud) {
  541. // 限定锁区域,解决因条件变量在析构时无法获得内部mutex导致此互斥锁卡住,造成死锁无法结束程序的问题。
  542. {
  543. std::lock_guard<std::mutex> lck(m_cloud_collection_mutex);
  544. mp_cloud_collection = cloud;
  545. DLOG(WARNING) << "update region cloud size: " << mp_cloud_collection->size() << ",,, input size: "
  546. << cloud->size();
  547. m_cloud_collection_time = std::chrono::system_clock::now();
  548. }
  549. m_measure_condition.notify_one(false, true);
  550. return SUCCESS;
  551. }
  552. void GroundRegion::thread_measure_func() {
  553. LOG(INFO) << " GroundRegion::thread_measure_func() start " << this;
  554. #if OPTION_ENABLE_DATA_FROM_LOCAL
  555. pcl::PointCloud<pcl::PointXYZ>::Ptr read_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  556. ReadTxtCloud(ETC_PATH"MeasureNodeAlgTest/data/" + std::to_string(m_region.region_id()) + "/total.txt", read_cloud);
  557. #endif
  558. while (m_measure_condition.is_alive()) {
  559. m_measure_condition.wait();
  560. // if (m_region.region_id() != 3118) {
  561. // std::this_thread::sleep_for(std::chrono::milliseconds(1000));
  562. // continue;
  563. // }
  564. if (m_measure_condition.is_alive()) {
  565. m_region_status = E_BUSY;
  566. Error_manager ec = Error_code::FAILED;
  567. detect_wheel_ceres3d::Detect_result t_result{};
  568. mp_cloud_collection->clear();
  569. #if OPTION_ENABLE_DATA_FROM_LOCAL
  570. pcl::copyPointCloud(*read_cloud, *mp_cloud_collection);
  571. #else
  572. for (auto &lidar_ext: m_region.lidar_exts()) {
  573. CloudDataMqttAsync::instance()->getCloudData("rslidar/" + std::to_string(lidar_ext.lidar_id()), mp_cloud_collection);
  574. }
  575. #endif
  576. // LOG(INFO) << "thread_measure_func is running: " << mp_cloud_collection->size();
  577. // continue;
  578. ec = detect(mp_cloud_collection, t_result);
  579. m_pose_record = t_result;
  580. if (ec == SUCCESS) {
  581. LOG(WARNING) << m_region.region_id() << " detect result: " << t_result.to_string();
  582. } else {
  583. if (ec != VELODYNE_REGION_EMPTY_CLOUD) {
  584. LOG(ERROR) << m_region.region_id() << " detect result: " << t_result.to_string();
  585. }
  586. }
  587. }
  588. m_region_status = E_READY;
  589. }
  590. LOG(INFO) << " GroundRegion::thread_measure_func() end " << this;
  591. }
  592. void GroundRegion::getMSE(MemoryBox<double> &box, float &value) {;
  593. std::vector<float> values;
  594. auto infos = box.get();
  595. for (auto &info: infos) {
  596. if (isnan(info.second)) {
  597. continue;
  598. }
  599. values.emplace_back(info.second);
  600. }
  601. if (values.size() > 4) {
  602. double mse = MSE(values, 2);
  603. if (isnan(mse)) {
  604. value = mean(values);
  605. } else {
  606. value = mse;
  607. }
  608. }
  609. }
  610. bool GroundRegion::CompareCeresResult(detect_wheel_ceres3d::Detect_result &first, detect_wheel_ceres3d::Detect_result &second) {
  611. bool radio_cx = fabs(first.cx - second.cx) < 0.01;
  612. bool radio_cy = fabs(first.cy - second.cy) < 0.03;
  613. bool radio_th = fabs(first.theta - second.theta) < 0.4;
  614. bool radio_wb = fabs(first.wheel_base - second.wheel_base) < 0.025;
  615. bool radio_wwd = true;//fabs(first.wheel_width - second.wheel_width) <0.0;
  616. bool radio_fth = fabs(first.front_theta - second.front_theta) < 4;
  617. return (radio_cx && radio_cy && radio_th && radio_wb && radio_wwd && radio_fth);
  618. }