region_detect.cpp 25 KB

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