ground_region.cpp 27 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683
  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. // 测量结果滤波,不影响现有结构
  11. #include "../tool/measure_filter.h"
  12. //欧式聚类*******************************************************
  13. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> Ground_region::segmentation(pcl::PointCloud<pcl::PointXYZ>::Ptr sor_cloud)
  14. {
  15. std::vector<pcl::PointIndices> ece_inlier;
  16. pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>);
  17. pcl::EuclideanClusterExtraction<pcl::PointXYZ> ece;
  18. ece.setInputCloud(sor_cloud);
  19. ece.setClusterTolerance(0.07);
  20. ece.setMinClusterSize(20);
  21. ece.setMaxClusterSize(20000);
  22. ece.setSearchMethod(tree);
  23. ece.extract(ece_inlier);
  24. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation_clouds;
  25. for (int i = 0; i < ece_inlier.size(); i++)
  26. {
  27. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_copy(new pcl::PointCloud<pcl::PointXYZ>);
  28. std::vector<int> ece_inlier_ext = ece_inlier[i].indices;
  29. copyPointCloud(*sor_cloud, ece_inlier_ext, *cloud_copy); //按照索引提取点云数据
  30. segmentation_clouds.push_back(cloud_copy);
  31. }
  32. return segmentation_clouds;
  33. }
  34. /**
  35. * @description: distance between two points
  36. * @param {Point2f} p1
  37. * @param {Point2f} p2
  38. * @return the distance
  39. */
  40. double Ground_region::distance(cv::Point2f p1, cv::Point2f p2)
  41. {
  42. return sqrt(pow(p1.x - p2.x, 2.0) + pow(p1.y - p2.y, 2.0));
  43. }
  44. /**
  45. * @description: point rectangle detect
  46. * @param points detect if points obey the rectangle rule
  47. * @return wether forms a rectangle
  48. */
  49. bool Ground_region::isRect(std::vector<cv::Point2f> &points)
  50. {
  51. if (points.size() == 4)
  52. {
  53. double L[3] = {0.0};
  54. L[0] = distance(points[0], points[1]);
  55. L[1] = distance(points[1], points[2]);
  56. L[2] = distance(points[0], points[2]);
  57. double max_l = L[0];
  58. double l1 = L[1];
  59. double l2 = L[2];
  60. cv::Point2f ps = points[0], pt = points[1];
  61. cv::Point2f pc = points[2];
  62. for (int i = 1; i < 3; ++i)
  63. {
  64. if (L[i] > max_l)
  65. {
  66. max_l = L[i];
  67. l1 = L[abs(i + 1) % 3];
  68. l2 = L[abs(i + 2) % 3];
  69. ps = points[i % 3];
  70. pt = points[(i + 1) % 3];
  71. pc = points[(i + 2) % 3];
  72. }
  73. }
  74. //直角边与坐标轴的夹角 <20°
  75. float thresh = 20.0 * M_PI / 180.0;
  76. cv::Point2f vct(pt.x - pc.x, pt.y - pc.y);
  77. float angle = atan2(vct.y, vct.x);
  78. if (!(fabs(angle) < thresh || (M_PI_2 - fabs(angle) < thresh)))
  79. {
  80. //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
  81. return false;
  82. }
  83. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  84. if (fabs(cosa) >= 0.15)
  85. {
  86. /*char description[255]={0};
  87. sprintf(description,"angle cos value(%.2f) >0.13 ",cosa);
  88. std::cout<<description<<std::endl;*/
  89. return false;
  90. }
  91. float width = std::min(l1, l2);
  92. float length = std::max(l1, l2);
  93. if (width < 1.400 || width > 1.900 || length > 3.300 || length < 2.200)
  94. {
  95. /*char description[255]={0};
  96. sprintf(description,"width<1400 || width >1900 || length >3300 ||length < 2200 l:%.1f,w:%.1f",length,width);
  97. std::cout<<description<<std::endl;*/
  98. return false;
  99. }
  100. double d = distance(pc, points[3]);
  101. cv::Point2f center1 = (ps + pt) * 0.5;
  102. cv::Point2f center2 = (pc + points[3]) * 0.5;
  103. if (fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150)
  104. {
  105. /*std::cout << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2<<std::endl;
  106. char description[255]={0};
  107. sprintf(description,"Verify failed-4 fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150 ");
  108. std::cout<<description<<std::endl;*/
  109. return false;
  110. }
  111. //std::cout << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2<<std::endl;
  112. return true;
  113. }
  114. else if (points.size() == 3)
  115. {
  116. double L[3] = {0.0};
  117. L[0] = distance(points[0], points[1]);
  118. L[1] = distance(points[1], points[2]);
  119. L[2] = distance(points[0], points[2]);
  120. double max_l = L[0];
  121. double l1 = L[1];
  122. double l2 = L[2];
  123. int max_index = 0;
  124. cv::Point2f ps = points[0], pt = points[1];
  125. cv::Point2f pc = points[2];
  126. for (int i = 1; i < 3; ++i)
  127. {
  128. if (L[i] > max_l)
  129. {
  130. max_index = i;
  131. max_l = L[i];
  132. l1 = L[abs(i + 1) % 3];
  133. l2 = L[abs(i + 2) % 3];
  134. ps = points[i % 3];
  135. pt = points[(i + 1) % 3];
  136. pc = points[(i + 2) % 3];
  137. }
  138. }
  139. //直角边与坐标轴的夹角 <20°
  140. float thresh = 20.0 * M_PI / 180.0;
  141. cv::Point2f vct(pt.x - pc.x, pt.y - pc.y);
  142. float angle = atan2(vct.y, vct.x);
  143. if (!(fabs(angle) < thresh || (M_PI_2 - fabs(angle) < thresh)))
  144. {
  145. //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
  146. return false;
  147. }
  148. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  149. if (fabs(cosa) >= 0.15)
  150. {
  151. /*char description[255]={0};
  152. sprintf(description,"3 wheels angle cos value(%.2f) >0.13 ",cosa);
  153. std::cout<<description<<std::endl;*/
  154. return false;
  155. }
  156. double l = std::max(l1, l2);
  157. double w = std::min(l1, l2);
  158. if (l > 2.100 && l < 3.300 && w > 1.400 && w < 2.100)
  159. {
  160. //生成第四个点
  161. cv::Point2f vec1 = ps - pc;
  162. cv::Point2f vec2 = pt - pc;
  163. cv::Point2f point4 = (vec1 + vec2) + pc;
  164. points.push_back(point4);
  165. /*char description[255]={0};
  166. sprintf(description,"3 wheels rectangle cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  167. std::cout<<description<<std::endl;*/
  168. return true;
  169. }
  170. else
  171. {
  172. /*char description[255]={0};
  173. sprintf(description,"3 wheels rectangle verify Failed cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  174. std::cout<<description<<std::endl;*/
  175. return false;
  176. }
  177. }
  178. //std::cout<<" default false"<<std::endl;
  179. return false;
  180. }
  181. /**
  182. * @description: 3d wheel detect core func
  183. * @param cloud input cloud for measure
  184. * @param thresh_z z value to cut wheel
  185. * @param result detect result
  186. * @return wether successfully detected
  187. */
  188. bool Ground_region::classify_ceres_detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double thresh_z,
  189. detect_wheel_ceres3d::Detect_result &result)
  190. {
  191. if (m_detector == nullptr)
  192. return false;
  193. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  194. for (int i = 0; i < cloud->size(); ++i)
  195. {
  196. pcl::PointXYZ pt = cloud->points[i];
  197. if (pt.z < thresh_z)
  198. {
  199. cloud_filtered->push_back(pt);
  200. }
  201. }
  202. //下采样
  203. pcl::VoxelGrid<pcl::PointXYZ> vox; //创建滤波对象
  204. vox.setInputCloud(cloud_filtered); //设置需要过滤的点云给滤波对象
  205. vox.setLeafSize(0.01f, 0.01f, 0.01f); //设置滤波时创建的体素体积为1cm的立方体
  206. vox.filter(*cloud_filtered); //执行滤波处理,存储输出
  207. if (cloud_filtered->size() == 0)
  208. {
  209. return false;
  210. }
  211. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor; //创建滤波器对象
  212. sor.setInputCloud(cloud_filtered); //设置待滤波的点云
  213. sor.setMeanK(5); //设置在进行统计时考虑的临近点个数
  214. sor.setStddevMulThresh(3.0); //设置判断是否为离群点的阀值,用来倍乘标准差,也就是上面的std_mul
  215. sor.filter(*cloud_filtered); //滤波结果存储到cloud_filtered
  216. if (cloud_filtered->size() == 0)
  217. {
  218. return false;
  219. }
  220. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> seg_clouds;
  221. seg_clouds = segmentation(cloud_filtered);
  222. if (!(seg_clouds.size() == 4 || seg_clouds.size() == 3))
  223. {
  224. return false;
  225. }
  226. std::vector<cv::Point2f> centers;
  227. for (int i = 0; i < seg_clouds.size(); ++i)
  228. {
  229. Eigen::Vector4f centroid;
  230. pcl::compute3DCentroid(*seg_clouds[i], centroid);
  231. centers.push_back(cv::Point2f(centroid[0], centroid[1]));
  232. }
  233. bool ret = isRect(centers);
  234. if (ret)
  235. {
  236. std::string error_str;
  237. if (m_detector->detect(seg_clouds, result, error_str))
  238. {
  239. return true;
  240. }
  241. else
  242. {
  243. // LOG(WARNING) << error_str;
  244. return false;
  245. }
  246. }
  247. return ret;
  248. }
  249. // constructor
  250. Ground_region::Ground_region()
  251. {
  252. m_region_status = E_UNKNOWN;
  253. m_detector = nullptr;
  254. m_measure_thread = nullptr;
  255. }
  256. // deconstructor
  257. Ground_region::~Ground_region()
  258. {
  259. // LOG(WARNING) << "start deconstruct ground region";
  260. if (m_measure_thread)
  261. {
  262. m_measure_condition.kill_all();
  263. // Close Capturte Thread
  264. if (m_measure_thread->joinable())
  265. {
  266. m_measure_thread->join();
  267. delete m_measure_thread;
  268. m_measure_thread = nullptr;
  269. }
  270. }
  271. // LOG(WARNING) << "thread released";
  272. // 将创建的检测器析构
  273. if(m_detector)
  274. {
  275. delete m_detector;
  276. m_detector = nullptr;
  277. }
  278. // LOG(WARNING) << "detector released";
  279. }
  280. Error_manager Ground_region::init(velodyne::Region region, pcl::PointCloud<pcl::PointXYZ>::Ptr left_model, pcl::PointCloud<pcl::PointXYZ>::Ptr right_model)
  281. {
  282. m_region = region;
  283. m_detector = new detect_wheel_ceres3d(left_model,right_model);
  284. mp_cloud_collection = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  285. mp_cloud_filtered = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  286. mp_cloud_detect_z = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  287. m_measure_thread = new std::thread(&Ground_region::thread_measure_func, this);
  288. m_measure_condition.reset();
  289. m_region_status = E_READY;
  290. return SUCCESS;
  291. }
  292. // 计算均方误差
  293. bool computer_var(std::vector<double> data, double &var)
  294. {
  295. if (data.size() == 0)
  296. return false;
  297. Eigen::VectorXd dis_vec(data.size());
  298. for (int i = 0; i < data.size(); ++i)
  299. {
  300. dis_vec[i] = data[i];
  301. }
  302. double mean = dis_vec.mean();
  303. Eigen::VectorXd mean_vec(data.size());
  304. Eigen::VectorXd mat = dis_vec - (mean_vec.setOnes() * mean);
  305. Eigen::MatrixXd result = (mat.transpose()) * mat;
  306. var = sqrt(result(0) / double(data.size()));
  307. return true;
  308. }
  309. Error_manager Ground_region::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, detect_wheel_ceres3d::Detect_result &last_result)
  310. {
  311. // 1.*********点云合法性检验*********
  312. if (cloud->size() == 0)
  313. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NORMAL, "no point");
  314. // 2.*********点云预处理*********
  315. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  316. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  317. for (int i = 0; i < cloud->size(); ++i)
  318. {
  319. pcl::PointXYZ pt = cloud->points[i];
  320. 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())
  321. {
  322. cloud_filtered->push_back(pt);
  323. }
  324. }
  325. //离群点过滤
  326. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
  327. sor.setInputCloud(cloud_filtered);
  328. sor.setMeanK(15); //K近邻搜索点个数
  329. sor.setStddevMulThresh(3.0); //标准差倍数
  330. sor.setNegative(false); //保留未滤波点(内点)
  331. sor.filter(*cloud_filtered); //保存滤波结果到cloud_filter
  332. if (cloud_filtered->size() == 0)
  333. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NORMAL, "filtered no point");
  334. //下采样
  335. pcl::ApproximateVoxelGrid<pcl::PointXYZ> vox; //创建滤波对象
  336. vox.setInputCloud(cloud_filtered); //设置需要过滤的点云给滤波对象
  337. vox.setLeafSize(0.02f, 0.02f, 0.02f); //设置滤波时创建的体素体积为1cm的立方体
  338. vox.filter(*cloud_filtered); //执行滤波处理,存储输出
  339. if (cloud_filtered->size() == 0)
  340. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NORMAL, "filtered no point");
  341. // 更新过滤点
  342. m_filtered_cloud_mutex.lock();
  343. mp_cloud_filtered->clear();
  344. mp_cloud_filtered->operator+=(*cloud_filtered);
  345. m_filtered_cloud_mutex.unlock();
  346. // 3.*********位姿优化,获取中心xy与角度*********
  347. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_detect_z(new pcl::PointCloud<pcl::PointXYZ>);
  348. double x, y, theta, width, z_value=0.2;
  349. if(!Car_pose_detector::get_instance_references().detect_pose(cloud_filtered, cloud_detect_z, x, y, theta, width, z_value, false))
  350. {
  351. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, "find general car pose value failed.");
  352. }
  353. // LOG(INFO) << "car pose :::: cx: " << x+m_region.plc_offsetx() << ", cy: " << y+m_region.plc_offsety() << ", theta: " << theta*180.0/M_PI << std::endl;
  354. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  355. std::chrono::duration<double> time_used_bowl = std::chrono::duration_cast<std::chrono::duration<double>>(t2 - t1);
  356. // 4.*********xoz优化获取底盘高度*********
  357. // 重新取包含地面点的点云,用于底盘优化
  358. chassis_ceres_solver t_solver;
  359. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_z_solver(new pcl::PointCloud<pcl::PointXYZ>);
  360. for (int i = 0; i < cloud->size(); ++i)
  361. {
  362. pcl::PointXYZ pt = cloud->points[i];
  363. if (pt.x > m_region.minx() && pt.x < m_region.maxx() && pt.y > m_region.miny() && pt.y < m_region.maxy())
  364. {
  365. cloud_z_solver->push_back(pt);
  366. }
  367. }
  368. //离群点过滤
  369. sor.setInputCloud(cloud_z_solver);
  370. sor.setMeanK(15); //K近邻搜索点个数
  371. sor.setStddevMulThresh(3.0); //标准差倍数
  372. sor.setNegative(false); //保留未滤波点(内点)
  373. sor.filter(*cloud_z_solver); //保存滤波结果到cloud_filter
  374. double mid_z = 0.05, height = 0.08;
  375. // 去中心,角度调正
  376. Car_pose_detector::get_instance_references().inv_trans_cloud(cloud_z_solver, x, y, theta);
  377. if (cloud_z_solver->size() == 0)
  378. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NORMAL, "z solver no point");
  379. x = 0.0;
  380. width = 1.0;
  381. // Error_manager ec = t_solver.solve(cloud_z_solver, x, mid_z, width, height);
  382. Error_manager ec = t_solver.solve_mat(cloud_z_solver, x, mid_z, width, height, false);
  383. // 切除大于height高度以外点,并显示width直线
  384. // 根据z值切原始点云
  385. pcl::PassThrough<pcl::PointXYZ> pass;
  386. pass.setInputCloud(cloud_z_solver);
  387. pass.setFilterFieldName("z");
  388. pass.setFilterLimits(m_region.minz(), mid_z + height / 2.0);
  389. pass.setFilterLimitsNegative(false);
  390. pass.filter(*cloud_z_solver);
  391. // // 车宽方向画线
  392. // for (double i = -3.0; i < 3.0; i+=0.02)
  393. // {
  394. // cloud_z_solver->push_back(pcl::PointXYZ(-width/2.0, i, 0));
  395. // cloud_z_solver->push_back(pcl::PointXYZ(width/2.0, i, 0));
  396. // }
  397. // std::cout << "\n------------------------------------ chassis z1: " << mid_z + height / 2.0 << std::endl;
  398. if(ec != SUCCESS)
  399. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NORMAL, "failed to find chassis z value.");
  400. std::chrono::steady_clock::time_point t3 = std::chrono::steady_clock::now();
  401. std::chrono::duration<double> time_used_block = std::chrono::duration_cast<std::chrono::duration<double>>(t3 - t2);
  402. // 更新z中间点
  403. m_detect_z_cloud_mutex.lock();
  404. mp_cloud_detect_z->clear();
  405. mp_cloud_detect_z->operator+=(*cloud_z_solver);
  406. m_detect_z_cloud_mutex.unlock();
  407. // 二分法存在错误弃用!!!直接使用底盘z值
  408. std::vector<detect_wheel_ceres3d::Detect_result> results;
  409. detect_wheel_ceres3d::Detect_result result;
  410. double chassis_z = mid_z + height / 2.0; // + 0.02;
  411. if(chassis_z > m_region.maxz() || chassis_z < m_region.minz())
  412. {
  413. 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());
  414. }
  415. bool ret = false;
  416. while (chassis_z > (mid_z))
  417. {
  418. // LOG_IF(WARNING, m_region.region_id() == 4) << "chassis z: " << chassis_z;
  419. ret = classify_ceres_detect(cloud_filtered, chassis_z, result);
  420. // changed by yct, 根据底盘z识别,失败则向下移动直至成功或超过底盘内空中点
  421. if(ret)
  422. {
  423. results.push_back(result);
  424. break;
  425. }else{
  426. chassis_z -= 0.01;
  427. }
  428. }
  429. // } while (fabs(center_z - last_center_z) > 0.01);
  430. std::chrono::steady_clock::time_point t4 = std::chrono::steady_clock::now();
  431. std::chrono::duration<double> time_used_div = std::chrono::duration_cast<std::chrono::duration<double>>(t4 - t3);
  432. // 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::endl;
  433. if (results.size() == 0)
  434. {
  435. // // 20201010, may lead to problem in chutian, uncomment in debug only
  436. // // changed by yct, save 3d wheel detect result.
  437. // static int save_debug = 0;
  438. // if (save_debug++ == 5)
  439. // m_detector->save_debug_data("/home/youchen/extra_space/chutian/measure/chutian_velo_ws/log/debug");
  440. // std::cout << "\n-------- no result: " << std::endl;
  441. LOG_IF(INFO, m_region.region_id() == 4) << "failed with midz, currz: " << mid_z << ", " << chassis_z;
  442. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, "3d wheel detect failed.");
  443. }
  444. else
  445. {
  446. LOG_IF(INFO, m_region.region_id() == 4) << "detected with suitable z value: " << chassis_z;
  447. }
  448. /// to be
  449. float min_mean_loss = 1.0;
  450. for (int i = 0; i < results.size(); ++i)
  451. {
  452. detect_wheel_ceres3d::Detect_result result = results[i];
  453. std::vector<double> loss;
  454. loss.push_back(result.loss.lf_loss);
  455. loss.push_back(result.loss.rf_loss);
  456. loss.push_back(result.loss.lb_loss);
  457. loss.push_back(result.loss.rb_loss);
  458. double mean = (result.loss.lf_loss + result.loss.rf_loss + result.loss.lb_loss + result.loss.rb_loss) / 4.0;
  459. double var = -1.;
  460. computer_var(loss, var);
  461. if (mean < min_mean_loss)
  462. {
  463. last_result = result;
  464. min_mean_loss = mean;
  465. }
  466. }
  467. // printf("z : %.3f angle : %.3f front : %.3f wheel_base:%.3f,width:%.3f, mean:%.5f\n",
  468. // center_z, last_result.theta, last_result.front_theta, last_result.wheel_base, last_result.width,
  469. // min_mean_loss);
  470. // std::cout << "\n-------- final z: " << chassis_z << std::endl;
  471. // std::cout << "cx: " << last_result.cx << ", cy: " << last_result.cy << ", theta: " << last_result.theta
  472. // << ", front: " << last_result.front_theta << ", wheelbase: " << last_result.wheel_base << ", width: " << last_result.width << std::endl << std::endl;
  473. // last_result.cx -= x;
  474. // last_result.cy -= y;
  475. // last_result.theta -= theta;
  476. return SUCCESS;
  477. }
  478. int Ground_region::outOfRangeDetection(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double plate_cx, double plate_cy, double theta)
  479. {
  480. if(cloud->size() <= 0)
  481. return Range_status::Range_correct;
  482. int res = Range_status::Range_correct;
  483. double theta_rad = theta * M_PI / 180.0;
  484. pcl::PointCloud<pcl::PointXYZ> t_cloud;
  485. for (size_t i = 0; i < cloud->size(); i++)
  486. {
  487. Eigen::Vector2d t_point(cloud->points[i].x - plate_cx, cloud->points[i].y - plate_cy);
  488. pcl::PointXYZ t_pcl_point;
  489. t_pcl_point.x = (t_point.x() * cos(theta_rad) - t_point.y() * sin(theta_rad)) + plate_cx;
  490. t_pcl_point.y = (t_point.x() * sin(theta_rad) + t_point.y() * cos(theta_rad)) + plate_cy;
  491. t_pcl_point.z = cloud->points[i].z;
  492. t_cloud.push_back(t_pcl_point);
  493. }
  494. pcl::PointXYZ min_p, max_p;
  495. pcl::getMinMax3D(t_cloud, min_p, max_p);
  496. if(min_p.x < m_region.border_minx())
  497. res |= Range_status::Range_left;
  498. if(max_p.x > m_region.border_maxx())
  499. res |= Range_status::Range_right;
  500. return res;
  501. }
  502. //外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待
  503. 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)
  504. {
  505. if ( p_car_wheel_information == NULL )
  506. {
  507. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  508. " POINTER IS NULL ");
  509. }
  510. //获取指令时间之后的信息, 如果没有就会报错, 不会等待
  511. if( m_detect_update_time > command_time )
  512. {
  513. std::lock_guard<std::mutex> lck(m_car_result_mutex);
  514. *p_car_wheel_information = m_car_wheel_information;
  515. if(m_car_wheel_information.correctness)
  516. return Error_code::SUCCESS;
  517. else
  518. return Error_manager(Error_code::VELODYNE_REGION_CERES_SOLVE_ERROR, Error_level::MINOR_ERROR, " Ground_region detect error");
  519. }
  520. else
  521. {
  522. return Error_manager(Error_code::VELODYNE_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
  523. " Ground_region::get_current_wheel_information error ");
  524. }
  525. }
  526. //外部调用获取最新的车轮定位信息, 获取指令时间往前一个周期内的车轮定位信息, 如果没有就会报错, 不会等待
  527. 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)
  528. {
  529. if ( p_car_wheel_information == NULL )
  530. {
  531. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  532. " POINTER IS NULL ");
  533. }
  534. //获取指令时间之后的信息, 如果没有就会报错, 不会等待
  535. // LOG(WARNING) << std::chrono::duration_cast<std::chrono::milliseconds>(command_time-m_detect_update_time).count()/1000.0 <<", "
  536. // <<std::chrono::duration_cast<std::chrono::milliseconds>(command_time-m_cloud_collection_time).count()/1000.0;
  537. if( m_detect_update_time > command_time - std::chrono::milliseconds(GROUND_REGION_DETECT_CYCLE_MS))
  538. {
  539. std::lock_guard<std::mutex> lck(m_car_result_mutex);
  540. *p_car_wheel_information = m_car_wheel_information;
  541. if(m_car_wheel_information.correctness)
  542. return Error_code::SUCCESS;
  543. else
  544. return Error_manager(Error_code::VELODYNE_REGION_CERES_SOLVE_ERROR, Error_level::MINOR_ERROR, " Ground_region detect error");
  545. }
  546. else
  547. {
  548. return Error_manager(Error_code::VELODYNE_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
  549. " Ground_region::get_current_wheel_information error ");
  550. }
  551. }
  552. Error_manager Ground_region::update_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
  553. {
  554. // // 点云z转90度,调试用
  555. //Eigen::AngleAxisd rot_z = Eigen::AngleAxisd(M_PI_2, Eigen::Vector3d::UnitZ());
  556. //for (size_t i = 0; i < cloud->size(); i++)
  557. //{
  558. // Eigen::Vector3d t_point(cloud->points[i].x, cloud->points[i].y, cloud->points[i].z);
  559. // t_point = rot_z.toRotationMatrix() * t_point;
  560. // cloud->points[i].x = t_point.x();
  561. // cloud->points[i].y = t_point.y();
  562. // cloud->points[i].z = t_point.z();
  563. //}
  564. // 限定锁区域,解决因条件变量在析构时无法获得内部mutex导致此互斥锁卡住,造成死锁无法结束程序的问题。
  565. {
  566. std::lock_guard<std::mutex> lck(m_cloud_collection_mutex);
  567. mp_cloud_collection = cloud;
  568. // LOG(WARNING) << "update region cloud size: " << mp_cloud_collection->size() << ",,, input size: " << cloud->size();
  569. m_cloud_collection_time = std::chrono::system_clock::now();
  570. }
  571. m_measure_condition.notify_one(false, true);
  572. // std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  573. // std::chrono::duration<double> time_used_update = std::chrono::duration_cast<std::chrono::duration<double>>(t1 - t0);
  574. // std::cout << "update cloud time: " << time_used_update.count() << std::endl;
  575. return SUCCESS;
  576. }
  577. void Ground_region::thread_measure_func()
  578. {
  579. LOG(INFO) << " Ground_region::thread_measure_func() start " << this;
  580. while (m_measure_condition.is_alive())
  581. {
  582. m_measure_condition.wait();
  583. if (m_measure_condition.is_alive())
  584. {
  585. m_region_status = E_BUSY;
  586. detect_wheel_ceres3d::Detect_result t_result;
  587. Error_manager ec = detect(mp_cloud_collection, t_result);
  588. std::lock_guard<std::mutex> lck(m_car_result_mutex);
  589. if (ec == SUCCESS)
  590. {
  591. m_car_wheel_information.correctness = true;
  592. m_car_wheel_information.car_center_x = t_result.cx;
  593. m_car_wheel_information.car_center_y = t_result.cy;
  594. m_car_wheel_information.car_angle = t_result.theta;
  595. m_car_wheel_information.car_wheel_base = t_result.wheel_base;
  596. m_car_wheel_information.car_wheel_width = t_result.width;
  597. m_car_wheel_information.car_front_theta = t_result.front_theta;
  598. m_car_wheel_information.theta_uniform(m_region.turnplate_cx(), m_region.turnplate_cy());
  599. // 添加plc偏移
  600. m_car_wheel_information.car_center_x += m_region.plc_offsetx();
  601. m_car_wheel_information.car_center_y += m_region.plc_offsety();
  602. // 超界校验
  603. {
  604. std::lock_guard<std::mutex> lck(m_filtered_cloud_mutex);
  605. int res = outOfRangeDetection(mp_cloud_filtered, m_region.turnplate_cx(), m_region.turnplate_cy(), 90.0 - t_result.theta);
  606. m_car_wheel_information.range_status = res;
  607. }
  608. Common_data::Car_wheel_information_stamped t_wheel_info_stamped;
  609. t_wheel_info_stamped.wheel_data = m_car_wheel_information;
  610. t_wheel_info_stamped.measure_time = m_detect_update_time;
  611. Measure_filter::get_instance_references().update_data(m_region.region_id(), t_wheel_info_stamped);
  612. }
  613. else
  614. {
  615. m_car_wheel_information.correctness = false;
  616. LOG(ERROR) << ec.to_string();
  617. }
  618. m_detect_update_time = std::chrono::system_clock::now();
  619. }
  620. m_region_status = E_READY;
  621. }
  622. LOG(INFO) << " Ground_region::thread_measure_func() end " << this;
  623. }