ground_region.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493
  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.02f, 0.02f, 0.2f); //设置滤波时创建的体素体积为1cm的立方体
  206. vox.filter(*cloud_filtered); //执行滤波处理,存储输出
  207. if (cloud_filtered->size() == 0)
  208. {
  209. return false;
  210. }
  211. if (cloud_filtered->size() == 0)
  212. return false;
  213. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor; //创建滤波器对象
  214. sor.setInputCloud(cloud_filtered); //设置待滤波的点云
  215. sor.setMeanK(5); //设置在进行统计时考虑的临近点个数
  216. sor.setStddevMulThresh(3.0); //设置判断是否为离群点的阀值,用来倍乘标准差,也就是上面的std_mul
  217. sor.filter(*cloud_filtered); //滤波结果存储到cloud_filtered
  218. if (cloud_filtered->size() == 0)
  219. {
  220. return false;
  221. }
  222. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> seg_clouds;
  223. seg_clouds = segmentation(cloud_filtered);
  224. if (!(seg_clouds.size() == 4 || seg_clouds.size() == 3))
  225. {
  226. return false;
  227. }
  228. std::vector<cv::Point2f> centers;
  229. for (int i = 0; i < seg_clouds.size(); ++i)
  230. {
  231. Eigen::Vector4f centroid;
  232. pcl::compute3DCentroid(*seg_clouds[i], centroid);
  233. centers.push_back(cv::Point2f(centroid[0], centroid[1]));
  234. }
  235. bool ret = isRect(centers);
  236. if (ret)
  237. {
  238. std::string error_str;
  239. if (m_detector->detect(seg_clouds, result, error_str))
  240. {
  241. return true;
  242. }
  243. else
  244. {
  245. return false;
  246. }
  247. }
  248. return ret;
  249. }
  250. // constructor
  251. Ground_region::Ground_region()
  252. {
  253. m_region_status = E_UNKNOWN;
  254. m_detector = nullptr;
  255. m_measure_thread = nullptr;
  256. }
  257. // deconstructor
  258. Ground_region::~Ground_region()
  259. {
  260. if(m_measure_thread){
  261. m_measure_condition.kill_all();
  262. // Close Capturte Thread
  263. if (m_measure_thread->joinable())
  264. {
  265. m_measure_thread->join();
  266. delete m_measure_thread;
  267. m_measure_thread = nullptr;
  268. }
  269. }
  270. }
  271. Error_manager Ground_region::init(velodyne::Region region, pcl::PointCloud<pcl::PointXYZ>::Ptr left_model, pcl::PointCloud<pcl::PointXYZ>::Ptr right_model)
  272. {
  273. m_region = region;
  274. m_detector = new detect_wheel_ceres3d(left_model,right_model);
  275. mp_cloud_collection = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  276. m_measure_thread = new std::thread(&Ground_region::thread_measure_func, this);
  277. m_measure_condition.reset();
  278. m_region_status = E_READY;
  279. return SUCCESS;
  280. }
  281. // 计算均方误差
  282. bool computer_var(std::vector<double> data, double &var)
  283. {
  284. if (data.size() == 0)
  285. return false;
  286. Eigen::VectorXd dis_vec(data.size());
  287. for (int i = 0; i < data.size(); ++i)
  288. {
  289. dis_vec[i] = data[i];
  290. }
  291. double mean = dis_vec.mean();
  292. Eigen::VectorXd mean_vec(data.size());
  293. Eigen::VectorXd mat = dis_vec - (mean_vec.setOnes() * mean);
  294. Eigen::MatrixXd result = (mat.transpose()) * mat;
  295. var = sqrt(result(0) / double(data.size()));
  296. return true;
  297. }
  298. Error_manager Ground_region::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, detect_wheel_ceres3d::Detect_result &last_result)
  299. {
  300. if (cloud->size() == 0)
  301. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NORMAL, "no point");
  302. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  303. for (int i = 0; i < cloud->size(); ++i)
  304. {
  305. pcl::PointXYZ pt = cloud->points[i];
  306. 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())
  307. {
  308. cloud_filtered->push_back(pt);
  309. }
  310. }
  311. if (cloud_filtered->size() == 0)
  312. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NORMAL, "filtered no point");
  313. float start_z = m_region.minz();
  314. float max_z = 0.2;
  315. float center_z = (start_z + max_z) / 2.0;
  316. float last_center_z = start_z;
  317. float last_succ_z = -1.0;
  318. int count = 0;
  319. //二分法 找识别成功的 最高的z
  320. std::vector<detect_wheel_ceres3d::Detect_result> results;
  321. do
  322. {
  323. detect_wheel_ceres3d::Detect_result result;
  324. bool ret = classify_ceres_detect(cloud_filtered, center_z, result);
  325. // std::cout << "z: " << center_z <<", "<<start_z<<"," << max_z << std::endl;
  326. if (ret)
  327. {
  328. results.push_back(result);
  329. last_succ_z = center_z;
  330. start_z = center_z;
  331. last_center_z = center_z;
  332. }
  333. else
  334. {
  335. max_z = center_z;
  336. last_center_z = center_z;
  337. }
  338. center_z = (start_z + max_z) / 2.0;
  339. count++;
  340. } while (fabs(center_z - last_center_z) > 0.01);
  341. //
  342. if (results.size() == 0)
  343. {
  344. return Error_manager(FAILED, NORMAL, "no car detected");
  345. }
  346. /// to be
  347. float min_mean_loss = 1.0;
  348. for (int i = 0; i < results.size(); ++i)
  349. {
  350. detect_wheel_ceres3d::Detect_result result = results[i];
  351. std::vector<double> loss;
  352. loss.push_back(result.loss.lf_loss);
  353. loss.push_back(result.loss.rf_loss);
  354. loss.push_back(result.loss.lb_loss);
  355. loss.push_back(result.loss.rb_loss);
  356. double mean = (result.loss.lf_loss + result.loss.rf_loss + result.loss.lb_loss + result.loss.rb_loss) / 4.0;
  357. double var = -1.;
  358. computer_var(loss, var);
  359. if (mean < min_mean_loss)
  360. {
  361. last_result = result;
  362. min_mean_loss = mean;
  363. }
  364. }
  365. // printf("z : %.3f angle : %.3f front : %.3f wheel_base:%.3f,width:%.3f, mean:%.5f\n",
  366. // center_z, last_result.theta, last_result.front_theta, last_result.wheel_base, last_result.width,
  367. // min_mean_loss);
  368. //m_detector->save_debug_data("/home/zx/zzw/catkin_ws/src/feature_extra/debug");
  369. return SUCCESS;
  370. }
  371. //外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待
  372. 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)
  373. {
  374. if ( p_car_wheel_information == NULL )
  375. {
  376. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  377. " POINTER IS NULL ");
  378. }
  379. //获取指令时间之后的信息, 如果没有就会报错, 不会等待
  380. if( m_detect_update_time > command_time )
  381. {
  382. *p_car_wheel_information = m_car_wheel_information;
  383. if(m_car_wheel_information.correctness)
  384. return Error_code::SUCCESS;
  385. else
  386. return Error_manager(Error_code::VELODYNE_REGION_CERES_SOLVE_ERROR, Error_level::MINOR_ERROR, " Ground_region detect error");
  387. }
  388. else
  389. {
  390. return Error_manager(Error_code::VELODYNE_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
  391. " Ground_region::get_current_wheel_information error ");
  392. }
  393. }
  394. //外部调用获取最新的车轮定位信息, 获取指令时间往前一个周期内的车轮定位信息, 如果没有就会报错, 不会等待
  395. 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)
  396. {
  397. if ( p_car_wheel_information == NULL )
  398. {
  399. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  400. " POINTER IS NULL ");
  401. }
  402. //获取指令时间之后的信息, 如果没有就会报错, 不会等待
  403. if( m_detect_update_time > command_time - std::chrono::milliseconds(GROUND_REGION_DETECT_CYCLE_MS))
  404. {
  405. *p_car_wheel_information = m_car_wheel_information;
  406. if(m_car_wheel_information.correctness)
  407. return Error_code::SUCCESS;
  408. else
  409. return Error_manager(Error_code::VELODYNE_REGION_CERES_SOLVE_ERROR, Error_level::MINOR_ERROR, " Ground_region detect error ");
  410. }
  411. else
  412. {
  413. return Error_manager(Error_code::VELODYNE_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
  414. " Ground_region::get_current_wheel_information error ");
  415. }
  416. }
  417. Error_manager Ground_region::update_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
  418. {
  419. std::lock_guard<std::mutex> lck(m_cloud_collection_mutex);
  420. mp_cloud_collection = cloud;
  421. m_cloud_collection_time = std::chrono::system_clock::now();
  422. m_measure_condition.notify_one(false, true);
  423. return SUCCESS;
  424. }
  425. void Ground_region::thread_measure_func()
  426. {
  427. while (m_measure_condition.is_alive())
  428. {
  429. m_measure_condition.wait();
  430. if (m_measure_condition.is_alive())
  431. {
  432. m_region_status = E_BUSY;
  433. detect_wheel_ceres3d::Detect_result t_result;
  434. Error_manager ec = detect(mp_cloud_collection, t_result);
  435. m_detect_update_time = std::chrono::system_clock::now();
  436. m_car_wheel_information.center_x = t_result.cx;
  437. m_car_wheel_information.center_y = t_result.cy;
  438. m_car_wheel_information.car_angle = t_result.theta;
  439. m_car_wheel_information.wheel_base = t_result.wheel_base;
  440. m_car_wheel_information.wheel_width = t_result.width;
  441. m_car_wheel_information.front_theta = t_result.front_theta;
  442. if (ec == SUCCESS)
  443. {
  444. m_car_wheel_information.correctness = true;
  445. Common_data::Car_wheel_information_stamped t_wheel_info_stamped;
  446. t_wheel_info_stamped.wheel_data = m_car_wheel_information;
  447. t_wheel_info_stamped.measure_time = m_detect_update_time;
  448. Measure_filter::get_instance_references().update_data(m_region.region_id(), t_wheel_info_stamped);
  449. }
  450. else
  451. {
  452. m_car_wheel_information.correctness = false;
  453. }
  454. }
  455. m_region_status = E_READY;
  456. }
  457. }