ground_region.cpp 30 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733
  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, NEGLIGIBLE_ERROR, "no input point");
  314. // 2.*********点云预处理*********
  315. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  316. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cut(new pcl::PointCloud<pcl::PointXYZ>);
  317. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_clean(new pcl::PointCloud<pcl::PointXYZ>);
  318. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  319. for (int i = 0; i < cloud->size(); ++i)
  320. {
  321. pcl::PointXYZ pt = cloud->points[i];
  322. 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())
  323. {
  324. cloud_cut->push_back(pt);
  325. }
  326. }
  327. if(cloud_cut->size() <= 0)
  328. {
  329. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "cut no point");
  330. }
  331. //下采样
  332. pcl::VoxelGrid<pcl::PointXYZ> vox; //创建滤波对象
  333. vox.setInputCloud(cloud_cut); //设置需要过滤的点云给滤波对象
  334. vox.setLeafSize(0.02f, 0.02f, 0.02f); //设置滤波时创建的体素体积为1cm的立方体
  335. vox.filter(*cloud_clean); //执行滤波处理,存储输出
  336. // cloud_filtered = cloud_clean;
  337. if (cloud_clean->size() == 0)
  338. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "ApproximateVoxelGrid no point");
  339. //离群点过滤
  340. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
  341. sor.setInputCloud(cloud_clean);
  342. sor.setMeanK(5); //K近邻搜索点个数
  343. sor.setStddevMulThresh(3.0); //标准差倍数
  344. sor.setNegative(false); //保留未滤波点(内点)
  345. sor.filter(*cloud_filtered); //保存滤波结果到cloud_filter
  346. if (cloud_filtered->size() == 0)
  347. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "StatisticalOutlierRemoval no point");
  348. // 更新过滤点
  349. m_filtered_cloud_mutex.lock();
  350. mp_cloud_filtered->clear();
  351. mp_cloud_filtered->operator+=(*cloud_filtered);
  352. m_filtered_cloud_mutex.unlock();
  353. // 3.*********位姿优化,获取中心xy与角度*********
  354. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_detect_z(new pcl::PointCloud<pcl::PointXYZ>);
  355. double car_pose_x, car_pose_y, car_pose_theta, car_pose_width, z_value=0.2;
  356. // 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))
  357. 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))
  358. {
  359. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, "find general car pose value failed.");
  360. }
  361. // LOG(INFO) << "car pose :::: cx: " << x+m_region.plc_offsetx() << ", cy: " << y+m_region.plc_offsety() << ", theta: " << theta*180.0/M_PI << std::endl;
  362. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  363. std::chrono::duration<double> time_used_bowl = std::chrono::duration_cast<std::chrono::duration<double>>(t2 - t1);
  364. // 4.*********xoz优化获取底盘高度*********
  365. // 重新取包含地面点的点云,用于底盘优化
  366. double z_solver_x = car_pose_x;
  367. double z_solver_y = car_pose_y;
  368. double z_solver_theta = car_pose_theta;
  369. double z_solver_width = 1.0;
  370. chassis_ceres_solver t_solver;
  371. // !!!重新筛选地面点并滤波,融入第一步位姿使用的滤波后点云,传入第二步获取底盘高度
  372. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_z_solver(new pcl::PointCloud<pcl::PointXYZ>);
  373. for (int i = 0; i < cloud->size(); ++i)
  374. {
  375. pcl::PointXYZ pt = cloud->points[i];
  376. 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())
  377. {
  378. cloud_z_solver->push_back(pt);
  379. }
  380. }
  381. //离群点过滤
  382. sor.setInputCloud(cloud_z_solver);
  383. sor.setMeanK(5); //K近邻搜索点个数
  384. sor.setStddevMulThresh(3.0); //标准差倍数
  385. sor.setNegative(false); //保留未滤波点(内点)
  386. sor.filter(*cloud_z_solver); //保存滤波结果到cloud_filter
  387. // 补上车身与车轮点
  388. cloud_z_solver->operator+=(*mp_cloud_filtered);
  389. // 去中心,角度调正
  390. Car_pose_detector::get_instance_references().inv_trans_cloud(cloud_z_solver, z_solver_x, z_solver_y, z_solver_theta);
  391. if (cloud_z_solver->size() == 0)
  392. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NORMAL, "z solver no point");
  393. // 给予底盘z中心与高度初值
  394. double mid_z = 0.05, height = 0.08;
  395. z_solver_x = 0.0;
  396. // Error_manager ec = t_solver.solve(cloud_z_solver, z_solver_x, mid_z, z_solver_width, height);
  397. Error_manager ec = t_solver.solve_mat(cloud_z_solver, z_solver_x, mid_z, z_solver_width, height, false);
  398. // 切除大于height高度以外点,并显示width直线
  399. // 根据z值切原始点云
  400. pcl::PassThrough<pcl::PointXYZ> pass;
  401. pass.setInputCloud(cloud_z_solver);
  402. pass.setFilterFieldName("z");
  403. pass.setFilterLimits(m_region.minz(), mid_z + height / 2.0);
  404. pass.setFilterLimitsNegative(false);
  405. pass.filter(*cloud_z_solver);
  406. // // 车宽方向画线
  407. // for (double i = -3.0; i < 3.0; i+=0.02)
  408. // {
  409. // cloud_z_solver->push_back(pcl::PointXYZ(-width/2.0, i, 0));
  410. // cloud_z_solver->push_back(pcl::PointXYZ(width/2.0, i, 0));
  411. // }
  412. // std::cout << "\n------------------------------------ chassis z1: " << mid_z + height / 2.0 << ", mid z: "<< mid_z << std::endl;
  413. if(ec != SUCCESS)
  414. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NORMAL, "failed to find chassis z value.");
  415. std::chrono::steady_clock::time_point t3 = std::chrono::steady_clock::now();
  416. std::chrono::duration<double> time_used_block = std::chrono::duration_cast<std::chrono::duration<double>>(t3 - t2);
  417. // 更新z中间点
  418. m_detect_z_cloud_mutex.lock();
  419. mp_cloud_detect_z->clear();
  420. mp_cloud_detect_z->operator+=(*cloud_z_solver);
  421. m_detect_z_cloud_mutex.unlock();
  422. // 二分法存在错误弃用!!!直接使用底盘z值
  423. std::vector<detect_wheel_ceres3d::Detect_result> results;
  424. detect_wheel_ceres3d::Detect_result result;
  425. double chassis_z = mid_z + height / 2.0; // + 0.02;
  426. if(chassis_z > m_region.maxz() || chassis_z < m_region.minz())
  427. {
  428. 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());
  429. }
  430. bool ret = false;
  431. while (chassis_z > (mid_z - height / 2.0))
  432. {
  433. // LOG_IF(WARNING, m_region.region_id() == 4) << "chassis z: " << chassis_z << ", midz: " << mid_z - height / 2.0;
  434. ret = classify_ceres_detect(cloud_filtered, chassis_z, result);
  435. // changed by yct, 根据底盘z识别,失败则向下移动直至成功或超过底盘内空中点
  436. if(ret)
  437. {
  438. results.push_back(result);
  439. break;
  440. }else{
  441. chassis_z -= 0.01;
  442. }
  443. }
  444. // } while (fabs(center_z - last_center_z) > 0.01);
  445. std::chrono::steady_clock::time_point t4 = std::chrono::steady_clock::now();
  446. std::chrono::duration<double> time_used_div = std::chrono::duration_cast<std::chrono::duration<double>>(t4 - t3);
  447. // 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;
  448. if (results.size() == 0)
  449. {
  450. // // 20201010, may lead to problem in chutian, uncomment in debug only
  451. // // changed by yct, save 3d wheel detect result.
  452. // static int save_debug = 0;
  453. // if (save_debug++ == 5)
  454. // m_detector->save_debug_data("/home/youchen/extra_space/chutian/measure/chutian_velo_ws/log/debug");
  455. // std::cout << "\n-------- no result: " << std::endl;
  456. //LOG_IF(INFO, m_region.region_id() == 4) << "failed with midz, currz: " << mid_z << ", " << chassis_z;
  457. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, "3d wheel detect failed.");
  458. }
  459. else
  460. {
  461. // LOG_IF(INFO, m_region.region_id() == 4) << "detected with suitable z value: " << chassis_z;
  462. }
  463. /// to be
  464. float min_mean_loss = 1.0;
  465. for (int i = 0; i < results.size(); ++i)
  466. {
  467. detect_wheel_ceres3d::Detect_result result = results[i];
  468. std::vector<double> loss;
  469. loss.push_back(result.loss.lf_loss);
  470. loss.push_back(result.loss.rf_loss);
  471. loss.push_back(result.loss.lb_loss);
  472. loss.push_back(result.loss.rb_loss);
  473. double mean = (result.loss.lf_loss + result.loss.rf_loss + result.loss.lb_loss + result.loss.rb_loss) / 4.0;
  474. double var = -1.;
  475. computer_var(loss, var);
  476. if (mean < min_mean_loss)
  477. {
  478. last_result = result;
  479. min_mean_loss = mean;
  480. }
  481. }
  482. // printf("z : %.3f angle : %.3f front : %.3f wheel_base:%.3f,width:%.3f, mean:%.5f\n",
  483. // center_z, last_result.theta, last_result.front_theta, last_result.wheel_base, last_result.width,
  484. // min_mean_loss);
  485. // std::cout << "\n-------- final z: " << chassis_z << std::endl;
  486. // std::cout << "cx: " << last_result.cx << ", cy: " << last_result.cy << ", theta: " << last_result.theta
  487. // << ", front: " << last_result.front_theta << ", wheelbase: " << last_result.wheel_base << ", width: " << last_result.width << std::endl << std::endl;
  488. // last_result.cx -= x;
  489. // last_result.cy -= y;
  490. // last_result.theta -= theta;
  491. // 角度校验,理论上car pose检测使用车身点云,应与车轮点云识别得到的车身 x偏移(0.025)与角度(<1°)一致
  492. double car_pose_theta_deg = 90 - car_pose_theta * 180.0 / M_PI;
  493. if (fabs(car_pose_x - last_result.cx) > 0.025 || fabs(car_pose_theta_deg - last_result.theta) > 1)
  494. {
  495. char valid_info[255];
  496. 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);
  497. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, valid_info);
  498. }
  499. // LOG_IF(INFO, m_region.region_id() == 4) << last_result.to_string();
  500. return SUCCESS;
  501. }
  502. int Ground_region::outOfRangeDetection(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double plate_cx, double plate_cy, double theta)
  503. {
  504. if(cloud->size() <= 0)
  505. return Range_status::Range_correct;
  506. int res = Range_status::Range_correct;
  507. double theta_rad = theta * M_PI / 180.0;
  508. pcl::PointCloud<pcl::PointXYZ> t_cloud;
  509. for (size_t i = 0; i < cloud->size(); i++)
  510. {
  511. Eigen::Vector2d t_point(cloud->points[i].x - plate_cx, cloud->points[i].y - plate_cy);
  512. pcl::PointXYZ t_pcl_point;
  513. t_pcl_point.x = (t_point.x() * cos(theta_rad) - t_point.y() * sin(theta_rad)) + plate_cx;
  514. t_pcl_point.y = (t_point.x() * sin(theta_rad) + t_point.y() * cos(theta_rad)) + plate_cy;
  515. t_pcl_point.z = cloud->points[i].z;
  516. t_cloud.push_back(t_pcl_point);
  517. }
  518. pcl::PointXYZ min_p, max_p;
  519. pcl::getMinMax3D(t_cloud, min_p, max_p);
  520. if(min_p.x < m_region.border_minx())
  521. res |= Range_status::Range_left;
  522. if(max_p.x > m_region.border_maxx())
  523. res |= Range_status::Range_right;
  524. // LOG_IF(WARNING, m_region.region_id() == 4)<< "border minmax x: "<< min_p.x<<", "<<max_p.x<<", res: "<<res;
  525. return res;
  526. }
  527. 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)
  528. {
  529. int res = Range_status::Range_correct;
  530. if(cloud->size() <= 0)
  531. return res;
  532. Eigen::Vector2d car_center(measure_result.car_center_x, measure_result.car_center_y);
  533. Eigen::Vector2d car_uniform_center;
  534. double theta_rad = theta * M_PI / 180.0;
  535. car_uniform_center.x() = car_center.x() * cos(theta_rad) - car_center.y() * sin(theta_rad);
  536. car_uniform_center.y() = car_center.x() * sin(theta_rad) + car_center.y() * cos(theta_rad);
  537. // 车位位于y负方向
  538. double rear_wheel_y = car_uniform_center.y() + m_region.plc_offsety() - 0.5 * measure_result.car_wheel_base;
  539. if(rear_wheel_y < m_region.plc_border_miny())
  540. {
  541. res |= Range_status::Range_back;
  542. }
  543. res |= outOfRangeDetection(cloud, plate_cx, plate_cy, theta);
  544. return res;
  545. }
  546. //外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待
  547. 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)
  548. {
  549. if ( p_car_wheel_information == NULL )
  550. {
  551. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  552. " POINTER IS NULL ");
  553. }
  554. //获取指令时间之后的信息, 如果没有就会报错, 不会等待
  555. if( m_detect_update_time > command_time )
  556. {
  557. std::lock_guard<std::mutex> lck(m_car_result_mutex);
  558. *p_car_wheel_information = m_car_wheel_information;
  559. if(m_car_wheel_information.correctness)
  560. return Error_code::SUCCESS;
  561. else
  562. return Error_manager(Error_code::VELODYNE_REGION_CERES_SOLVE_ERROR, Error_level::MINOR_ERROR, " Ground_region detect error");
  563. }
  564. else
  565. {
  566. return Error_manager(Error_code::VELODYNE_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
  567. " Ground_region::get_current_wheel_information error ");
  568. }
  569. }
  570. //外部调用获取最新的车轮定位信息, 获取指令时间往前一个周期内的车轮定位信息, 如果没有就会报错, 不会等待
  571. 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)
  572. {
  573. if ( p_car_wheel_information == NULL )
  574. {
  575. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  576. " POINTER IS NULL ");
  577. }
  578. //获取指令时间之后的信息, 如果没有就会报错, 不会等待
  579. // LOG(WARNING) << std::chrono::duration_cast<std::chrono::milliseconds>(command_time-m_detect_update_time).count()/1000.0 <<", "
  580. // <<std::chrono::duration_cast<std::chrono::milliseconds>(command_time-m_cloud_collection_time).count()/1000.0;
  581. if( m_detect_update_time > command_time - std::chrono::milliseconds(GROUND_REGION_DETECT_CYCLE_MS))
  582. {
  583. std::lock_guard<std::mutex> lck(m_car_result_mutex);
  584. *p_car_wheel_information = m_car_wheel_information;
  585. if(m_car_wheel_information.correctness)
  586. return Error_code::SUCCESS;
  587. else
  588. return Error_manager(Error_code::VELODYNE_REGION_CERES_SOLVE_ERROR, Error_level::MINOR_ERROR, " Ground_region detect error");
  589. }
  590. else
  591. {
  592. return Error_manager(Error_code::VELODYNE_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
  593. " Ground_region::get_current_wheel_information error ");
  594. }
  595. }
  596. Error_manager Ground_region::update_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
  597. {
  598. // // 点云z转90度,调试用
  599. //Eigen::AngleAxisd rot_z = Eigen::AngleAxisd(M_PI_2, Eigen::Vector3d::UnitZ());
  600. //for (size_t i = 0; i < cloud->size(); i++)
  601. //{
  602. // Eigen::Vector3d t_point(cloud->points[i].x, cloud->points[i].y, cloud->points[i].z);
  603. // t_point = rot_z.toRotationMatrix() * t_point;
  604. // cloud->points[i].x = t_point.x();
  605. // cloud->points[i].y = t_point.y();
  606. // cloud->points[i].z = t_point.z();
  607. //}
  608. // 限定锁区域,解决因条件变量在析构时无法获得内部mutex导致此互斥锁卡住,造成死锁无法结束程序的问题。
  609. {
  610. std::lock_guard<std::mutex> lck(m_cloud_collection_mutex);
  611. mp_cloud_collection = cloud;
  612. // LOG(WARNING) << "update region cloud size: " << mp_cloud_collection->size() << ",,, input size: " << cloud->size();
  613. m_cloud_collection_time = std::chrono::system_clock::now();
  614. }
  615. m_measure_condition.notify_one(false, true);
  616. // std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  617. // std::chrono::duration<double> time_used_update = std::chrono::duration_cast<std::chrono::duration<double>>(t1 - t0);
  618. // std::cout << "update cloud time: " << time_used_update.count() << std::endl;
  619. return SUCCESS;
  620. }
  621. void Ground_region::thread_measure_func()
  622. {
  623. LOG(INFO) << " Ground_region::thread_measure_func() start " << this;
  624. while (m_measure_condition.is_alive())
  625. {
  626. m_measure_condition.wait();
  627. if (m_measure_condition.is_alive())
  628. {
  629. m_region_status = E_BUSY;
  630. detect_wheel_ceres3d::Detect_result t_result;
  631. Error_manager ec = detect(mp_cloud_collection, t_result);
  632. std::lock_guard<std::mutex> lck(m_car_result_mutex);
  633. if (ec == SUCCESS)
  634. {
  635. m_car_wheel_information.correctness = true;
  636. m_car_wheel_information.car_center_x = t_result.cx;
  637. m_car_wheel_information.car_center_y = t_result.cy;
  638. m_car_wheel_information.car_angle = t_result.theta;
  639. m_car_wheel_information.car_wheel_base = t_result.wheel_base;
  640. m_car_wheel_information.car_wheel_width = t_result.width;
  641. m_car_wheel_information.car_front_theta = t_result.front_theta;
  642. m_car_wheel_information.theta_uniform(m_region.turnplate_cx(), m_region.turnplate_cy());
  643. // 超界校验
  644. {
  645. std::lock_guard<std::mutex> lck(m_filtered_cloud_mutex);
  646. int res = outOfRangeDetection(mp_cloud_filtered, m_car_wheel_information, m_region.turnplate_cx(), m_region.turnplate_cy(), 90.0 - t_result.theta);
  647. m_car_wheel_information.range_status = res;
  648. }
  649. // 添加plc偏移
  650. m_car_wheel_information.car_center_x += m_region.plc_offsetx();
  651. m_car_wheel_information.car_center_y += m_region.plc_offsety();
  652. m_car_wheel_information.uniform_car_x += m_region.plc_offsetx();
  653. m_car_wheel_information.uniform_car_y += m_region.plc_offsety();
  654. Common_data::Car_wheel_information_stamped t_wheel_info_stamped;
  655. t_wheel_info_stamped.wheel_data = m_car_wheel_information;
  656. t_wheel_info_stamped.measure_time = m_detect_update_time;
  657. Measure_filter::get_instance_references().update_data(m_region.region_id(), t_wheel_info_stamped);
  658. //LOG_IF(INFO, m_region.region_id() == 4) << m_car_wheel_information.to_string();
  659. }
  660. else
  661. {
  662. m_car_wheel_information.correctness = false;
  663. //LOG_IF(ERROR, m_region.region_id() == 4) << ec.to_string();
  664. }
  665. m_detect_update_time = std::chrono::system_clock::now();
  666. }
  667. m_region_status = E_READY;
  668. }
  669. LOG(INFO) << " Ground_region::thread_measure_func() end " << this;
  670. }