region_detect.cpp 19 KB

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