ground_region.cpp 48 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090
  1. //
  2. // Created by zx on 2021/5/20.
  3. //
  4. #include "ground_region.h"
  5. #include <pcl/common/transforms.h>
  6. #include <pcl/filters/statistical_outlier_removal.h>
  7. #include <pcl/filters/voxel_grid.h>
  8. #include <pcl/segmentation/extract_clusters.h>
  9. #include <fcntl.h>
  10. #include "../tool/point_tool.h"
  11. // 测量结果滤波,不影响现有结构
  12. #include "../tool/measure_filter.h"
  13. // 增加车辆停止状态判断
  14. #include "../tool/region_status_checker.h"
  15. #include "../system/system_communication_mq.h"
  16. //欧式聚类*******************************************************
  17. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> Ground_region::segmentation(pcl::PointCloud<pcl::PointXYZ>::Ptr sor_cloud)
  18. {
  19. std::vector<pcl::PointIndices> ece_inlier;
  20. pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>);
  21. pcl::EuclideanClusterExtraction<pcl::PointXYZ> ece;
  22. ece.setInputCloud(sor_cloud);
  23. ece.setClusterTolerance(0.07);
  24. ece.setMinClusterSize(20);
  25. ece.setMaxClusterSize(20000);
  26. ece.setSearchMethod(tree);
  27. ece.extract(ece_inlier);
  28. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation_clouds;
  29. for (int i = 0; i < ece_inlier.size(); i++)
  30. {
  31. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_copy(new pcl::PointCloud<pcl::PointXYZ>);
  32. std::vector<int> ece_inlier_ext = ece_inlier[i].indices;
  33. copyPointCloud(*sor_cloud, ece_inlier_ext, *cloud_copy); //按照索引提取点云数据
  34. segmentation_clouds.push_back(cloud_copy);
  35. }
  36. return segmentation_clouds;
  37. }
  38. // /**
  39. // * @description: distance between two points
  40. // * @param {Point2f} p1
  41. // * @param {Point2f} p2
  42. // * @return the distance
  43. // */
  44. // double Ground_region::distance(cv::Point2f p1, cv::Point2f p2)
  45. // {
  46. // return sqrt(pow(p1.x - p2.x, 2.0) + pow(p1.y - p2.y, 2.0));
  47. // }
  48. /**
  49. * @description: point rectangle detect
  50. * @param points detect if points obey the rectangle rule
  51. * @return wether forms a rectangle
  52. */
  53. bool Ground_region::isRect(std::vector<cv::Point2f> &points)
  54. {
  55. if (points.size() == 4)
  56. {
  57. double L[3] = {0.0};
  58. L[0] = distance(points[0], points[1]);
  59. L[1] = distance(points[1], points[2]);
  60. L[2] = distance(points[0], points[2]);
  61. double max_l = L[0];
  62. double l1 = L[1];
  63. double l2 = L[2];
  64. cv::Point2f ps = points[0], pt = points[1];
  65. cv::Point2f pc = points[2];
  66. for (int i = 1; i < 3; ++i)
  67. {
  68. if (L[i] > max_l)
  69. {
  70. max_l = L[i];
  71. l1 = L[abs(i + 1) % 3];
  72. l2 = L[abs(i + 2) % 3];
  73. ps = points[i % 3];
  74. pt = points[(i + 1) % 3];
  75. pc = points[(i + 2) % 3];
  76. }
  77. }
  78. //直角边与坐标轴的夹角 <20°
  79. float thresh = 20.0 * M_PI / 180.0;
  80. cv::Point2f vct(pt.x - pc.x, pt.y - pc.y);
  81. float angle = atan2(vct.y, vct.x);
  82. if (!(fabs(angle) < thresh || (M_PI_2 - fabs(angle) < thresh)))
  83. {
  84. //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
  85. return false;
  86. }
  87. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  88. if (fabs(cosa) >= 0.15)
  89. {
  90. /*char description[255]={0};
  91. sprintf(description,"angle cos value(%.2f) >0.13 ",cosa);
  92. std::cout<<description<<std::endl;*/
  93. return false;
  94. }
  95. float width = std::min(l1, l2);
  96. float length = std::max(l1, l2);
  97. if (width < 1.400 || width > 1.900 || length > 3.300 || length < 2.200)
  98. {
  99. /*char description[255]={0};
  100. sprintf(description,"width<1400 || width >1900 || length >3300 ||length < 2200 l:%.1f,w:%.1f",length,width);
  101. std::cout<<description<<std::endl;*/
  102. return false;
  103. }
  104. double d = distance(pc, points[3]);
  105. cv::Point2f center1 = (ps + pt) * 0.5;
  106. cv::Point2f center2 = (pc + points[3]) * 0.5;
  107. if (fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150)
  108. {
  109. /*std::cout << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2<<std::endl;
  110. char description[255]={0};
  111. sprintf(description,"Verify failed-4 fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150 ");
  112. std::cout<<description<<std::endl;*/
  113. return false;
  114. }
  115. //std::cout << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2<<std::endl;
  116. return true;
  117. }
  118. else if (points.size() == 3)
  119. {
  120. double L[3] = {0.0};
  121. L[0] = distance(points[0], points[1]);
  122. L[1] = distance(points[1], points[2]);
  123. L[2] = distance(points[0], points[2]);
  124. double max_l = L[0];
  125. double l1 = L[1];
  126. double l2 = L[2];
  127. int max_index = 0;
  128. cv::Point2f ps = points[0], pt = points[1];
  129. cv::Point2f pc = points[2];
  130. for (int i = 1; i < 3; ++i)
  131. {
  132. if (L[i] > max_l)
  133. {
  134. max_index = i;
  135. max_l = L[i];
  136. l1 = L[abs(i + 1) % 3];
  137. l2 = L[abs(i + 2) % 3];
  138. ps = points[i % 3];
  139. pt = points[(i + 1) % 3];
  140. pc = points[(i + 2) % 3];
  141. }
  142. }
  143. //直角边与坐标轴的夹角 <20°
  144. float thresh = 20.0 * M_PI / 180.0;
  145. cv::Point2f vct(pt.x - pc.x, pt.y - pc.y);
  146. float angle = atan2(vct.y, vct.x);
  147. if (!(fabs(angle) < thresh || (M_PI_2 - fabs(angle) < thresh)))
  148. {
  149. //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
  150. return false;
  151. }
  152. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  153. if (fabs(cosa) >= 0.15)
  154. {
  155. /*char description[255]={0};
  156. sprintf(description,"3 wheels angle cos value(%.2f) >0.13 ",cosa);
  157. std::cout<<description<<std::endl;*/
  158. return false;
  159. }
  160. double l = std::max(l1, l2);
  161. double w = std::min(l1, l2);
  162. if (l > 2.100 && l < 3.300 && w > 1.400 && w < 2.100)
  163. {
  164. //生成第四个点
  165. cv::Point2f vec1 = ps - pc;
  166. cv::Point2f vec2 = pt - pc;
  167. cv::Point2f point4 = (vec1 + vec2) + pc;
  168. points.push_back(point4);
  169. /*char description[255]={0};
  170. sprintf(description,"3 wheels rectangle cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  171. std::cout<<description<<std::endl;*/
  172. return true;
  173. }
  174. else
  175. {
  176. /*char description[255]={0};
  177. sprintf(description,"3 wheels rectangle verify Failed cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  178. std::cout<<description<<std::endl;*/
  179. return false;
  180. }
  181. }
  182. //std::cout<<" default false"<<std::endl;
  183. return false;
  184. }
  185. /**
  186. * @description: 3d wheel detect core func
  187. * @param cloud input cloud for measure
  188. * @param thresh_z z value to cut wheel
  189. * @param result detect result
  190. * @return wether successfully detected
  191. */
  192. bool Ground_region::classify_ceres_detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double thresh_z,
  193. detect_wheel_ceres3d::Detect_result &result)
  194. {
  195. if (m_detector == nullptr)
  196. return false;
  197. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  198. for (int i = 0; i < cloud->size(); ++i)
  199. {
  200. pcl::PointXYZ pt = cloud->points[i];
  201. if (pt.z < thresh_z)
  202. {
  203. cloud_filtered->push_back(pt);
  204. }
  205. }
  206. //下采样
  207. pcl::VoxelGrid<pcl::PointXYZ> vox; //创建滤波对象
  208. vox.setInputCloud(cloud_filtered); //设置需要过滤的点云给滤波对象
  209. vox.setLeafSize(0.01f, 0.01f, 0.01f); //设置滤波时创建的体素体积为1cm的立方体
  210. vox.filter(*cloud_filtered); //执行滤波处理,存储输出
  211. if (cloud_filtered->size() == 0)
  212. {
  213. return false;
  214. }
  215. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor; //创建滤波器对象
  216. sor.setInputCloud(cloud_filtered); //设置待滤波的点云
  217. sor.setMeanK(5); //设置在进行统计时考虑的临近点个数
  218. sor.setStddevMulThresh(3.0); //设置判断是否为离群点的阀值,用来倍乘标准差,也就是上面的std_mul
  219. sor.filter(*cloud_filtered); //滤波结果存储到cloud_filtered
  220. if (cloud_filtered->size() == 0)
  221. {
  222. return false;
  223. }
  224. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> seg_clouds;
  225. seg_clouds = segmentation(cloud_filtered);
  226. if (!(seg_clouds.size() == 4 || seg_clouds.size() == 3))
  227. {
  228. return false;
  229. }
  230. std::vector<cv::Point2f> centers;
  231. cv::Point2f temp_centers(0,0);
  232. for (int i = 0; i < seg_clouds.size(); ++i)
  233. {
  234. Eigen::Vector4f centroid;
  235. pcl::compute3DCentroid(*seg_clouds[i], centroid);
  236. centers.push_back(cv::Point2f(centroid[0], centroid[1]));
  237. temp_centers += cv::Point2f(centroid[0], centroid[1]);
  238. }
  239. temp_centers /= 4.0f;
  240. bool ret = isRect(centers);
  241. if (ret)
  242. {
  243. std::string error_str;
  244. // LOG(WARNING) << "region id: "<< m_region.region_id();
  245. if (m_detector->detect(seg_clouds, result, error_str))
  246. {
  247. return true;
  248. }
  249. else
  250. {
  251. // LOG(WARNING) << error_str;
  252. return false;
  253. }
  254. }
  255. return ret;
  256. }
  257. // constructor
  258. Ground_region::Ground_region()
  259. {
  260. m_region_status = E_UNKNOWN;
  261. m_detector = nullptr;
  262. m_measure_thread = nullptr;
  263. }
  264. // deconstructor
  265. Ground_region::~Ground_region()
  266. {
  267. // LOG(WARNING) << "start deconstruct ground region";
  268. if (m_measure_thread)
  269. {
  270. m_measure_condition.kill_all();
  271. // Close Capturte Thread
  272. if (m_measure_thread->joinable())
  273. {
  274. m_measure_thread->join();
  275. delete m_measure_thread;
  276. m_measure_thread = nullptr;
  277. }
  278. }
  279. // LOG(WARNING) << "thread released";
  280. // 将创建的检测器析构
  281. if(m_detector)
  282. {
  283. delete m_detector;
  284. m_detector = nullptr;
  285. }
  286. Region_status_checker::get_instance_references().Region_status_checker_uninit();
  287. // LOG(WARNING) << "detector released";
  288. }
  289. Error_manager Ground_region::init(velodyne::Region region, pcl::PointCloud<pcl::PointXYZ>::Ptr left_model, pcl::PointCloud<pcl::PointXYZ>::Ptr right_model)
  290. {
  291. m_range_status_last = 0;
  292. Region_status_checker::get_instance_references().Region_status_checker_init();
  293. m_region = region;
  294. m_detector = new detect_wheel_ceres3d(left_model,right_model);
  295. mp_cloud_collection = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  296. mp_cloud_filtered = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  297. mp_cloud_detect_z = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  298. m_measure_thread = new std::thread(&Ground_region::thread_measure_func, this);
  299. m_measure_condition.reset();
  300. m_region_status = E_READY;
  301. return SUCCESS;
  302. }
  303. // 计算均方误差
  304. bool computer_var(std::vector<double> data, double &var)
  305. {
  306. if (data.size() == 0)
  307. return false;
  308. Eigen::VectorXd dis_vec(data.size());
  309. for (int i = 0; i < data.size(); ++i)
  310. {
  311. dis_vec[i] = data[i];
  312. }
  313. double mean = dis_vec.mean();
  314. Eigen::VectorXd mean_vec(data.size());
  315. Eigen::VectorXd mat = dis_vec - (mean_vec.setOnes() * mean);
  316. Eigen::MatrixXd result = (mat.transpose()) * mat;
  317. var = sqrt(result(0) / double(data.size()));
  318. return true;
  319. }
  320. Error_manager Ground_region::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, detect_wheel_ceres3d::Detect_result &last_result)
  321. {
  322. // 1.*********点云合法性检验*********
  323. if (cloud->size() == 0){
  324. // 更新过滤点
  325. m_filtered_cloud_mutex.lock();
  326. mp_cloud_filtered->clear();
  327. m_filtered_cloud_mutex.unlock();
  328. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "no input point");
  329. }
  330. // 2.*********点云预处理*********
  331. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  332. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cut(new pcl::PointCloud<pcl::PointXYZ>);
  333. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_clean(new pcl::PointCloud<pcl::PointXYZ>);
  334. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  335. for (int i = 0; i < cloud->size(); ++i)
  336. {
  337. pcl::PointXYZ pt = cloud->points[i];
  338. if (pt.x > m_region.minx() && pt.x < m_region.maxx() && pt.y > m_region.miny() && pt.y < m_region.maxy() && pt.z > m_region.minz() && pt.z < m_region.maxz())
  339. {
  340. cloud_cut->push_back(pt);
  341. }
  342. }
  343. if(cloud_cut->size() <= 0)
  344. {
  345. // 更新过滤点
  346. m_filtered_cloud_mutex.lock();
  347. mp_cloud_filtered->clear();
  348. m_filtered_cloud_mutex.unlock();
  349. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "cut no point");
  350. }
  351. //下采样
  352. pcl::VoxelGrid<pcl::PointXYZ> vox; //创建滤波对象
  353. vox.setInputCloud(cloud_cut); //设置需要过滤的点云给滤波对象
  354. vox.setLeafSize(0.02f, 0.02f, 0.02f); //设置滤波时创建的体素体积为1cm的立方体
  355. vox.filter(*cloud_clean); //执行滤波处理,存储输出
  356. // cloud_filtered = cloud_clean;
  357. if (cloud_clean->size() == 0){
  358. // 更新过滤点
  359. m_filtered_cloud_mutex.lock();
  360. mp_cloud_filtered->clear();
  361. m_filtered_cloud_mutex.unlock();
  362. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "ApproximateVoxelGrid no point");
  363. }
  364. //离群点过滤
  365. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
  366. sor.setInputCloud(cloud_clean);
  367. sor.setMeanK(5); //K近邻搜索点个数
  368. sor.setStddevMulThresh(3.0); //标准差倍数
  369. sor.setNegative(false); //保留未滤波点(内点)
  370. sor.filter(*cloud_filtered); //保存滤波结果到cloud_filter
  371. if (cloud_filtered->size() == 0){
  372. // 更新过滤点
  373. m_filtered_cloud_mutex.lock();
  374. mp_cloud_filtered->clear();
  375. m_filtered_cloud_mutex.unlock();
  376. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "StatisticalOutlierRemoval no point");
  377. }
  378. // 更新过滤点
  379. m_filtered_cloud_mutex.lock();
  380. mp_cloud_filtered->clear();
  381. mp_cloud_filtered->operator+=(*cloud_filtered);
  382. m_filtered_cloud_mutex.unlock();
  383. // 3.*********位姿优化,获取中心xy与角度*********
  384. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_detect_z(new pcl::PointCloud<pcl::PointXYZ>);
  385. double car_pose_x, car_pose_y, car_pose_theta, car_pose_width, z_value=0.2;
  386. // if(!Car_pose_detector::get_instance_references().detect_pose(cloud_filtered, cloud_detect_z, car_pose_x, car_pose_y, car_pose_theta, car_pose_width, z_value, false))
  387. if(!Car_pose_detector::get_instance_references().detect_pose_mat(cloud_filtered, cloud_detect_z, car_pose_x, car_pose_y, car_pose_theta, false))
  388. {
  389. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, "find general car pose value failed.");
  390. }
  391. // LOG_IF(INFO, m_region.region_id() == 0) << "car pose :::: cx: " << car_pose_x+m_region.plc_offsetx() << ", cy: " << car_pose_y+m_region.plc_offsety() << ", theta: " << car_pose_theta*180.0/M_PI << std::endl;
  392. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  393. std::chrono::duration<double> time_used_bowl = std::chrono::duration_cast<std::chrono::duration<double>>(t2 - t1);
  394. // 4.*********xoz优化获取底盘高度*********
  395. // 重新取包含地面点的点云,用于底盘优化
  396. double z_solver_x = car_pose_x;
  397. double z_solver_y = car_pose_y;
  398. double z_solver_theta = car_pose_theta;
  399. double z_solver_width = 1.0;
  400. chassis_ceres_solver t_solver;
  401. // !!!重新筛选地面点并滤波,融入第一步位姿使用的滤波后点云,传入第二步获取底盘高度
  402. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_z_solver(new pcl::PointCloud<pcl::PointXYZ>);
  403. for (int i = 0; i < cloud->size(); ++i)
  404. {
  405. pcl::PointXYZ pt = cloud->points[i];
  406. if (pt.x > m_region.minx() && pt.x < m_region.maxx() && pt.y > m_region.miny() && pt.y < m_region.maxy() && pt.z <= m_region.minz())
  407. {
  408. cloud_z_solver->push_back(pt);
  409. }
  410. }
  411. if (cloud_z_solver->size() == 0){
  412. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "cloud z no point for outlier removal");
  413. }
  414. //离群点过滤
  415. sor.setInputCloud(cloud_z_solver);
  416. sor.setMeanK(5); //K近邻搜索点个数
  417. sor.setStddevMulThresh(3.0); //标准差倍数
  418. sor.setNegative(false); //保留未滤波点(内点)
  419. sor.filter(*cloud_z_solver); //保存滤波结果到cloud_filter
  420. // 补上车身与车轮点
  421. cloud_z_solver->operator+=(*mp_cloud_filtered);
  422. // 去中心,角度调正
  423. Car_pose_detector::get_instance_references().inv_trans_cloud(cloud_z_solver, z_solver_x, z_solver_y, z_solver_theta);
  424. if (cloud_z_solver->size() == 0)
  425. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NORMAL, "z solver no point");
  426. // 给予底盘z中心与高度初值
  427. double mid_z = 0.05, height = 0.08;
  428. z_solver_x = 0.0;
  429. // Error_manager ec = t_solver.solve(cloud_z_solver, z_solver_x, mid_z, z_solver_width, height);
  430. Error_manager ec = t_solver.solve_mat(cloud_z_solver, z_solver_x, mid_z, z_solver_width, height, false);
  431. // 切除大于height高度以外点,并显示width直线
  432. // 根据z值切原始点云
  433. // std::cout<<"before clip: "<<cloud_z_solver->size()<<std::endl;
  434. pcl::PassThrough<pcl::PointXYZ> pass;
  435. pass.setInputCloud(cloud_z_solver);
  436. pass.setFilterFieldName("z");
  437. pass.setFilterLimits(m_region.minz(), mid_z + height / 2.0);
  438. pass.setFilterLimitsNegative(false);
  439. pass.filter(*cloud_z_solver);
  440. // std::cout<<"after clip: "<<cloud_z_solver->size()<<std::endl;
  441. // // 车宽方向画线
  442. // for (double i = -3.0; i < 3.0; i+=0.02)
  443. // {
  444. // cloud_z_solver->push_back(pcl::PointXYZ(-width/2.0, i, 0));
  445. // cloud_z_solver->push_back(pcl::PointXYZ(width/2.0, i, 0));
  446. // }
  447. // std::cout << "\n------------------------------------ chassis z1: " << mid_z + height / 2.0 << ", mid z: "<< mid_z << std::endl;
  448. if(ec != SUCCESS)
  449. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NORMAL, "failed to find chassis z value.");
  450. std::chrono::steady_clock::time_point t3 = std::chrono::steady_clock::now();
  451. std::chrono::duration<double> time_used_block = std::chrono::duration_cast<std::chrono::duration<double>>(t3 - t2);
  452. // 更新z中间点
  453. m_detect_z_cloud_mutex.lock();
  454. mp_cloud_detect_z->clear();
  455. mp_cloud_detect_z->operator+=(*cloud_z_solver);
  456. m_detect_z_cloud_mutex.unlock();
  457. // 二分法存在错误弃用!!!直接使用底盘z值
  458. std::vector<detect_wheel_ceres3d::Detect_result> results;
  459. detect_wheel_ceres3d::Detect_result result;
  460. double chassis_z = mid_z + height / 2.0; // + 0.02;
  461. if(chassis_z > m_region.maxz() || chassis_z < m_region.minz())
  462. {
  463. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, (std::string("optimized chassis z value out of range: ")+std::to_string(chassis_z)).c_str());
  464. }
  465. bool ret = false;
  466. while (chassis_z > (mid_z - height / 2.0))
  467. {
  468. // LOG_IF(WARNING, m_region.region_id() == 0) << "chassis z: " << chassis_z << ", midz: " << mid_z - height / 2.0;
  469. // 初值中x使用第一步优化的值
  470. result.cx = car_pose_x;
  471. // 传入整车角度,用于准确判断轮宽,此处需要的是点云的角度,通常逆时针90度到x轴
  472. result.theta = -(M_PI_2 - car_pose_theta);
  473. ret = classify_ceres_detect(cloud_filtered, chassis_z, result);
  474. // changed by yct, 根据底盘z识别,失败则向下移动直至成功或超过底盘内空中点
  475. if(ret)
  476. {
  477. results.push_back(result);
  478. break;
  479. }else{
  480. chassis_z -= 0.01;
  481. }
  482. }
  483. // } while (fabs(center_z - last_center_z) > 0.01);
  484. std::chrono::steady_clock::time_point t4 = std::chrono::steady_clock::now();
  485. std::chrono::duration<double> time_used_div = std::chrono::duration_cast<std::chrono::duration<double>>(t4 - t3);
  486. // std::cout << "\n------------------------------------------------------------ " << std::to_string(time_used_bowl.count()) << " " << std::to_string(time_used_block.count()) << " " << std::to_string(time_used_div.count())<<" || "<< std::to_string(time_used_bowl.count()+time_used_block.count()+time_used_div.count())<< std::endl;
  487. if (results.size() == 0)
  488. {
  489. // std::cout << "\n-------- no result: " << std::endl;
  490. //LOG_IF(INFO, m_region.region_id() == 4) << "failed with midz, currz: " << mid_z << ", " << chassis_z;
  491. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, "3d wheel detect failed.");
  492. }
  493. else
  494. {
  495. // // 20201010, may lead to problem in chutian, uncomment in debug only
  496. // // changed by yct, save 3d wheel detect result.
  497. // static int save_debug = 0;
  498. // if (m_region.region_id() == 0 && save_debug++ == 5)
  499. // m_detector->save_debug_data("/home/zx/yct/chutian_measure_2021/build");
  500. // LOG_IF(INFO, m_region.region_id() == 4) << "detected with suitable z value: " << chassis_z;
  501. }
  502. /// to be
  503. float min_mean_loss = 1.0;
  504. for (int i = 0; i < results.size(); ++i)
  505. {
  506. detect_wheel_ceres3d::Detect_result result = results[i];
  507. std::vector<double> loss;
  508. loss.push_back(result.loss.lf_loss);
  509. loss.push_back(result.loss.rf_loss);
  510. loss.push_back(result.loss.lb_loss);
  511. loss.push_back(result.loss.rb_loss);
  512. double mean = (result.loss.lf_loss + result.loss.rf_loss + result.loss.lb_loss + result.loss.rb_loss) / 4.0;
  513. double var = -1.;
  514. computer_var(loss, var);
  515. if (mean < min_mean_loss)
  516. {
  517. last_result = result;
  518. min_mean_loss = mean;
  519. }
  520. }
  521. // printf("z : %.3f angle : %.3f front : %.3f wheel_base:%.3f,width:%.3f, mean:%.5f\n",
  522. // center_z, last_result.theta, last_result.front_theta, last_result.wheel_base, last_result.width,
  523. // min_mean_loss);
  524. // std::cout << "\n-------- final z: " << chassis_z << std::endl;
  525. // std::cout << "cx: " << last_result.cx << ", cy: " << last_result.cy << ", theta: " << last_result.theta
  526. // << ", front: " << last_result.front_theta << ", wheelbase: " << last_result.wheel_base << ", width: " << last_result.width << std::endl << std::endl;
  527. // last_result.cx -= x;
  528. // last_result.cy -= y;
  529. // last_result.theta -= theta;
  530. // 角度校验,理论上car pose检测使用车身点云,应与车轮点云识别得到的车身 x偏移(0.035)与角度(<1°)一致
  531. double car_pose_theta_deg = 90 - car_pose_theta * 180.0 / M_PI;
  532. if (fabs(car_pose_x - last_result.cx) > 0.035 || fabs(car_pose_theta_deg - last_result.theta) > 1)
  533. {
  534. char valid_info[255];
  535. sprintf(valid_info, "validation failed for x and theta, carpose: (%.3f, %.3f), result: (%.3f, %.3f)", car_pose_x, car_pose_theta_deg, last_result.cx, last_result.theta);
  536. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, valid_info);
  537. }
  538. // 车宽精度优化
  539. {
  540. pcl::PointCloud<pcl::PointXYZ>::Ptr t_width_extract_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  541. t_width_extract_cloud->operator+=(m_detector->m_left_front_cloud);
  542. t_width_extract_cloud->operator+=(m_detector->m_right_front_cloud);
  543. t_width_extract_cloud->operator+=(m_detector->m_left_rear_cloud);
  544. t_width_extract_cloud->operator+=(m_detector->m_right_rear_cloud);
  545. //离群点过滤
  546. sor.setInputCloud(t_width_extract_cloud);
  547. sor.setMeanK(5); //K近邻搜索点个数
  548. sor.setStddevMulThresh(1.0); //标准差倍数
  549. sor.setNegative(false); //保留未滤波点(内点)
  550. sor.filter(*t_width_extract_cloud); //保存滤波结果到cloud_filter
  551. Eigen::Affine3d t_affine = Eigen::Affine3d::Identity();
  552. t_affine.prerotate(Eigen::AngleAxisd((90 - last_result.theta) * M_PI / 180.0, Eigen::Vector3d::UnitZ()));
  553. pcl::transformPointCloud(*t_width_extract_cloud, *t_width_extract_cloud, t_affine.matrix());
  554. // 车宽重计算,并赋值到当前车宽
  555. pcl::PointXYZ t_min_p, t_max_p;
  556. pcl::getMinMax3D(*t_width_extract_cloud, t_min_p, t_max_p);
  557. double accurate_width = t_max_p.x - t_min_p.x;
  558. last_result.width = accurate_width;
  559. // !!!暂时不限制宽度数据
  560. // char valid_info[255];
  561. // sprintf(valid_info, "validation for car width, origin/accurate: (%.3f, %.3f)", last_result.width, accurate_width);
  562. // // 允许一边5cm误差,且保证车宽应比车轮识别计算出的大,否则为错误宽度数据
  563. // if (accurate_width - last_result.width > 0.1 || accurate_width < last_result.width)
  564. // {
  565. // return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, valid_info);
  566. // }
  567. // if (m_region.region_id() == 0 || m_region.region_id() == 4)
  568. // {
  569. // LOG(WARNING) << valid_info;
  570. // // 保存车宽数据,统计用
  571. // if (m_file_out.is_open())
  572. // m_file_out << std::setprecision(5) << std::to_string(1.883) << "," << last_result.width << "," << accurate_width << std::endl;
  573. // }
  574. }
  575. // LOG_IF(INFO, m_region.region_id() == 4) << last_result.to_string();
  576. return SUCCESS;
  577. }
  578. int Ground_region::outOfRangeDetection(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double cx, double cy, double plate_cx, double plate_cy, double theta)
  579. {
  580. // LOG(WARNING) << m_range_status_last;
  581. if(cloud->size() <= 0)
  582. return Range_status::Range_correct;
  583. int res = Range_status::Range_correct;
  584. // 计算转盘旋转后点云坐标
  585. double theta_rad = theta * M_PI / 180.0;
  586. pcl::PointCloud<pcl::PointXYZ> t_cloud;
  587. for (size_t i = 0; i < cloud->size(); i++)
  588. {
  589. Eigen::Vector2d t_point(cloud->points[i].x - plate_cx, cloud->points[i].y - plate_cy);
  590. pcl::PointXYZ t_pcl_point;
  591. t_pcl_point.x = (t_point.x() * cos(theta_rad) - t_point.y() * sin(theta_rad)) + plate_cx;
  592. t_pcl_point.y = (t_point.x() * sin(theta_rad) + t_point.y() * cos(theta_rad)) + plate_cy;
  593. t_pcl_point.z = cloud->points[i].z;
  594. t_cloud.push_back(t_pcl_point);
  595. }
  596. pcl::PointXYZ min_p, max_p;
  597. pcl::getMinMax3D(t_cloud, min_p, max_p);
  598. #ifndef ANTI_SHAKE
  599. // 判断左右超界情况
  600. if(min_p.x < m_region.border_minx())
  601. res |= Range_status::Range_left;
  602. if(max_p.x > m_region.border_maxx())
  603. res |= Range_status::Range_right;
  604. // LOG_IF(WARNING, m_region.region_id() == 4)<< "border minmax x: "<< min_p.x<<", "<<max_p.x<<", res: "<<res;
  605. return res;
  606. #else
  607. /*
  608. if(min_p.x < m_region.border_minx()-0.000)
  609. {
  610. m_range_status_last |= Range_status::Range_left;
  611. }
  612. else if(min_p.x > m_region.border_minx()+0.010)
  613. {
  614. int t = Range_status::Range_left;
  615. m_range_status_last &= (~t);
  616. }
  617. //else m_range_status_last no change
  618. if(max_p.x > m_region.border_maxx()+0.000)
  619. {
  620. m_range_status_last |= Range_status::Range_right;
  621. }
  622. else if(max_p.x < m_region.border_maxx()-0.010)
  623. {
  624. int t = Range_status::Range_right;
  625. m_range_status_last &= (~t);
  626. }
  627. //else m_range_status_last no change
  628. */
  629. //huli 不再使用汽车左右边界来判断,直接使用中心点x值判断左右超界。
  630. //plc坐标,1 3 5入口x为-1.8左右, 2 4 6入口为1.8左右
  631. //要求x取值范围,1650~2150左右
  632. float t_center_x = cx + m_region.plc_offsetx();
  633. if(t_center_x < m_region.border_minx()-0.000)
  634. {
  635. m_range_status_last |= Range_status::Range_left;
  636. }
  637. else if(t_center_x > m_region.border_minx()+0.010)
  638. {
  639. int t = Range_status::Range_left;
  640. m_range_status_last &= (~t);
  641. }
  642. //else m_range_status_last no change
  643. if(t_center_x > m_region.border_maxx()+0.000)
  644. {
  645. m_range_status_last |= Range_status::Range_right;
  646. }
  647. else if(t_center_x < m_region.border_maxx()-0.010)
  648. {
  649. int t = Range_status::Range_right;
  650. m_range_status_last &= (~t);
  651. }
  652. //else m_range_status_last no change
  653. // LOG(WARNING) << "-------------------------------------------------------" <<std::endl;
  654. // LOG(WARNING) << "min_p.x = " << min_p.x <<std::endl;
  655. // LOG(WARNING) << "max_p.x = " << max_p.x <<std::endl;
  656. // LOG(WARNING) << "t_center_x = " << t_center_x <<std::endl;
  657. // LOG(WARNING) << "+++++++++++++++++++++++++++++++++++++++++++++++++++++++" <<std::endl;
  658. return m_range_status_last;
  659. #endif //ANTI_SHAKE
  660. }
  661. int Ground_region::outOfRangeDetection(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, Common_data::Car_wheel_information measure_result, double plate_cx, double plate_cy, double theta)
  662. {
  663. int res = Range_status::Range_correct;
  664. if(cloud->size() <= 0)
  665. return res;
  666. // 计算转盘旋转后车辆中心点坐标
  667. Eigen::Vector2d car_center(measure_result.car_center_x, measure_result.car_center_y);
  668. Eigen::Vector2d car_uniform_center;
  669. double theta_rad = theta * M_PI / 180.0;
  670. car_uniform_center.x() = car_center.x() * cos(theta_rad) - car_center.y() * sin(theta_rad);
  671. car_uniform_center.y() = car_center.x() * sin(theta_rad) + car_center.y() * cos(theta_rad);
  672. #ifndef ANTI_SHAKE
  673. // 车位位于y负方向,判断后轮超界情况
  674. //yct old program 20221101
  675. // double rear_wheel_y = car_uniform_center.y() + m_region.plc_offsety() - 0.5 * measure_result.car_wheel_base;
  676. // if(rear_wheel_y < m_region.plc_border_miny())
  677. // {
  678. // res |= Range_status::Range_back;
  679. // }
  680. //huli new program 20221101
  681. double t_center_y = 0.0 - (car_uniform_center.y() + m_region.plc_offsety()); // 汽车中心y, 参照plc坐标,并且进行偏移, 绝对值。结果大约为 5~6左右
  682. if( t_center_y - 4.88 + 0.5*(measure_result.car_wheel_base - 2.7) < m_region.plc_border_maxy() &&
  683. t_center_y - 4.88 - 0.5*(measure_result.car_wheel_base - 2.7) < m_region.plc_border_miny() )
  684. {
  685. //normal
  686. } else
  687. {
  688. res |= Range_status::Range_back;
  689. }
  690. // 判断车辆宽度超界情况
  691. if (measure_result.car_wheel_width < m_region.car_min_width() || measure_result.car_wheel_width > m_region.car_max_width())
  692. {
  693. res |= Range_status::Range_car_width;
  694. }
  695. // 判断车辆轴距超界情况
  696. if (measure_result.car_wheel_base < m_region.car_min_wheelbase() || measure_result.car_wheel_base > m_region.car_max_wheelbase())
  697. {
  698. res |= Range_status::Range_car_wheelbase;
  699. }
  700. //yct old program 20221103 , 使用 velodyne_manager.prototxt 里面的 turnplate_angle_limit 来做边界判断
  701. // 判断车辆旋转角超界情况
  702. // double dtheta = 90-measure_result.car_angle;
  703. // if (dtheta > m_region.turnplate_angle_limit_anti_clockwise())
  704. // {
  705. // res |= Range_status::Range_angle_clock;
  706. // }
  707. // if (dtheta < -m_region.turnplate_angle_limit_clockwise())
  708. // {
  709. // res |= Range_status::Range_angle_anti_clock;
  710. // }
  711. //huli new program 20221103, 使用 plc dispatch_1_statu_port 里面的 来做边界判断
  712. // double t_dtheta = 90-measure_result.car_angle; // 车身的旋转角, 修正到正负5度,
  713. double t_dtheta = measure_result.car_angle + m_region.plc_offset_degree(); // 车身的旋转角, 修正到正5度, (m_region.plc_offset_degree():-89)
  714. int t_terminal_id = m_region.region_id() +1; //region_id:0~5, terminal_id:1~6
  715. //turnplate_angle_min = -5, turnplate_angle_max = 5,
  716. if (t_dtheta > System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_max())
  717. {
  718. res |= Range_status::Range_angle_anti_clock;
  719. }
  720. if (t_dtheta < System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_min())
  721. {
  722. res |= Range_status::Range_angle_clock;
  723. }
  724. // // 判断车辆前轮角回正情况
  725. // if (fabs(measure_result.car_front_theta) > 8.0)
  726. // {
  727. // res |= Range_status::Range_steering_wheel_nozero;
  728. // }
  729. res |= outOfRangeDetection(cloud, plate_cx, plate_cy, theta);
  730. return res;
  731. #else
  732. // LOG(WARNING) << m_range_status_last;
  733. // 车位位于y负方向,判断后轮超界情况
  734. double t_center_y = 0.0 - (car_uniform_center.y() + m_region.plc_offsety()); // 汽车中心y, 参照plc坐标,并且进行偏移, 绝对值。结果大约为 5~6左右
  735. if( t_center_y - 4.88 + 0.5*(measure_result.car_wheel_base - 2.7) < m_region.plc_border_maxy()-0.000 &&
  736. t_center_y - 4.88 - 0.5*(measure_result.car_wheel_base - 2.7) < m_region.plc_border_miny()-0.000 )
  737. {
  738. int t = Range_status::Range_back;
  739. m_range_status_last &= (~t);
  740. }
  741. else if( t_center_y - 4.88 + 0.5*(measure_result.car_wheel_base - 2.7) > m_region.plc_border_maxy()+0.010 ||
  742. t_center_y - 4.88 - 0.5*(measure_result.car_wheel_base - 2.7) > m_region.plc_border_miny()+0.010 )
  743. {
  744. m_range_status_last |= Range_status::Range_back;
  745. }
  746. //else m_range_status_last no change
  747. // LOG(WARNING) << m_range_status_last;
  748. // 判断车辆宽度超界情况
  749. if (measure_result.car_wheel_width < m_region.car_min_width()-0.000 ||
  750. measure_result.car_wheel_width > m_region.car_max_width()+0.000)
  751. {
  752. m_range_status_last |= Range_status::Range_car_width;
  753. }
  754. else if (measure_result.car_wheel_width > m_region.car_min_width()+0.010 &&
  755. measure_result.car_wheel_width < m_region.car_max_width()-0.010)
  756. {
  757. int t = Range_status::Range_car_width;
  758. m_range_status_last &= (~t);
  759. }
  760. //else m_range_status_last no change
  761. // LOG(WARNING) << m_range_status_last;
  762. // 判断车辆轴距超界情况
  763. if (measure_result.car_wheel_base < m_region.car_min_wheelbase()-0.000 ||
  764. measure_result.car_wheel_base > m_region.car_max_wheelbase()+0.000)
  765. {
  766. res |= Range_status::Range_car_wheelbase;
  767. }
  768. else if (measure_result.car_wheel_base > m_region.car_min_wheelbase()+0.010 ||
  769. measure_result.car_wheel_base < m_region.car_max_wheelbase()-0.010)
  770. {
  771. int t = Range_status::Range_car_wheelbase;
  772. m_range_status_last &= (~t);
  773. }
  774. //else m_range_status_last no change
  775. // LOG(WARNING) << m_range_status_last;
  776. // 判断车辆旋转角超界情况
  777. //huli new program 20221103, 使用 plc dispatch_1_statu_port 里面的 来做边界判断
  778. // double t_dtheta = 90-measure_result.car_angle; // 车身的旋转角, 修正到正负5度,
  779. double t_dtheta = measure_result.car_angle + m_region.plc_offset_degree(); // 车身的旋转角, 修正到正5度, (m_region.plc_offset_degree():-89)
  780. int t_terminal_id = m_region.region_id() +1; //region_id:0~5, terminal_id:1~6
  781. //turnplate_angle_min = -5, turnplate_angle_max = 5,
  782. if (t_dtheta > System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_max()+0.00)
  783. {
  784. m_range_status_last |= Range_status::Range_angle_anti_clock;
  785. }
  786. else if (t_dtheta < System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_max()-0.10)
  787. {
  788. int t = Range_status::Range_angle_anti_clock;
  789. m_range_status_last &= (~t);
  790. }
  791. // LOG(WARNING) << m_range_status_last;
  792. //else m_range_status_last no change
  793. if (t_dtheta < System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_min()-0.00)
  794. {
  795. res |= Range_status::Range_angle_clock;
  796. }
  797. else if (t_dtheta > System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_min()+0.10)
  798. {
  799. int t = Range_status::Range_angle_clock;
  800. m_range_status_last &= (~t);
  801. }
  802. // LOG(WARNING) << m_range_status_last;
  803. // LOG(INFO) << t_dtheta<<", "<<System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_min()<<std::endl;
  804. //else m_range_status_last no change
  805. m_range_status_last |= outOfRangeDetection(cloud, measure_result.car_center_x, measure_result.car_center_y, plate_cx, plate_cy, theta);
  806. return m_range_status_last;
  807. #endif
  808. }
  809. //外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待
  810. Error_manager Ground_region::get_current_wheel_information(Common_data::Car_wheel_information *p_car_wheel_information, std::chrono::system_clock::time_point command_time)
  811. {
  812. if ( p_car_wheel_information == NULL )
  813. {
  814. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  815. " POINTER IS NULL ");
  816. }
  817. //获取指令时间之后的信息, 如果没有就会报错, 不会等待
  818. if( m_detect_update_time > command_time )
  819. {
  820. std::lock_guard<std::mutex> lck(m_car_result_mutex);
  821. *p_car_wheel_information = m_car_wheel_information;
  822. if(m_car_wheel_information.correctness)
  823. return Error_code::SUCCESS;
  824. else
  825. return Error_manager(Error_code::VELODYNE_REGION_CERES_SOLVE_ERROR, Error_level::MINOR_ERROR, " Ground_region detect error");
  826. }
  827. else
  828. {
  829. return Error_manager(Error_code::VELODYNE_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
  830. " Ground_region::get_current_wheel_information error ");
  831. }
  832. }
  833. //外部调用获取最新的车轮定位信息, 获取指令时间往前一个周期内的车轮定位信息, 如果没有就会报错, 不会等待
  834. Error_manager Ground_region::get_last_wheel_information(Common_data::Car_wheel_information *p_car_wheel_information, std::chrono::system_clock::time_point command_time)
  835. {
  836. if ( p_car_wheel_information == NULL )
  837. {
  838. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  839. " POINTER IS NULL ");
  840. }
  841. //获取指令时间之后的信息, 如果没有就会报错, 不会等待
  842. // LOG(WARNING) << std::chrono::duration_cast<std::chrono::milliseconds>(command_time-m_detect_update_time).count()/1000.0 <<", "
  843. // <<std::chrono::duration_cast<std::chrono::milliseconds>(command_time-m_cloud_collection_time).count()/1000.0;
  844. if( m_detect_update_time > command_time - std::chrono::milliseconds(GROUND_REGION_DETECT_CYCLE_MS))
  845. {
  846. std::lock_guard<std::mutex> lck(m_car_result_mutex);
  847. *p_car_wheel_information = m_car_wheel_information;
  848. if(m_car_wheel_information.correctness)
  849. return Error_code::SUCCESS;
  850. else
  851. return Error_manager(Error_code::VELODYNE_REGION_CERES_SOLVE_ERROR, Error_level::MINOR_ERROR, " Ground_region detect error");
  852. }
  853. else
  854. {
  855. return Error_manager(Error_code::VELODYNE_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
  856. " Ground_region::get_current_wheel_information error ");
  857. }
  858. }
  859. Error_manager Ground_region::update_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
  860. {
  861. // // 点云z转90度,调试用
  862. //Eigen::AngleAxisd rot_z = Eigen::AngleAxisd(M_PI_2, Eigen::Vector3d::UnitZ());
  863. //for (size_t i = 0; i < cloud->size(); i++)
  864. //{
  865. // Eigen::Vector3d t_point(cloud->points[i].x, cloud->points[i].y, cloud->points[i].z);
  866. // t_point = rot_z.toRotationMatrix() * t_point;
  867. // cloud->points[i].x = t_point.x();
  868. // cloud->points[i].y = t_point.y();
  869. // cloud->points[i].z = t_point.z();
  870. //}
  871. // 限定锁区域,解决因条件变量在析构时无法获得内部mutex导致此互斥锁卡住,造成死锁无法结束程序的问题。
  872. {
  873. std::lock_guard<std::mutex> lck(m_cloud_collection_mutex);
  874. mp_cloud_collection = cloud;
  875. // LOG(WARNING) << "update region cloud size: " << mp_cloud_collection->size() << ",,, input size: " << cloud->size();
  876. m_cloud_collection_time = std::chrono::system_clock::now();
  877. }
  878. m_measure_condition.notify_one(false, true);
  879. // std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  880. // std::chrono::duration<double> time_used_update = std::chrono::duration_cast<std::chrono::duration<double>>(t1 - t0);
  881. // std::cout << "update cloud time: " << time_used_update.count() << std::endl;
  882. return SUCCESS;
  883. }
  884. void Ground_region::thread_measure_func()
  885. {
  886. LOG(INFO) << " Ground_region::thread_measure_func() start " << this;
  887. while (m_measure_condition.is_alive())
  888. {
  889. m_measure_condition.wait();
  890. if (m_measure_condition.is_alive())
  891. {
  892. m_region_status = E_BUSY;
  893. detect_wheel_ceres3d::Detect_result t_result;
  894. Error_manager ec = detect(mp_cloud_collection, t_result);
  895. std::lock_guard<std::mutex> lck(m_car_result_mutex);
  896. m_detect_update_time = std::chrono::system_clock::now();
  897. // 增加滤波轴距
  898. Common_data::Car_wheel_information_stamped t_wheel_info_stamped;
  899. // 车辆移动检测
  900. Common_data::Car_wheel_information_stamped t_wheel_info_stamped_for_car_move;
  901. if (ec == SUCCESS)
  902. {
  903. m_car_wheel_information.correctness = true;
  904. m_car_wheel_information.car_center_x = t_result.cx;
  905. m_car_wheel_information.car_center_y = t_result.cy;
  906. m_car_wheel_information.car_angle = t_result.theta;
  907. m_car_wheel_information.car_wheel_base = t_result.wheel_base;
  908. m_car_wheel_information.car_wheel_width = t_result.width;
  909. m_car_wheel_information.car_front_theta = t_result.front_theta;
  910. // 220110 added by yct, single wheel width filtering
  911. m_car_wheel_information.single_wheel_width = t_result.single_wheel_width;
  912. m_car_wheel_information.single_wheel_length = t_result.single_wheel_length;
  913. m_car_wheel_information.theta_uniform(m_region.turnplate_cx(), m_region.turnplate_cy());
  914. // 超界校验
  915. {
  916. std::lock_guard<std::mutex> lck(m_filtered_cloud_mutex);
  917. int res = outOfRangeDetection(mp_cloud_filtered, m_car_wheel_information, m_region.turnplate_cx(), m_region.turnplate_cy(), 90.0 - t_result.theta);
  918. m_car_wheel_information.range_status = res;
  919. }
  920. // 添加plc偏移
  921. m_car_wheel_information.car_center_x += m_region.plc_offsetx();
  922. m_car_wheel_information.car_center_y += m_region.plc_offsety();
  923. m_car_wheel_information.uniform_car_x += m_region.plc_offsetx();
  924. m_car_wheel_information.uniform_car_y += m_region.plc_offsety();
  925. m_car_wheel_information.car_angle += m_region.plc_offset_degree();
  926. // LOG(INFO) << "yyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyy t_result.theta = " << t_result.theta << " ";
  927. // LOG(INFO) << "yyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyy m_region.plc_offset_degree() = " << m_region.plc_offset_degree() << " ";
  928. // LOG(INFO) << "yyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyy m_car_wheel_information.car_angle= " << m_car_wheel_information.car_angle << " ";
  929. t_wheel_info_stamped.wheel_data = m_car_wheel_information;
  930. t_wheel_info_stamped.measure_time = m_detect_update_time;
  931. Measure_filter::get_instance_references().update_data(m_region.region_id(), t_wheel_info_stamped);
  932. // 20211228 added by yct, car movement checking, human and door detection
  933. t_wheel_info_stamped_for_car_move = t_wheel_info_stamped;
  934. t_wheel_info_stamped_for_car_move.wheel_data.car_center_x -= m_region.plc_offsetx();
  935. t_wheel_info_stamped_for_car_move.wheel_data.car_center_y -= m_region.plc_offsety();
  936. t_wheel_info_stamped_for_car_move.wheel_data.uniform_car_x -= m_region.plc_offsetx();
  937. t_wheel_info_stamped_for_car_move.wheel_data.uniform_car_y -= m_region.plc_offsety();
  938. t_wheel_info_stamped_for_car_move.wheel_data.car_angle -= m_region.plc_offset_degree();
  939. Error_manager car_status_res = Region_status_checker::get_instance_references().get_region_parking_status(m_region.region_id(), t_wheel_info_stamped_for_car_move, *mp_cloud_filtered);
  940. // success means car stable
  941. if(car_status_res == SUCCESS)
  942. {
  943. m_car_wheel_information.range_status &= ~((int)Range_status::Range_car_moving);
  944. }else
  945. {
  946. m_car_wheel_information.range_status |= Range_status::Range_car_moving;
  947. // if(m_region.region_id()==4){
  948. // std::cout<<"success: "<<car_status_res.to_string()<<std::endl;
  949. // }
  950. }
  951. Region_status_checker::get_instance_references().add_measure_data(m_region.region_id(), t_wheel_info_stamped_for_car_move, *mp_cloud_filtered);
  952. ec = Measure_filter::get_instance_references().get_filtered_wheel_information(m_region.region_id(), t_wheel_info_stamped.wheel_data);
  953. if (ec == SUCCESS)
  954. {
  955. // 20221208 added by yct, use avg car angle and width data.
  956. // LOG(WARNING)<<m_region.region_id()<<" angles: "<<m_car_wheel_information.car_angle<<", "<<t_wheel_info_stamped.wheel_data.car_angle;
  957. // LOG(WARNING)<<m_region.region_id()<<" filter res: "<<t_wheel_info_stamped.wheel_data.to_string()<<std::endl;
  958. // m_car_wheel_information.car_angle = t_wheel_info_stamped.wheel_data.car_angle;
  959. // m_car_wheel_information.car_wheel_width = t_wheel_info_stamped.wheel_data.car_wheel_width;
  960. m_car_wheel_information.car_wheel_base = t_wheel_info_stamped.wheel_data.car_wheel_base;
  961. m_car_wheel_information.car_front_theta = t_wheel_info_stamped.wheel_data.car_front_theta;
  962. // 临时添加,滤波后前轮超界
  963. if(fabs(m_car_wheel_information.car_front_theta)>8.0)
  964. {
  965. m_car_wheel_information.range_status |= Range_status::Range_steering_wheel_nozero;
  966. }
  967. }
  968. // else{
  969. // std::cout<<ec.to_string()<<std::endl;
  970. // }
  971. // LOG_IF(INFO, m_region.region_id() == 1) << m_car_wheel_information.to_string();
  972. }
  973. else
  974. {
  975. m_car_wheel_information.correctness = false;
  976. // LOG_IF(ERROR, m_region.region_id() == 1) << ec.to_string();
  977. // 20211228 added by yct, car movement checking, human and door detection
  978. Error_manager car_status_res = Region_status_checker::get_instance_references().get_region_parking_status(m_region.region_id(), t_wheel_info_stamped_for_car_move, *mp_cloud_filtered);
  979. // success means car stable
  980. if(car_status_res == SUCCESS)
  981. {
  982. m_car_wheel_information.range_status &= ~((int)Range_status::Range_car_moving);
  983. }else
  984. {
  985. m_car_wheel_information.range_status |= Range_status::Range_car_moving;
  986. // if(m_region.region_id()==1){
  987. // std::cout<<"failed: "<<car_status_res.to_string()<<std::endl;
  988. // }
  989. }
  990. }
  991. }
  992. m_region_status = E_READY;
  993. }
  994. LOG(INFO) << " Ground_region::thread_measure_func() end " << this;
  995. }