cnn3d_segmentation.cpp 23 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705
  1. #include "cnn3d_segmentation.h"
  2. #include "tf_wheel_3Dcnn_api.h"
  3. #include <iostream>
  4. #include <glog/logging.h>
  5. #include <pcl/segmentation/extract_clusters.h>
  6. #include <pcl/kdtree/kdtree.h>
  7. #include <pcl/sample_consensus/model_types.h>
  8. #include <pcl/filters/statistical_outlier_removal.h>
  9. #include <pcl/filters/project_inliers.h>
  10. #include <pcl/surface/convex_hull.h>
  11. #include <pcl/features/moment_of_inertia_estimation.h>
  12. #include <pcl/common/centroid.h>
  13. void save_rgb_cloud_txt(std::string txt, pcl::PointCloud<pcl::PointXYZRGB>::Ptr pCloud)
  14. {
  15. std::ofstream os;
  16. os.open(txt, std::ios::out);
  17. for (int i = 0; i < pCloud->points.size(); i++)
  18. {
  19. pcl::PointXYZRGB point = pCloud->points[i];
  20. char buf[255];
  21. memset(buf, 0, 255);
  22. sprintf(buf, "%f %f %f %d %d %d\n", point.x, point.y, point.z, point.r, point.g, point.b);
  23. os.write(buf, strlen(buf));
  24. }
  25. os.close();
  26. }
  27. double Cnn3d_segmentation::distance(cv::Point2f p1, cv::Point2f p2)
  28. {
  29. return sqrt(pow(p1.x - p2.x, 2.0) + pow(p1.y - p2.y, 2.0));
  30. }
  31. cv::RotatedRect minAreaRect_cloud(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud)
  32. {
  33. std::vector<cv::Point2f> points;
  34. for (int i = 0; i < cloud->size(); ++i)
  35. {
  36. pcl::PointXYZRGB point = cloud->points[i];
  37. points.push_back(cv::Point2f(point.x, point.y));
  38. }
  39. cv::RotatedRect rect= cv::minAreaRect(points);
  40. return rect;
  41. }
  42. cv::RotatedRect minAreaRect_cloud(std::vector<cv::Point2f> centers)
  43. {
  44. cv::RotatedRect rect = cv::minAreaRect(centers);
  45. return rect;
  46. }
  47. Error_manager Cnn3d_segmentation::set_parameter(int l, int w, int h,int freq,int classes)
  48. {
  49. m_lenth = l;
  50. m_width = w;
  51. m_height = h;
  52. m_freq = freq;
  53. m_nClass = classes;
  54. return SUCCESS;
  55. }
  56. Cnn3d_segmentation::Cnn3d_segmentation(int l, int w, int h,int freq,int classes)
  57. {
  58. m_lenth = l;
  59. m_width = w;
  60. m_height = h;
  61. m_freq = freq;
  62. m_nClass = classes;
  63. }
  64. Cnn3d_segmentation::~Cnn3d_segmentation()
  65. {
  66. //3dcnn 原校验功能保留,不加载网络
  67. //tf_wheel_3dcnn_close();
  68. }
  69. Error_manager Cnn3d_segmentation::init(std::string weights)
  70. {
  71. //3dcnn 原校验功能保留,不加载网络
  72. return SUCCESS;
  73. /*if (0 != tf_wheel_3dcnn_init(weights, m_lenth,m_width,m_height))
  74. {
  75. std::string error_description="tf_wheel_3Dcnn model load failed :";
  76. error_description+=weights;
  77. return Error_manager(LOCATER_3DCNN_INIT_FAILED,MINOR_ERROR,error_description);
  78. }
  79. //空跑一次
  80. float* data = (float*)malloc(m_lenth*m_width*m_height*sizeof(float));
  81. float* pout = (float*)malloc(m_lenth*m_width*m_height*m_nClass*sizeof(float));
  82. if (!tf_wheel_3dcnn_predict(data, pout))
  83. {
  84. free(data);
  85. free(pout);
  86. return Error_manager(LOCATER_3DCNN_PREDICT_FAILED,MINOR_ERROR,"first locate 3dcnn failed");
  87. }
  88. free(data);
  89. free(pout);
  90. return SUCCESS;*/
  91. }
  92. void save_cloudT(std::string txt, pcl::PointCloud<pcl::PointXYZRGB>& pCloud)
  93. {
  94. std::ofstream os;
  95. os.open(txt, std::ios::out);
  96. for (int i = 0; i < pCloud.points.size(); i++)
  97. {
  98. pcl::PointXYZRGB point = pCloud.points[i];
  99. char buf[255];
  100. memset(buf, 0, 255);
  101. sprintf(buf, "%f %f %f\n", point.x, point.y, point.z);
  102. os.write(buf, strlen(buf));
  103. }
  104. os.close();
  105. }
  106. //解析4个轮胎
  107. Error_manager Cnn3d_segmentation::analytic_wheel(std::map<int,pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& wheel_cloud_map, bool cloud_aggregation_flag,
  108. Locate_information* p_locate_information,
  109. bool save_flag, std::string save_dir)
  110. {
  111. Error_manager t_error;
  112. if ( p_locate_information == NULL )
  113. {
  114. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  115. " analytic_wheel POINTER_IS_NULL ");
  116. }
  117. //第一步 离群点过滤
  118. t_error = filter_cloud_with_outlier_for_map(wheel_cloud_map);
  119. if ( t_error != Error_code::SUCCESS)
  120. {
  121. return t_error;
  122. }
  123. //第二步, //将map分为4个轮胎
  124. //注: 前面的雷达扫描并point sift之后, 可能只能识别3个轮胎, 此时允许3个轮胎 继续运行.
  125. std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> wheel_source_vector; //拆分后的轮胎点云, 不同的轮胎点是分开的,
  126. t_error = split_wheel_cloud(wheel_cloud_map, cloud_aggregation_flag, wheel_source_vector, save_flag, save_dir);
  127. if ( t_error != Error_code::SUCCESS)
  128. {
  129. return t_error;
  130. }
  131. //第三步, pca过滤, 并计算每个轮子的中心点
  132. std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> wheel_pca_vector; //pca过滤后的点云
  133. t_error = filter_cloud_with_pca(wheel_source_vector, wheel_pca_vector, save_flag, save_dir);
  134. if ( t_error != Error_code::SUCCESS)
  135. {
  136. return t_error;
  137. }
  138. //第四步,提取关键矩形,
  139. cv::RotatedRect rect_of_wheel_center; //4个轮胎中心点构成的矩形
  140. cv::RotatedRect rect_of_wheel_cloud; //所有点云构成的矩形
  141. t_error = extract_key_rect(wheel_pca_vector, rect_of_wheel_center, rect_of_wheel_cloud, save_flag, save_dir);
  142. if ( t_error != Error_code::SUCCESS)
  143. {
  144. return t_error;
  145. }
  146. //第五步, //通过关键矩形, 计算出车辆的定位信息, (输出中心点的x和y, 前后轮距, 左右轮距, 旋转角)
  147. t_error = calculate_key_rect(rect_of_wheel_center, rect_of_wheel_cloud, p_locate_information);
  148. if ( t_error != Error_code::SUCCESS)
  149. {
  150. return t_error;
  151. }
  152. return Error_code::SUCCESS;
  153. }
  154. //过滤离群点,
  155. Error_manager Cnn3d_segmentation::filter_cloud_with_outlier_for_map(std::map<int,pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& wheel_cloud_map)
  156. {
  157. Error_manager t_error;
  158. Error_manager t_result;
  159. //遍历map, 对点云进行 离群点过滤
  160. for (auto iter = wheel_cloud_map.begin(); iter != wheel_cloud_map.end(); ++iter)
  161. {
  162. //过滤离群点,
  163. t_error = filter_cloud_with_outlier(iter->second);
  164. if (t_error != Error_code::SUCCESS)
  165. {
  166. char buf[256] = {0};
  167. sprintf(buf, " map.id = %d, filter_cloud_with_outlier error", iter->first );
  168. t_error.add_error_description(buf, strlen(buf) );
  169. t_result.compare_and_cover_error(t_error);
  170. //注:这里不直接return,而是要把map全部执行完成
  171. }
  172. }
  173. if ( t_result != Error_code::SUCCESS)
  174. {
  175. return t_result;
  176. }
  177. return Error_code::SUCCESS;
  178. }
  179. //过滤离群点,
  180. Error_manager Cnn3d_segmentation::filter_cloud_with_outlier(pcl::PointCloud<pcl::PointXYZRGB>::Ptr p_cloud)
  181. {
  182. if(p_cloud.get()==NULL)
  183. {
  184. return Error_manager(LOCATER_3DCNN_INPUT_CLOUD_UNINIT,MINOR_ERROR,"Cnn3d_segmentation input cloud uninit");
  185. }
  186. if(p_cloud->size()<=0)
  187. {
  188. return Error_manager(LOCATER_3DCNN_INPUT_CLOUD_EMPTY,MINOR_ERROR,"Cnn3d_segmentation input cloud empty");
  189. }
  190. pcl::StatisticalOutlierRemoval<pcl::PointXYZRGB> sorfilter(true); // Initializing with true will allow us to extract the removed indices
  191. sorfilter.setInputCloud(p_cloud);
  192. sorfilter.setMeanK(20);
  193. sorfilter.setStddevMulThresh(2.0);
  194. sorfilter.filter(*p_cloud);
  195. return Error_code::SUCCESS;
  196. }
  197. //拆分车轮, 将map分为4个轮胎
  198. //wheel_cloud_map, 输入点云
  199. //cloud_out_vector, 输出4轮点云vector, (vector是空的, 函数内部会添加4个点云)
  200. Error_manager Cnn3d_segmentation::split_wheel_cloud(std::map<int,pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& wheel_cloud_map, bool cloud_aggregation_flag,
  201. std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & wheel_cloud_vector,
  202. bool save_flag, std::string save_dir)
  203. {
  204. Error_manager t_error;
  205. wheel_cloud_vector.clear();
  206. //如果输入的map只有一个cloud, 那么就要进行聚类, 拆分为4个轮胎
  207. if ( wheel_cloud_map.size() == 1 && cloud_aggregation_flag == true )
  208. {
  209. t_error = split_cloud_with_kmeans(wheel_cloud_map[0], wheel_cloud_vector, save_flag, save_dir);
  210. //注:此时wheel_clouds_vector里面可能有一个的点云为空的,
  211. if ( t_error != Error_code::SUCCESS )
  212. {
  213. return t_error;
  214. }
  215. }
  216. //如果输入的map有3~4个cloud, 那么就直接复制,
  217. else if ( (wheel_cloud_map.size() == CNN3D_WHEEL_NUMBER || wheel_cloud_map.size() == CNN3D_WHEEL_NUMBER - 1 )
  218. && cloud_aggregation_flag == false )
  219. {
  220. for (auto iter = wheel_cloud_map.begin(); iter != wheel_cloud_map.end(); ++iter)
  221. {
  222. wheel_cloud_vector.push_back(iter->second);
  223. //注:此时的 clouds_vector 可能有3~4个点云,
  224. }
  225. }
  226. else
  227. {
  228. return Error_manager(Error_code::LOCATER_3DCNN_INPUT_CLOUD_MAP_ERROR, Error_level::MINOR_ERROR,
  229. " split_wheel_cloud p_wheel_cloud_map size error ");
  230. }
  231. return Error_code::SUCCESS;
  232. }
  233. //聚类, 将一个车轮点云拆分为4个轮胎点云,
  234. //p_cloud_in, 输入点云
  235. //cloud_out_vector, 输出4轮点云vector, (vector是空的, 函数内部会添加4个点云)
  236. Error_manager Cnn3d_segmentation::split_cloud_with_kmeans(pcl::PointCloud<pcl::PointXYZRGB>::Ptr p_cloud_in,
  237. std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & cloud_out_vector,
  238. bool save_flag, std::string save_dir)
  239. {
  240. if(p_cloud_in.get()==NULL)
  241. {
  242. return Error_manager(LOCATER_3DCNN_INPUT_CLOUD_UNINIT,MINOR_ERROR,"Cnn3d_segmentation input cloud uninit");
  243. }
  244. if(p_cloud_in->size()<=0)
  245. {
  246. return Error_manager(LOCATER_3DCNN_INPUT_CLOUD_EMPTY,MINOR_ERROR,"Cnn3d_segmentation input cloud empty");
  247. }
  248. //为cloud_out_vector重新分配内存, 添加4个轮胎点云
  249. cloud_out_vector.clear();
  250. for(int i=0;i<CNN3D_WHEEL_NUMBER;++i)
  251. {
  252. pcl::PointCloud<pcl::PointXYZRGB>::Ptr t_cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
  253. cloud_out_vector.push_back(t_cloud);
  254. }
  255. //开始分割,
  256. //注: 实际上只考虑了x和y轴, 以水平面为标准,
  257. // 根据每个点到的4个角落的距离, 分为4个车轮
  258. //p_cloud_in转化为opencv的点云
  259. std::vector<cv::Point2f> cv_points;
  260. for (int i = 0; i < p_cloud_in->size(); ++i)
  261. {
  262. cv::Point2f point(p_cloud_in->points[i].x, p_cloud_in->points[i].y);
  263. cv_points.push_back(point);
  264. }
  265. //rect 为输入点云的外截最小矩形
  266. cv::RotatedRect rect = cv::minAreaRect(cv_points);
  267. //corner 为矩形的4个角落的点
  268. cv::Point2f corner[CNN3D_WHEEL_NUMBER];
  269. rect.points(corner);
  270. //遍历输入点云
  271. for (int i = 0; i < p_cloud_in->size(); ++i)
  272. {
  273. //计算出当前点距离哪个角落最近,
  274. double min_distance = 9999999.9; //当前点距离角落的最小距离
  275. int cluste_index = 0; //当前点最近角落的索引编号
  276. cv::Point2f point(p_cloud_in->points[i].x, p_cloud_in->points[i].y);
  277. for (int j = 0; j < CNN3D_WHEEL_NUMBER; ++j)
  278. {
  279. double dis=distance(point, corner[j]);
  280. if (dis < min_distance)
  281. {
  282. min_distance = dis;
  283. cluste_index = j;
  284. }
  285. }
  286. //根据点位的归属, 将其重新标色并填充到对应的输出点云
  287. if (cluste_index == 0)
  288. {
  289. p_cloud_in->points[i].r = 255;
  290. p_cloud_in->points[i].g = 0;
  291. p_cloud_in->points[i].b = 0;
  292. }
  293. else if (cluste_index == 1)
  294. {
  295. p_cloud_in->points[i].r = 0;
  296. p_cloud_in->points[i].g = 255;
  297. p_cloud_in->points[i].b = 0;
  298. }
  299. else if (cluste_index == 2)
  300. {
  301. p_cloud_in->points[i].r = 0;
  302. p_cloud_in->points[i].g = 0;
  303. p_cloud_in->points[i].b = 255;
  304. }
  305. else
  306. {
  307. p_cloud_in->points[i].r = 255;
  308. p_cloud_in->points[i].g = 255;
  309. p_cloud_in->points[i].b = 255;
  310. }
  311. cloud_out_vector[cluste_index]->push_back(p_cloud_in->points[i]);
  312. }
  313. //保存修改颜色后的点云.
  314. if ( save_flag )
  315. {
  316. std::string save_file=save_dir+"/cnn3d_with_kmeans.txt";
  317. save_rgb_cloud_txt(save_file, p_cloud_in);
  318. }
  319. return Error_code::SUCCESS;
  320. }
  321. //pca, 使用pca算法对每个车轮的点云进行过滤,
  322. Error_manager Cnn3d_segmentation::filter_cloud_with_pca(std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & cloud_in_vector,
  323. std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & cloud_out_vector,
  324. bool save_flag, std::string save_dir)
  325. {
  326. Error_manager t_error;
  327. cloud_out_vector.clear();
  328. for (int i = 0; i < cloud_in_vector.size(); ++i)
  329. {
  330. if ( cloud_in_vector[i]->size() != 0 )
  331. {
  332. pcl::PointCloud<pcl::PointXYZRGB>::Ptr tp_cloud_pca(new pcl::PointCloud<pcl::PointXYZRGB>);
  333. //对点云作pca分析,然后在最小轴方向过滤, 防止轮胎左右两边出现噪声
  334. t_error = pca_minist_axis_filter(cloud_in_vector[i],tp_cloud_pca);
  335. if ( t_error != Error_code::SUCCESS )
  336. {
  337. return t_error;
  338. }
  339. cloud_out_vector.push_back(tp_cloud_pca);
  340. if ( save_flag )
  341. {
  342. char buf[255]={0};
  343. sprintf(buf,"%s/cnn3d_pca_wheel_%d.txt",save_dir.c_str(),i);
  344. save_cloudT(buf,*tp_cloud_pca);
  345. }
  346. }
  347. }
  348. //验证 vector 的大小
  349. if ( cloud_out_vector.size() < CNN3D_WHEEL_NUMBER - 1)
  350. {
  351. return Error_manager(Error_code::LOCATER_3DCNN_PCA_OUT_ERROR, Error_level::MINOR_ERROR,
  352. " wheel_pca_vector.size() < 3 ");
  353. }
  354. return Error_code::SUCCESS;
  355. }
  356. //对点云作pca分析,然后在最小轴方向过滤, 防止轮胎左右两边出现噪声
  357. Error_manager Cnn3d_segmentation::pca_minist_axis_filter(pcl::PointCloud<pcl::PointXYZRGB>::Ptr p_cloud_in,
  358. pcl::PointCloud<pcl::PointXYZRGB>::Ptr p_cloud_out)
  359. {
  360. if(p_cloud_in.get()==NULL)
  361. {
  362. return Error_manager(LOCATER_3DCNN_INPUT_CLOUD_UNINIT,MINOR_ERROR,"Cnn3d_segmentation input cloud uninit");
  363. }
  364. if(p_cloud_in->size()<=0)
  365. {
  366. return Error_manager(LOCATER_3DCNN_INPUT_CLOUD_EMPTY,MINOR_ERROR,"Cnn3d_segmentation input cloud empty");
  367. }
  368. //pca寻找主轴
  369. pcl::MomentOfInertiaEstimation <pcl::PointXYZRGB> feature_extractor;
  370. feature_extractor.setInputCloud (p_cloud_in);
  371. feature_extractor.compute ();
  372. std::vector <float> moment_of_inertia;
  373. std::vector <float> eccentricity;
  374. pcl::PointXYZRGB min_point_AABB;
  375. pcl::PointXYZRGB max_point_AABB;
  376. pcl::PointXYZRGB min_point_OBB;
  377. pcl::PointXYZRGB max_point_OBB;
  378. pcl::PointXYZRGB position_OBB;
  379. Eigen::Matrix3f rotational_matrix_OBB;
  380. float major_value, middle_value, minor_value;
  381. Eigen::Vector3f major_vector, middle_vector, minor_vector;
  382. Eigen::Vector3f mass_center;
  383. feature_extractor.getMomentOfInertia (moment_of_inertia);
  384. feature_extractor.getEccentricity (eccentricity);
  385. feature_extractor.getAABB (min_point_AABB, max_point_AABB);
  386. feature_extractor.getOBB (min_point_OBB, max_point_OBB, position_OBB, rotational_matrix_OBB);
  387. feature_extractor.getEigenValues (major_value, middle_value, minor_value);
  388. feature_extractor.getEigenVectors (major_vector, middle_vector, minor_vector);
  389. feature_extractor.getMassCenter (mass_center);
  390. //根据minor_vector 最小主轴方向,以及中心点, 计算轴所在三维平面
  391. float x=mass_center[0];
  392. float y=mass_center[1];
  393. float z=mass_center[2];
  394. float a=minor_vector[0];
  395. float b=minor_vector[1];
  396. float c=minor_vector[2];
  397. float d=-(a*x+b*y+c*z);
  398. //计算各点距离平面的距离,距离操过轮胎的一半厚,舍弃(100mm)
  399. float S=sqrt(a*a+b*b+c*c);
  400. for(int i=0;i<p_cloud_in->size();++i)
  401. {
  402. pcl::PointXYZRGB point=p_cloud_in->points[i];
  403. if(fabs(point.x*a+point.y*b+point.z*c+d)/S <40 )
  404. {
  405. p_cloud_out->push_back(point);
  406. }
  407. }
  408. /*if(cloud_out->size()==0)
  409. {
  410. return Error_manager(LOCATER_3DCNN_PCA_OUT_CLOUD_EMPTY,MINOR_ERROR,"wheel pca filter out cloud empty");
  411. }*/
  412. return SUCCESS;
  413. }
  414. //提取关键矩形,
  415. //cloud_in_vector, 输入点云
  416. //rect_of_wheel_center, 输出4轮中心点构成的矩形
  417. //rect_of_wheel_cloud, 输出所有车轮点构成的矩形
  418. Error_manager Cnn3d_segmentation::extract_key_rect(std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> & cloud_in_vector,
  419. cv::RotatedRect & rect_of_wheel_center, cv::RotatedRect & rect_of_wheel_cloud,
  420. bool save_flag, std::string save_dir)
  421. {
  422. //验证 vector 的大小
  423. if ( cloud_in_vector.size() < CNN3D_WHEEL_NUMBER - 1)
  424. {
  425. return Error_manager(Error_code::LOCATER_3DCNN_EXTRACT_RECT_ERROR, Error_level::MINOR_ERROR,
  426. " cloud_in_vector.size() < 3 ");
  427. }
  428. Error_manager t_error;
  429. //4个轮子的中心点, 只要x和y轴的坐标,
  430. std::vector<cv::Point2f> wheel_center_vector;
  431. //取出轮胎的中心点
  432. for (int i = 0; i < cloud_in_vector.size(); ++i)
  433. {
  434. if ( cloud_in_vector[i]->size() != 0 )
  435. {
  436. //提取每个车轮中心点
  437. Eigen::Vector4f centroid;
  438. pcl::compute3DCentroid(*(cloud_in_vector[i]), centroid);
  439. wheel_center_vector.push_back(cv::Point2f(centroid[0],centroid[1]));
  440. }
  441. }
  442. //验证 vector 的大小
  443. int t_vector_size = wheel_center_vector.size();
  444. if ( wheel_center_vector.size() < CNN3D_WHEEL_NUMBER - 1)
  445. {
  446. return Error_manager(Error_code::LOCATER_3DCNN_EXTRACT_RECT_ERROR, Error_level::MINOR_ERROR,
  447. " wheel_center_vector.size() < 3 ");
  448. }
  449. //检查并修复关键点, 此时可以通过3个轮胎模拟出第四个轮胎的中心点位置, 并添加到 vector
  450. // t_error = check_and_repair_center(wheel_center_vector);
  451. if ( t_error != Error_code::SUCCESS )
  452. {
  453. return t_error;
  454. }
  455. //rect_of_wheel_center, 输出4轮中心点构成的矩形
  456. rect_of_wheel_center = minAreaRect_cloud(wheel_center_vector);
  457. // t_error = check_rect_size(rect_of_wheel_center);
  458. if ( t_error != Error_code::SUCCESS )
  459. {
  460. return t_error;
  461. }
  462. //将输入的车轮点云, 汇总为 cv::Point2f的vector
  463. std::vector<cv::Point2f> wheel_points_vector;
  464. for(int i=0;i<cloud_in_vector.size();++i)
  465. {
  466. for(int j=0;j<cloud_in_vector[i]->size();++j)
  467. wheel_points_vector.push_back(cv::Point2f(cloud_in_vector[i]->points[j].x,
  468. cloud_in_vector[i]->points[j].y));
  469. }
  470. //如果前面check_and_repair_center为wheel_center_vector添加了第四个中心点, 那么也要加入到wheel_points_vector
  471. if(t_vector_size == CNN3D_WHEEL_NUMBER - 1 && wheel_center_vector.size() == CNN3D_WHEEL_NUMBER)
  472. {
  473. wheel_points_vector.push_back(wheel_center_vector[CNN3D_WHEEL_NUMBER - 1]);
  474. }
  475. //rect_of_wheel_cloud, 输出所有车轮点构成的矩形
  476. rect_of_wheel_cloud = minAreaRect_cloud(wheel_points_vector);
  477. return Error_code::SUCCESS;
  478. }
  479. //检查并修复关键点, 此时可以通过3个轮胎模拟出第四个轮胎的中心点位置, 并添加到 vector
  480. Error_manager Cnn3d_segmentation::check_and_repair_center(std::vector<cv::Point2f> & cloud_centers)
  481. {
  482. //取四轮中心计算轴长
  483. return centers_is_rect(cloud_centers);
  484. }
  485. //判断矩形框是否找到
  486. //points:输入轮子中心点, 只能是3或者4个
  487. Error_manager Cnn3d_segmentation::centers_is_rect(std::vector<cv::Point2f>& points)
  488. {
  489. if (points.size() == 4)
  490. {
  491. double L[3] = {0.0};
  492. L[0] = distance(points[0], points[1]);
  493. L[1] = distance(points[1], points[2]);
  494. L[2] = distance(points[0], points[2]);
  495. double max_l = L[0];
  496. double l1 = L[1];
  497. double l2 = L[2];
  498. int max_index = 0;
  499. cv::Point2f ps = points[0], pt = points[1];
  500. cv::Point2f pc = points[2];
  501. for (int i = 1; i < 3; ++i) {
  502. if (L[i] > max_l) {
  503. max_index = i;
  504. max_l = L[i];
  505. l1 = L[abs(i + 1) % 3];
  506. l2 = L[abs(i + 2) % 3];
  507. ps = points[i % 3];
  508. pt = points[(i + 1) % 3];
  509. pc = points[(i + 2) % 3];
  510. }
  511. }
  512. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  513. if (fabs(cosa) >= 0.13) {
  514. char description[255]={0};
  515. sprintf(description,"angle cos value(%.2f) >0.13 ",cosa);
  516. return Error_manager(LOCATER_3DCNN_VERIFY_RECT_FAILED_4,MINOR_ERROR,description);
  517. }
  518. float width=std::min(l1,l2);
  519. float length=std::max(l1,l2);
  520. if(width<1400 || width >2000 || length >3300 ||length < 2200)
  521. {
  522. char description[255]={0};
  523. sprintf(description,"width<1400 || width >2100 || length >3300 ||length < 2100 l:%.1f,w:%.1f",length,width);
  524. return Error_manager(LOCATER_3DCNN_VERIFY_RECT_FAILED_4,MINOR_ERROR,description);
  525. }
  526. double d = distance(pc, points[3]);
  527. cv::Point2f center1 = (ps + pt) * 0.5;
  528. cv::Point2f center2 = (pc + points[3]) * 0.5;
  529. if (fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 150) {
  530. LOG(INFO) << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2;
  531. char description[255]={0};
  532. sprintf(description,"Verify failed-4 fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 150 ");
  533. return Error_manager(LOCATER_3DCNN_VERIFY_RECT_FAILED_4,MINOR_ERROR,description);
  534. }
  535. LOG(INFO) << " rectangle verify OK cos angle=" << cosa << " length off=" << fabs(d - max_l)
  536. << " center distance=" << distance(center1, center2);
  537. return SUCCESS;
  538. }
  539. else if(points.size()==3)
  540. {
  541. double L[3] = {0.0};
  542. L[0] = distance(points[0], points[1]);
  543. L[1] = distance(points[1], points[2]);
  544. L[2] = distance(points[0], points[2]);
  545. double max_l = L[0];
  546. double l1 = L[1];
  547. double l2 = L[2];
  548. int max_index = 0;
  549. cv::Point2f ps = points[0], pt = points[1];
  550. cv::Point2f pc = points[2];
  551. for (int i = 1; i < 3; ++i) {
  552. if (L[i] > max_l) {
  553. max_index = i;
  554. max_l = L[i];
  555. l1 = L[abs(i + 1) % 3];
  556. l2 = L[abs(i + 2) % 3];
  557. ps = points[i % 3];
  558. pt = points[(i + 1) % 3];
  559. pc = points[(i + 2) % 3];
  560. }
  561. }
  562. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  563. if (fabs(cosa) >= 0.12) {
  564. char description[255]={0};
  565. sprintf(description,"3 wheels angle cos value(%.2f) >0.12 ",cosa);
  566. return Error_manager(LOCATER_3DCNN_VERIFY_RECT_FAILED_3,MINOR_ERROR,description);
  567. }
  568. double l=std::max(l1,l2);
  569. double w=std::min(l1,l2);
  570. if(l>2100 && l<3300 && w>1400 && w<2100)
  571. {
  572. //生成第四个点
  573. cv::Point2f vec1=ps-pc;
  574. cv::Point2f vec2=pt-pc;
  575. cv::Point2f point4=(vec1+vec2)+pc;
  576. points.push_back(point4);
  577. LOG(INFO) << "3 wheels rectangle verify OK cos angle=" << cosa << " L=" << l
  578. << " w=" << w;
  579. return SUCCESS;
  580. }
  581. else
  582. {
  583. char description[255]={0};
  584. sprintf(description,"3 wheels rectangle verify Failed cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  585. return Error_manager(LOCATER_3DCNN_VERIFY_RECT_FAILED_3,MINOR_ERROR,description);
  586. }
  587. }
  588. return Error_code::SUCCESS;
  589. }
  590. //检查矩形的大小
  591. Error_manager Cnn3d_segmentation::check_rect_size(cv::RotatedRect& rect)
  592. {
  593. if ( std::min(rect.size.width, rect.size.height)>2.000 || std::min(rect.size.width, rect.size.height)<1.200)
  594. {
  595. return Error_manager(Error_code::LOCATER_3DCNN_RECT_SIZE_ERROR, Error_level::MINOR_ERROR,
  596. " check_rect_size error ");
  597. }
  598. if (std::max(rect.size.width, rect.size.height) < 1.900 || std::max(rect.size.width, rect.size.height) > 3.600)
  599. {
  600. return Error_manager(Error_code::LOCATER_3DCNN_RECT_SIZE_ERROR, Error_level::MINOR_ERROR,
  601. " check_rect_size error ");
  602. }
  603. return Error_code::SUCCESS;
  604. }
  605. //通过关键矩形, 计算出车辆的定位信息, (输出中心点的x和y, 前后轮距, 左右轮距, 旋转角)
  606. Error_manager Cnn3d_segmentation::calculate_key_rect(cv::RotatedRect & rect_of_wheel_center, cv::RotatedRect & rect_of_wheel_cloud,
  607. Locate_information* p_locate_information)
  608. {
  609. if ( p_locate_information == NULL )
  610. {
  611. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  612. " calculate_key_rect input parameter POINTER_IS_NULL ");
  613. }
  614. //计算中心点
  615. p_locate_information->locate_x=rect_of_wheel_center.center.x;
  616. p_locate_information->locate_y=rect_of_wheel_center.center.y;
  617. //计算轮距, 矩形的长边为前后轮距, 短边为左右轮距
  618. p_locate_information->locate_wheel_base=std::max(rect_of_wheel_center.size.height,rect_of_wheel_center.size.width);
  619. p_locate_information->locate_wheel_width=std::min(rect_of_wheel_center.size.height,rect_of_wheel_center.size.width);
  620. //计算旋转角
  621. const double C_PI=3.14159265;
  622. cv::Point2f vec;
  623. cv::Point2f vertice[4];
  624. rect_of_wheel_cloud.points(vertice);
  625. float len1 = pow(vertice[0].x - vertice[1].x, 2.0) + pow(vertice[0].y - vertice[1].y, 2.0);
  626. float len2 = pow(vertice[1].x - vertice[2].x, 2.0) + pow(vertice[1].y - vertice[2].y, 2.0);
  627. if (len1 > len2) {
  628. vec.x = vertice[0].x - vertice[1].x;
  629. vec.y = vertice[0].y - vertice[1].y;
  630. }
  631. else
  632. {
  633. vec.x = vertice[1].x - vertice[2].x;
  634. vec.y = vertice[1].y - vertice[2].y;
  635. }
  636. p_locate_information->locate_angle = 180.0 / C_PI * acos(vec.x / sqrt(vec.x * vec.x + vec.y * vec.y));
  637. LOG(INFO)<<"3dcnn rotate rect center :"<<rect_of_wheel_center.center<<" size : "<<rect_of_wheel_center.size<<" angle:"<<p_locate_information->locate_angle;
  638. return SUCCESS;
  639. }