region_detect.cpp 24 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619
  1. //
  2. // Created by zx on 2019/12/6.
  3. //
  4. #include "region_detect.h"
  5. #include "../tool/point_tool.h"
  6. /**
  7. * 有参构造函数
  8. * */
  9. Region_detector::Region_detector(wj::Region region) : m_region_id(-1)
  10. {
  11. m_region_param.CopyFrom(region);
  12. m_region_id = region.region_id();
  13. }
  14. /**
  15. * 析构函数
  16. * */
  17. Region_detector::~Region_detector()
  18. {
  19. }
  20. /**
  21. * 获取区域id
  22. * */
  23. int Region_detector::get_region_id()
  24. {
  25. return m_region_id;
  26. }
  27. /**
  28. * 预处理,xy直通滤波与离群点过滤
  29. * 返回 PARAMETER_ERROR,WJ_REGION_EMPTY_CLOUD 或 SUCCESS
  30. * */
  31. Error_manager Region_detector::preprocess(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in, pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_out)
  32. {
  33. // 1.参数合法性检验
  34. if (!m_region_param.has_maxx() || !m_region_param.has_maxy() || !m_region_param.has_minx() || !m_region_param.has_miny())
  35. return Error_manager(Error_code::PARAMETER_ERROR);
  36. if (cloud_in->size() <= 0)
  37. return Error_manager(Error_code::WJ_REGION_EMPTY_CLOUD);
  38. cloud_out->clear();
  39. pcl::copyPointCloud(*cloud_in, *cloud_out);
  40. if (cloud_out->size() <= 0)
  41. return Error_manager(Error_code::WJ_REGION_EMPTY_CLOUD);
  42. // 2.直通滤波, 筛选xy
  43. pcl::PassThrough<pcl::PointXYZ> pass;
  44. pass.setInputCloud(cloud_out);
  45. pass.setFilterFieldName("x"); //设置想在哪个坐标轴上操作
  46. pass.setFilterLimits(m_region_param.minx(), m_region_param.maxx()); //将x轴的0到1范围内
  47. pass.setFilterLimitsNegative(false); //保留(true就是删除,false就是保留而删除此区间外的)
  48. pass.filter(*cloud_out); //输出到结果指针
  49. if (cloud_out->size() <= 0)
  50. return Error_manager(Error_code::WJ_REGION_EMPTY_CLOUD);
  51. pass.setInputCloud(cloud_out);
  52. pass.setFilterFieldName("y"); //设置想在哪个坐标轴上操作
  53. pass.setFilterLimits(m_region_param.miny(), m_region_param.maxy()); //将x轴的0到1范围内
  54. pass.setFilterLimitsNegative(false); //保留(true就是删除,false就是保留而删除此区间外的)
  55. pass.filter(*cloud_out); //输出到结果指针
  56. if (cloud_out->size() <= 0)
  57. return Error_manager(Error_code::WJ_REGION_EMPTY_CLOUD);
  58. // 3.离群点过滤
  59. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
  60. sor.setInputCloud(cloud_out);
  61. sor.setMeanK(10); //K近邻搜索点个数
  62. sor.setStddevMulThresh(1.0); //标准差倍数
  63. sor.setNegative(false); //保留未滤波点(内点)
  64. sor.filter(*cloud_out); //保存滤波结果到cloud_filter
  65. if (cloud_out->size() <= 0)
  66. return Error_manager(Error_code::WJ_REGION_EMPTY_CLOUD);
  67. else
  68. return Error_manager(Error_code::SUCCESS);
  69. }
  70. // /**
  71. // * 返回二维点之间距离
  72. // * */
  73. // double distance(cv::Point2f p1, cv::Point2f p2)
  74. // {
  75. // return sqrt(pow(p1.x - p2.x, 2.0) + pow(p1.y - p2.y, 2.0));
  76. // }
  77. /**
  78. * 判断是否符合标准矩形,
  79. * 传入矩形四个角点,以及是否打印
  80. * 返回 WJ_REGION_RECTANGLE_ANGLE_ERROR, WJ_REGION_RECTANGLE_SIZE_ERROR,
  81. * WJ_REGION_RECTANGLE_SYMMETRY_ERROR, WJ_REGION_CLUSTER_SIZE_ERROR, SUCCESS
  82. * */
  83. Error_manager Region_detector::isRect(std::vector<cv::Point2f> &points, bool print)
  84. {
  85. if (points.size() == 4)
  86. {
  87. double L[3] = {0.0};
  88. L[0] = distance(points[0], points[1]);
  89. L[1] = distance(points[1], points[2]);
  90. L[2] = distance(points[0], points[2]);
  91. double max_l = L[0];
  92. double l1 = L[1];
  93. double l2 = L[2];
  94. int max_index = 0;
  95. cv::Point2f ps = points[0], pt = points[1];
  96. // 顶点
  97. cv::Point2f pc = points[2];
  98. for (int i = 1; i < 3; ++i)
  99. {
  100. if (L[i] > max_l)
  101. {
  102. max_index = i;
  103. max_l = L[i];
  104. l1 = L[abs(i + 1) % 3];
  105. l2 = L[abs(i + 2) % 3];
  106. ps = points[i % 3];
  107. pt = points[(i + 1) % 3];
  108. pc = points[(i + 2) % 3];
  109. }
  110. }
  111. // 顶角大小
  112. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  113. // 顶角相对于90度过大或小
  114. if (fabs(cosa) >= 0.15 /* || std::min(l1, l2) > 2.0 || std::max(l1, l2) > 3.3*/)
  115. {
  116. if (print)
  117. {
  118. LOG(WARNING) << " angle cos >0.13 =" << cosa << " i=" << max_index;
  119. // LOG(WARNING) << "L1:" << l1 << " L2:" << l2 << " L3:" << max_l;
  120. }
  121. return Error_manager(Error_code::WJ_REGION_RECTANGLE_ANGLE_ERROR);
  122. }
  123. float width = std::min(l1, l2);
  124. float length = std::max(l1, l2);
  125. // 车宽应位于[1.35, 2.0],车长应位于[2.2, 3.0]
  126. if (width < 1.350 || width > 2.000 || length > 3.000 || length < 2.200)
  127. {
  128. if (print)
  129. {
  130. LOG(WARNING) << "\t width<1350 || width >2100 || length >3300 ||length < 2100 "
  131. << " length:" << length << " width:" << width;
  132. }
  133. return Error_manager(Error_code::WJ_REGION_RECTANGLE_SIZE_ERROR);
  134. }
  135. double d = distance(pc, points[3]);
  136. cv::Point2f center1 = (ps + pt) * 0.5;
  137. cv::Point2f center2 = (pc + points[3]) * 0.5;
  138. // 对角线形变超过0.15倍,或中心点距离偏差0.15m
  139. if (fabs(d - max_l) > max_l * 0.15 || distance(center1, center2) > 0.150)
  140. {
  141. if (print)
  142. {
  143. LOG(WARNING) << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2
  144. << " center distance=" << distance(center1, center2);
  145. }
  146. return Error_manager(Error_code::WJ_REGION_RECTANGLE_SYMMETRY_ERROR);
  147. }
  148. if (print)
  149. {
  150. LOG(INFO) << " rectangle verify OK cos angle=" << cosa << " length off=" << fabs(d - max_l)
  151. << " center distance=" << distance(center1, center2);
  152. }
  153. return Error_manager(Error_code::SUCCESS);
  154. }
  155. // 以三个点进行验证
  156. else if (points.size() == 3)
  157. {
  158. double L[3] = {0.0};
  159. L[0] = distance(points[0], points[1]);
  160. L[1] = distance(points[1], points[2]);
  161. L[2] = distance(points[0], points[2]);
  162. double max_l = L[0];
  163. double l1 = L[1];
  164. double l2 = L[2];
  165. int max_index = 0;
  166. cv::Point2f ps = points[0], pt = points[1];
  167. cv::Point2f pc = points[2];
  168. for (int i = 1; i < 3; ++i)
  169. {
  170. if (L[i] > max_l)
  171. {
  172. max_index = i;
  173. max_l = L[i];
  174. l1 = L[abs(i + 1) % 3];
  175. l2 = L[abs(i + 2) % 3];
  176. ps = points[i % 3];
  177. pt = points[(i + 1) % 3];
  178. pc = points[(i + 2) % 3];
  179. }
  180. }
  181. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  182. // 顶角应接近90度
  183. if (fabs(cosa) >= 0.15)
  184. {
  185. if (print)
  186. {
  187. LOG(WARNING) << "3 wheels angle cos >0.12 =" << cosa << " i=" << max_index;
  188. LOG(WARNING) << "L1:" << l1 << " L2:" << l2 << " L3:" << max_l;
  189. }
  190. return Error_manager(Error_code::WJ_REGION_RECTANGLE_ANGLE_ERROR);
  191. }
  192. double length = std::max(l1, l2);
  193. double width = std::min(l1, l2);
  194. // 车宽应位于[1.4, 2.0],车长应位于[2.2, 3.0]
  195. if (length > 2.100 && length < 3.000 && width > 1.400 && width < 2.100)
  196. {
  197. //生成第四个点
  198. cv::Point2f vec1 = ps - pc;
  199. cv::Point2f vec2 = pt - pc;
  200. cv::Point2f point4 = (vec1 + vec2) + pc;
  201. points.push_back(point4);
  202. if (print)
  203. {
  204. LOG(WARNING) << "3 wheels rectangle verify OK cos angle=" << cosa << " L=" << length
  205. << " w=" << width;
  206. }
  207. return Error_manager(Error_code::SUCCESS);
  208. }
  209. else
  210. {
  211. if (print)
  212. {
  213. LOG(WARNING) << "3 wheels rectangle verify Failed cos angle=" << cosa << " L=" << length
  214. << " w=" << width;
  215. }
  216. return Error_manager(Error_code::WJ_REGION_RECTANGLE_SIZE_ERROR);
  217. }
  218. }
  219. else
  220. {
  221. return Error_manager(Error_code::WJ_REGION_CLUSTER_SIZE_ERROR);
  222. }
  223. }
  224. /*
  225. * 仅仅聚类
  226. */
  227. Error_manager Region_detector::clustering_only(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
  228. std::vector<pcl::PointCloud<pcl::PointXYZ>> &seg_clouds, bool print)
  229. {
  230. // 1.判断参数合法性
  231. if (cloud_in->size() <= 0)
  232. return Error_manager(Error_code::WJ_REGION_EMPTY_CLOUD);
  233. // 2.聚类
  234. pcl::search::KdTree<pcl::PointXYZ>::Ptr kdtree(new pcl::search::KdTree<pcl::PointXYZ>);
  235. kdtree->setInputCloud(cloud_in);
  236. pcl::EuclideanClusterExtraction<pcl::PointXYZ> clustering;
  237. // 设置聚类的最小值 2cm (small values may cause objects to be divided
  238. // in several clusters, whereas big values may join objects in a same cluster).
  239. clustering.setClusterTolerance(0.5);
  240. // 设置聚类的小点数和最大点云数
  241. clustering.setMinClusterSize(10);
  242. clustering.setMaxClusterSize(500);
  243. clustering.setSearchMethod(kdtree);
  244. clustering.setInputCloud(cloud_in);
  245. std::vector<pcl::PointIndices> clusters;
  246. clustering.extract(clusters);
  247. if(clusters.size() <= 0)
  248. return Error_manager(Error_code::WJ_REGION_EMPTY_CLOUD);
  249. for (int i = 0; i < clusters.size(); ++i)
  250. {
  251. seg_clouds.push_back(pcl::PointCloud<pcl::PointXYZ>());
  252. }
  253. int j = 0;
  254. for (std::vector<pcl::PointIndices>::const_iterator it = clusters.begin(); it != clusters.end(); ++it)
  255. {
  256. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster(new pcl::PointCloud<pcl::PointXYZ>);
  257. //创建新的点云数据集cloud_cluster,将所有当前聚类写入到点云数据集中
  258. for (std::vector<int>::const_iterator pit = it->indices.begin(); pit != it->indices.end(); ++pit)
  259. {
  260. cloud_cluster->points.push_back(cloud_in->points[*pit]);
  261. cloud_cluster->width = cloud_cluster->points.size();
  262. cloud_cluster->height = 1;
  263. cloud_cluster->is_dense = true;
  264. }
  265. seg_clouds[j] = *cloud_cluster;
  266. j++;
  267. }
  268. if (print)
  269. {
  270. LOG(INFO) << " cluster classes:" << clusters.size();
  271. }
  272. return SUCCESS;
  273. }
  274. /**
  275. * 聚类并通过矩形判断函数
  276. * 传入原始点云,传出角点与聚类出的点云
  277. * 返回 WJ_REGION_EMPTY_CLOUD, WJ_REGION_RECTANGLE_ANGLE_ERROR, WJ_REGION_RECTANGLE_SIZE_ERROR,
  278. * WJ_REGION_RECTANGLE_SYMMETRY_ERROR, WJ_REGION_CLUSTER_SIZE_ERROR, SUCCESS
  279. * */
  280. Error_manager Region_detector::clustering(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in, std::vector<cv::Point2f> &corner_points, std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> &seg_clouds, bool print)
  281. {
  282. // 1.判断参数合法性
  283. if (cloud_in->size() <= 0)
  284. return Error_manager(Error_code::WJ_REGION_EMPTY_CLOUD);
  285. // 2.聚类
  286. pcl::search::KdTree<pcl::PointXYZ>::Ptr kdtree(new pcl::search::KdTree<pcl::PointXYZ>);
  287. kdtree->setInputCloud(cloud_in);
  288. pcl::EuclideanClusterExtraction<pcl::PointXYZ> clustering;
  289. // 设置聚类的最小值 2cm (small values may cause objects to be divided
  290. // in several clusters, whereas big values may join objects in a same cluster).
  291. clustering.setClusterTolerance(0.2);
  292. // 设置聚类的小点数和最大点云数
  293. clustering.setMinClusterSize(10);
  294. clustering.setMaxClusterSize(500);
  295. clustering.setSearchMethod(kdtree);
  296. clustering.setInputCloud(cloud_in);
  297. std::vector<pcl::PointIndices> clusters;
  298. clustering.extract(clusters);
  299. if(clusters.size() <= 0)
  300. return Error_manager(Error_code::WJ_REGION_EMPTY_CLOUD);
  301. for (int i = 0; i < clusters.size(); ++i)
  302. {
  303. seg_clouds.push_back(pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>));
  304. }
  305. int j = 0;
  306. for (std::vector<pcl::PointIndices>::const_iterator it = clusters.begin(); it != clusters.end(); ++it)
  307. {
  308. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cluster(new pcl::PointCloud<pcl::PointXYZ>);
  309. //创建新的点云数据集cloud_cluster,将所有当前聚类写入到点云数据集中
  310. for (std::vector<int>::const_iterator pit = it->indices.begin(); pit != it->indices.end(); ++pit)
  311. {
  312. cloud_cluster->points.push_back(cloud_in->points[*pit]);
  313. cloud_cluster->width = cloud_cluster->points.size();
  314. cloud_cluster->height = 1;
  315. cloud_cluster->is_dense = true;
  316. }
  317. seg_clouds[j] = cloud_cluster;
  318. j++;
  319. }
  320. if (print)
  321. {
  322. LOG(INFO) << " cluster classes:" << clusters.size();
  323. }
  324. // 3.分别计算每团点云几何中心,作为矩形角点
  325. corner_points.clear();
  326. for (int i = 0; i < clusters.size(); ++i)
  327. {
  328. if (seg_clouds.size() <= i || seg_clouds[i]->size() == 0)
  329. continue;
  330. float sumX = 0, sumY = 0;
  331. for (int j = 0; j < seg_clouds[i]->size(); ++j)
  332. {
  333. sumX += seg_clouds[i]->points[j].x;
  334. sumY += seg_clouds[i]->points[j].y;
  335. }
  336. float center_x = sumX / float(seg_clouds[i]->size());
  337. float center_y = sumY / float(seg_clouds[i]->size());
  338. corner_points.push_back(cv::Point2f(center_x, center_y));
  339. }
  340. /*char buf[255]={0};
  341. for (int k = 0; k < corner_points.size(); ++k) {
  342. sprintf(buf+strlen(buf), "point %d: (%.2f, %.2f)__", k, corner_points[k].x, corner_points[k].y);
  343. }
  344. LOG(WARNING) << buf;*/
  345. cv::RotatedRect t_rect=cv::minAreaRect(corner_points);
  346. //display(t_rect,cv::Scalar(255,0,0));
  347. return isRect(corner_points, print);
  348. }
  349. /**
  350. * 省略传出参数的四轮检测算法函数
  351. * 传入待检测点云
  352. * 返回值检测结果
  353. * */
  354. Error_manager Region_detector::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in)
  355. {
  356. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  357. // 1.预处理
  358. Error_manager result = preprocess(cloud_in, cloud_filtered);
  359. if (result == SUCCESS)
  360. {
  361. std::vector<cv::Point2f> corner_points;
  362. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> seg_clouds;
  363. // 2.聚类与矩形校验
  364. result = clustering(cloud_filtered, corner_points, seg_clouds);
  365. }
  366. return result;
  367. }
  368. /**
  369. * ceres优化
  370. * 优化变量:中心点、角度、轮距与宽度的四轮点云检测函数
  371. * */
  372. Error_manager Region_detector::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_in, double &x, double &y, double &c, double &front_wheel_theta,
  373. double &wheelbase, double &width,bool print)
  374. {
  375. Error_manager result = Error_manager(Error_code::SUCCESS);
  376. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>));
  377. // 1.预处理
  378. result = preprocess(cloud_in, cloud_filtered);
  379. if (result != SUCCESS)
  380. return result;
  381. // 2.聚类
  382. std::vector<pcl::PointCloud<pcl::PointXYZ>> seg_clouds;
  383. result = clustering_only(cloud_filtered, seg_clouds, print);
  384. if (result != SUCCESS)
  385. return result;
  386. cloud_in->clear();
  387. cloud_in->operator+=(*cloud_filtered);
  388. detect_wheel_ceres::Detect_result detect_result{x,y,c,wheelbase,width,front_wheel_theta};
  389. std::string error_info;
  390. if(!m_detector_ceres.detect(seg_clouds, detect_result, error_info))
  391. {
  392. if(print)
  393. {
  394. LOG(WARNING) << error_info;
  395. }
  396. return WJ_REGION_CERES_SOLVE_ERROR;
  397. }
  398. else {
  399. x = detect_result.cx;
  400. y = detect_result.cy;
  401. c = detect_result.theta;
  402. wheelbase = detect_result.wheel_base;
  403. width = detect_result.width;
  404. front_wheel_theta = detect_result.front_theta;
  405. cloud_in->push_back(pcl::PointXYZ(x, y, 0));
  406. cloud_in->push_back(pcl::PointXYZ(x+(width-0.22)/2.0 * cos((c - 90)*M_PI/180.0) - wheelbase/2.0*sin((c - 90)*M_PI/180.0), y+(width-0.22)/2.0 * sin((c - 90)*M_PI/180.0) + wheelbase/2.0*cos((c - 90)*M_PI/180.0), 0));
  407. cloud_in->push_back(pcl::PointXYZ(x+(width-0.22)/2.0 * cos((c - 90)*M_PI/180.0) + wheelbase/2.0*sin((c - 90)*M_PI/180.0), y+(width-0.22)/2.0 * sin((c - 90)*M_PI/180.0) - wheelbase/2.0*cos((c - 90)*M_PI/180.0), 0));
  408. cloud_in->push_back(pcl::PointXYZ(x+(-width+0.22)/2.0 * cos((c - 90)*M_PI/180.0) - wheelbase/2.0*sin((c - 90)*M_PI/180.0), y+(-width+0.22)/2.0 * sin((c - 90)*M_PI/180.0) + wheelbase/2.0*cos((c - 90)*M_PI/180.0), 0));
  409. cloud_in->push_back(pcl::PointXYZ(x+(-width+0.22)/2.0 * cos((c - 90)*M_PI/180.0) + wheelbase/2.0*sin((c - 90)*M_PI/180.0), y+(-width+0.22)/2.0 * sin((c - 90)*M_PI/180.0) - wheelbase/2.0*cos((c - 90)*M_PI/180.0), 0));
  410. }
  411. return Error_manager(Error_code::SUCCESS);
  412. }
  413. //增加异常信息传出
  414. Error_manager Region_detector::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_in, double &x, double &y, double &c,double& front_wheel_theta,
  415. double &wheelbase, double &width, std::string &error_info, bool print)
  416. {
  417. Error_manager result = Error_manager(Error_code::SUCCESS);
  418. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>));
  419. // 1.预处理
  420. result = preprocess(cloud_in, cloud_filtered);
  421. if (result != SUCCESS) {
  422. error_info="预处理失败";
  423. return result;
  424. }
  425. // 2.聚类
  426. std::vector<pcl::PointCloud<pcl::PointXYZ>> seg_clouds;
  427. result = clustering_only(cloud_filtered, seg_clouds, print);
  428. if (result != SUCCESS) {
  429. error_info="聚类失败";
  430. return result;
  431. }
  432. detect_wheel_ceres::Detect_result detect_result{x,y,c,wheelbase,width,front_wheel_theta};
  433. if(!m_detector_ceres.detect(seg_clouds, detect_result, error_info))
  434. return WJ_REGION_CERES_SOLVE_ERROR;
  435. else {
  436. x = detect_result.cx;
  437. y = detect_result.cy;
  438. c = detect_result.theta;
  439. wheelbase = detect_result.wheel_base;
  440. width = detect_result.width;
  441. front_wheel_theta = detect_result.front_theta;
  442. }
  443. return Error_manager(Error_code::SUCCESS);
  444. }
  445. /**
  446. * 输出中心点、角度、轮距与宽度的四轮点云检测函数
  447. * */
  448. Error_manager Region_detector::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_in, double &x, double &y, double &c, double &wheelbase, double &width, bool print)
  449. {
  450. Error_manager result = Error_manager(Error_code::SUCCESS);
  451. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>));
  452. // 1.预处理
  453. result = preprocess(cloud_in, cloud_filtered);
  454. if (result != SUCCESS)
  455. return result;
  456. // 2.聚类计算角点
  457. std::vector<cv::Point2f> corner_points;
  458. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> seg_clouds;
  459. result = clustering(cloud_filtered, corner_points, seg_clouds, print);
  460. if (result != SUCCESS)
  461. return result;
  462. // 修改原始点云为预处理后点云,并加入角点供查验
  463. cloud_in->clear();
  464. cloud_in->operator+=(*cloud_filtered);
  465. for (size_t i = 0; i < corner_points.size(); i++)
  466. {
  467. cloud_in->points.push_back(pcl::PointXYZ(corner_points[i].x, corner_points[i].y, 0.0));
  468. }
  469. // convert all points after preprocessed into 2d
  470. std::vector<cv::Point2f> all_points;
  471. // car center
  472. for (int j = 0; j < cloud_filtered->size(); ++j)
  473. {
  474. all_points.push_back(cv::Point2f(cloud_filtered->points[j].x, cloud_filtered->points[j].y));
  475. }
  476. // find bounding rectangle of all wheel points
  477. cv::RotatedRect wheel_box = cv::minAreaRect(all_points);
  478. x = wheel_box.center.x;
  479. y = wheel_box.center.y;
  480. // add center point to the input cloud for further check
  481. cloud_in->points.push_back(pcl::PointXYZ(x, y, 0.0));
  482. // 长边向量
  483. cv::Point2f vec;
  484. cv::Point2f vertice[4];
  485. wheel_box.points(vertice);
  486. float len1 = pow(vertice[0].x - vertice[1].x, 2.0) + pow(vertice[0].y - vertice[1].y, 2.0);
  487. float len2 = pow(vertice[1].x - vertice[2].x, 2.0) + pow(vertice[1].y - vertice[2].y, 2.0);
  488. // 寻找长边,倾角为长边与x轴夹角
  489. if (len1 > len2)
  490. {
  491. vec.x = vertice[0].x - vertice[1].x;
  492. vec.y = vertice[0].y - vertice[1].y;
  493. }
  494. else
  495. {
  496. vec.x = vertice[1].x - vertice[2].x;
  497. vec.y = vertice[1].y - vertice[2].y;
  498. }
  499. float angle_x = 180.0 / M_PI * acos(vec.x / sqrt(vec.x * vec.x + vec.y * vec.y));
  500. c = angle_x;
  501. // get line formula, normal is (cos(theta), sin(theta)), towards the long side
  502. // the line formula is: nx * x + ny * y + (-(nx*cx+ny*cy)) = 0
  503. Eigen::Vector2f normal, center_point;
  504. normal << vec.x / sqrt(vec.x * vec.x + vec.y * vec.y), vec.y / sqrt(vec.x * vec.x + vec.y * vec.y);
  505. center_point << x, y;
  506. float line_param_c = -1 * center_point.transpose() * normal;
  507. // get rotation matrix, get the angle towards normal vector, rather than x axis
  508. // R = [ cos -sin]
  509. // [ sin cos]
  510. float rotate_angle = M_PI_2 - acos(vec.x / sqrt(vec.x * vec.x + vec.y * vec.y));
  511. Eigen::Matrix2f rotation_matrix;
  512. rotation_matrix << cos(rotate_angle), -sin(rotate_angle), sin(rotate_angle), cos(rotate_angle);
  513. // find min x and max x, separate y values according to the line, calculate difference between mean of y values as wheelbase
  514. float min_x = 20, max_x = 0;
  515. float y_values0 = 0, y_values1 = 0;
  516. int count0 = 0, count1 = 0;
  517. for (size_t i = 0; i < seg_clouds.size(); i++)
  518. {
  519. if (seg_clouds[i]->size() <= 0)
  520. continue;
  521. for (size_t j = 0; j < seg_clouds[i]->size(); j++)
  522. {
  523. // origin point and the point rotated around the origin
  524. Eigen::Vector2f vec, vec_rot;
  525. vec << seg_clouds[i]->points[j].x, seg_clouds[i]->points[j].y;
  526. vec_rot = rotation_matrix * (vec - center_point) + center_point;
  527. // find min max x
  528. if (vec_rot[0] < min_x)
  529. min_x = vec_rot[0];
  530. if (vec_rot[0] > max_x)
  531. max_x = vec_rot[0];
  532. // separate point as two clusters(front and back), calc y values respectively
  533. if (normal.transpose() * vec + line_param_c > 0)
  534. {
  535. y_values0 += vec_rot[1];
  536. count0 += 1;
  537. }
  538. else
  539. {
  540. y_values1 += vec_rot[1];
  541. count1 += 1;
  542. }
  543. }
  544. }
  545. // check if front and back both has points
  546. if (count0 > 0 && count1 > 0)
  547. {
  548. y_values0 /= count0;
  549. y_values1 /= count1;
  550. wheelbase = fabs(y_values1 - y_values0);
  551. width = fabs(min_x - max_x);
  552. // LOG(INFO) << "--------detector find width, wheelbase: " << width << ", " << wheelbase << ", y means: [" << y_values0 << ", " << y_values1 << "] -----";
  553. cloud_in->points.push_back(pcl::PointXYZ(min_x, y, 0.0));
  554. cloud_in->points.push_back(pcl::PointXYZ(max_x, y, 0.0));
  555. cloud_in->points.push_back(pcl::PointXYZ(x, y_values0, 0.0));
  556. cloud_in->points.push_back(pcl::PointXYZ(x, y_values1, 0.0));
  557. }
  558. else
  559. {
  560. // calculate wheelbase according to corner points
  561. // wheelbase = std::max(wheel_box.size.width, wheel_box.size.height);
  562. // LOG(INFO) << "--------detector find border: [" << wheel_box.size.width << ", " << wheel_box.size.height << "] -----";
  563. cv::RotatedRect wheel_center_box = cv::minAreaRect(corner_points);
  564. wheelbase = std::max(wheel_center_box.size.width, wheel_center_box.size.height);
  565. width = std::min(wheel_box.size.width, wheel_box.size.height);
  566. }
  567. return Error_manager(Error_code::SUCCESS);
  568. }