region_detect.cpp 24 KB

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