ground_region.cpp 39 KB

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