cnn3d_segmentation.cpp 23 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721
  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. double IIU(std::vector<cv::Point>& poly1, std::vector<cv::Point>& poly2, float max_x, float max_y)
  32. {
  33. int width = int(max_x) + 100;
  34. int height = int(max_y) + 100;
  35. //��ͼ1
  36. cv::Mat src1 = cv::Mat::zeros(cv::Size(width, height), CV_8UC1);
  37. cv::Mat src2 = cv::Mat::zeros(cv::Size(width, height), CV_8UC1);
  38. std::vector<std::vector<cv::Point> > polys1;
  39. std::vector<std::vector<cv::Point> > polys2;
  40. polys1.push_back(poly1);
  41. polys2.push_back(poly2);
  42. cv::fillPoly(src1, polys1, cv::Scalar(1));
  43. cv::fillPoly(src2, polys2, cv::Scalar(1));
  44. cv::Mat I = src1&src2;
  45. //cv::Mat U = src1 | src2;
  46. cv::Scalar S_I = cv::sum(I);
  47. cv::Scalar S_U = cv::sum(src1);
  48. if (S_U[0] == 0) return 0;
  49. return double(S_I[0]) / double(S_U[0]);
  50. }
  51. float* Cnn3d_segmentation::generate_tensor(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, float min_x, float max_x,
  52. float min_y, float max_y, float min_z, float max_z)
  53. {
  54. int size = m_lenth*m_width*m_height;
  55. float* data = (float*)malloc(size*sizeof(float));
  56. memset(data, 0, size*sizeof(float));
  57. for (int i = 0; i < cloud->size(); ++i)
  58. {
  59. pcl::PointXYZ point = cloud->points[i];
  60. int new_x = (point.x - min_x) / (max_x - min_x)*m_lenth;
  61. int new_y = (point.y - min_y) / (max_y - min_y)*m_width;
  62. int new_z = (point.z - min_z) / (max_z - min_z)*m_height;
  63. if (new_x < 0 || new_x >= m_lenth || new_y < 0 || new_y >= m_width || new_z < 0 || new_z >= m_height)
  64. {
  65. continue;
  66. }
  67. *(data + new_x*(m_width*m_height) + new_y*m_height + new_z) = 1.0;
  68. }
  69. return data;
  70. }
  71. std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> Cnn3d_segmentation::decodeCloud(pcl::PointCloud<pcl::PointXYZ>& cloud,
  72. float* data, float min_x, float max_x, float min_y, float max_y, float min_z, float max_z)
  73. {
  74. std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr> clouds;
  75. for (int i = 0; i < m_nClass - 1; ++i)
  76. clouds.push_back(pcl::PointCloud<pcl::PointXYZRGB>::Ptr(new pcl::PointCloud<pcl::PointXYZRGB>));
  77. for (int i = 0; i < cloud.size(); ++i)
  78. {
  79. pcl::PointXYZ point = cloud.points[i];
  80. int new_x = (point.x - min_x) / (max_x - min_x)*m_lenth;
  81. int new_y = (point.y - min_y) / (max_y - min_y)*m_width;
  82. int new_z = (point.z - min_z) / (max_z - min_z)*m_height;
  83. if (new_x < 0 || new_x >= m_lenth || new_y < 0 || new_y >= m_width || new_z < 0 || new_z >= m_height)
  84. {
  85. continue;
  86. }
  87. int max_index = 0;
  88. float max_prob = *(data + new_x*(m_width*m_height*m_nClass) + new_y*m_height*m_nClass + new_z*m_nClass + 0);
  89. for (int j = 0; j < m_nClass; ++j)
  90. {
  91. if (*(data + new_x*(m_width*m_height*m_nClass) + new_y*m_height*m_nClass + new_z*m_nClass + j) > max_prob)
  92. {
  93. max_prob = *(data + new_x*(m_width*m_height*m_nClass) + new_y*m_height*m_nClass + new_z*m_nClass + j);
  94. max_index = j;
  95. }
  96. }
  97. pcl::PointXYZRGB point_color;
  98. point_color.x = point.x;
  99. point_color.y = point.y;
  100. point_color.z = point.z;
  101. point_color.r = 255;
  102. point_color.g = 255;
  103. point_color.b = 255;
  104. switch (max_index)
  105. {
  106. case 1:
  107. point_color.r = 0;
  108. point_color.g = 255;
  109. point_color.b = 0;
  110. clouds[0]->push_back(point_color);
  111. break;
  112. case 2:
  113. point_color.r = 255;
  114. point_color.g = 0;
  115. point_color.b = 0;
  116. clouds[1]->push_back(point_color);
  117. break;
  118. default:break;
  119. }
  120. }
  121. return clouds;
  122. }
  123. cv::RotatedRect minAreaRect_cloud(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud)
  124. {
  125. std::vector<cv::Point2f> points;
  126. for (int i = 0; i < cloud->size(); ++i)
  127. {
  128. pcl::PointXYZRGB point = cloud->points[i];
  129. points.push_back(cv::Point2f(point.x, point.y));
  130. }
  131. cv::RotatedRect rect= cv::minAreaRect(points);
  132. return rect;
  133. }
  134. cv::RotatedRect minAreaRect_cloud(std::vector<cv::Point2f> centers)
  135. {
  136. cv::RotatedRect rect = cv::minAreaRect(centers);
  137. return rect;
  138. }
  139. Error_manager Cnn3d_segmentation::set_parameter(int l, int w, int h,int freq,int classes)
  140. {
  141. m_lenth = l;
  142. m_width = w;
  143. m_height = h;
  144. m_freq = freq;
  145. m_nClass = classes;
  146. return SUCCESS;
  147. }
  148. Cnn3d_segmentation::Cnn3d_segmentation(int l, int w, int h,int freq,int classes)
  149. {
  150. m_lenth = l;
  151. m_width = w;
  152. m_height = h;
  153. m_freq = freq;
  154. m_nClass = classes;
  155. }
  156. Cnn3d_segmentation::~Cnn3d_segmentation()
  157. {
  158. //3dcnn 原校验功能保留,不加载网络
  159. //tf_wheel_3dcnn_close();
  160. }
  161. Error_manager Cnn3d_segmentation::init(std::string weights)
  162. {
  163. //3dcnn 原校验功能保留,不加载网络
  164. return SUCCESS;
  165. /*if (0 != tf_wheel_3dcnn_init(weights, m_lenth,m_width,m_height))
  166. {
  167. std::string error_description="tf_wheel_3Dcnn model load failed :";
  168. error_description+=weights;
  169. return Error_manager(LOCATER_3DCNN_INIT_FAILED,NORMAL,error_description);
  170. }
  171. //空跑一次
  172. float* data = (float*)malloc(m_lenth*m_width*m_height*sizeof(float));
  173. float* pout = (float*)malloc(m_lenth*m_width*m_height*m_nClass*sizeof(float));
  174. if (!tf_wheel_3dcnn_predict(data, pout))
  175. {
  176. free(data);
  177. free(pout);
  178. return Error_manager(LOCATER_3DCNN_PREDICT_FAILED,NORMAL,"first locate 3dcnn failed");
  179. }
  180. free(data);
  181. free(pout);
  182. return SUCCESS;*/
  183. }
  184. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> Cnn3d_segmentation::kmeans(
  185. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,std::string file_path)
  186. {
  187. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> kmens_out_clouds;
  188. for(int i=0;i<4;++i)
  189. {
  190. pcl::PointCloud<pcl::PointXYZ>::Ptr t_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  191. kmens_out_clouds.push_back(t_cloud);
  192. }
  193. //开始分割
  194. std::vector<cv::Point2f> cv_points;
  195. for (int i = 0; i < cloud->size(); ++i)
  196. {
  197. cv::Point2f point(cloud->points[i].x, cloud->points[i].y);
  198. cv_points.push_back(point);
  199. }
  200. cv::RotatedRect rect = cv::minAreaRect(cv_points);
  201. cv::Point2f corner[4];
  202. rect.points(corner);
  203. std::vector<cv::Point2f> clusters[4];
  204. double sumX[4] = { 0.0};
  205. double sumY[4] = { 0.0 };
  206. for (int i = 0; i < cloud->size(); ++i)
  207. {
  208. double min_distance = 9999999.9;
  209. int cluste_index = 0;
  210. cv::Point2f point(cloud->points[i].x, cloud->points[i].y);
  211. for (int j = 0; j < 4; ++j)
  212. {
  213. double dis=distance(point, corner[j]);
  214. if (dis < min_distance)
  215. {
  216. min_distance = dis;
  217. cluste_index = j;
  218. }
  219. }
  220. clusters[cluste_index].push_back(point);
  221. sumX[cluste_index] += point.x;
  222. sumY[cluste_index] += point.y;
  223. pcl::PointXYZ t_point3d;
  224. t_point3d.x=cloud->points[i].x;
  225. t_point3d.y=cloud->points[i].y;
  226. t_point3d.z=cloud->points[i].z;
  227. if(cluste_index>=0&&cluste_index<4)
  228. {
  229. kmens_out_clouds[cluste_index]->push_back(t_point3d);
  230. }
  231. if (cluste_index == 0)
  232. {
  233. cloud->points[i].r = 255;
  234. cloud->points[i].g = 0;
  235. cloud->points[i].b = 0;
  236. }
  237. else if (cluste_index == 1)
  238. {
  239. cloud->points[i].r = 0;
  240. cloud->points[i].g = 255;
  241. cloud->points[i].b = 0;
  242. }
  243. else if (cluste_index == 2)
  244. {
  245. cloud->points[i].r = 0;
  246. cloud->points[i].g = 0;
  247. cloud->points[i].b = 255;
  248. }
  249. else
  250. {
  251. cloud->points[i].r = 255;
  252. cloud->points[i].g = 255;
  253. cloud->points[i].b = 255;
  254. }
  255. }
  256. std::vector<cv::Point2f> rets;
  257. for (int i = 0; i < 4; ++i)
  258. {
  259. if (clusters[i].size() == 0)
  260. {
  261. continue;
  262. }
  263. float avg_x = sumX[i] / float(clusters[i].size());
  264. float avg_y = sumY[i] / float(clusters[i].size());
  265. rets.push_back(cv::Point2f(avg_x, avg_y));
  266. }
  267. std::string save_file=file_path+"/cnn3d.txt";
  268. save_rgb_cloud_txt(save_file, cloud);
  269. return kmens_out_clouds;
  270. /*int clusterCount = 4;
  271. int sampleCount = cloud->size();
  272. cv::Mat points(sampleCount, 1, CV_32FC2), labels; //��������������ʵ����Ϊ2ͨ������������Ԫ������ΪPoint2f
  273. for (int i = 0; i < sampleCount; ++i)
  274. {
  275. points.at<cv::Point2f>(i) = cv::Point2f(cloud->points[i].x, cloud->points[i].y);
  276. }
  277. clusterCount = MIN(clusterCount, sampleCount);
  278. cv::Mat centers(clusterCount, 1, points.type()); //�����洢���������ĵ�
  279. cv::RNG rng(12345); //�����������
  280. cv::kmeans(points, clusterCount, labels,
  281. cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 500, 15.0),
  282. 5, cv::KMEANS_PP_CENTERS, centers);
  283. for (int i = 0; i < sampleCount; i++)
  284. {
  285. int clusterIdx = labels.at<int>(i);
  286. pcl::PointXYZ point;
  287. point.x=cloud->points[i].x;
  288. point.y=cloud->points[i].y;
  289. point.z=cloud->points[i].z;
  290. if(clusterIdx>=0&&clusterIdx<4)
  291. {
  292. kmens_out_clouds[clusterIdx]->push_back(point);
  293. }
  294. if (clusterIdx == 0)
  295. {
  296. cloud->points[i].r = 255;
  297. cloud->points[i].g = 0;
  298. cloud->points[i].b = 0;
  299. }
  300. else if (clusterIdx == 1)
  301. {
  302. cloud->points[i].r = 0;
  303. cloud->points[i].g = 255;
  304. cloud->points[i].b = 0;
  305. }
  306. else if (clusterIdx == 2)
  307. {
  308. cloud->points[i].r = 0;
  309. cloud->points[i].g = 0;
  310. cloud->points[i].b = 255;
  311. }
  312. else
  313. {
  314. cloud->points[i].r = 255;
  315. cloud->points[i].g = 255;
  316. cloud->points[i].b = 255;
  317. }
  318. }
  319. std::string save_file=file_path+"/cnn3d.txt";
  320. save_rgb_cloud_txt(save_file, cloud);*/
  321. return kmens_out_clouds;
  322. }
  323. Error_manager Cnn3d_segmentation::isRect(std::vector<cv::Point2f>& points)
  324. {
  325. if (points.size() == 4)
  326. {
  327. double L[3] = {0.0};
  328. L[0] = distance(points[0], points[1]);
  329. L[1] = distance(points[1], points[2]);
  330. L[2] = distance(points[0], points[2]);
  331. double max_l = L[0];
  332. double l1 = L[1];
  333. double l2 = L[2];
  334. int max_index = 0;
  335. cv::Point2f ps = points[0], pt = points[1];
  336. cv::Point2f pc = points[2];
  337. for (int i = 1; i < 3; ++i) {
  338. if (L[i] > max_l) {
  339. max_index = i;
  340. max_l = L[i];
  341. l1 = L[abs(i + 1) % 3];
  342. l2 = L[abs(i + 2) % 3];
  343. ps = points[i % 3];
  344. pt = points[(i + 1) % 3];
  345. pc = points[(i + 2) % 3];
  346. }
  347. }
  348. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  349. if (fabs(cosa) >= 0.13) {
  350. char description[255]={0};
  351. sprintf(description,"angle cos value(%.2f) >0.13 ",cosa);
  352. return Error_manager(LOCATER_3DCNN_VERIFY_RECT_FAILED_4,NORMAL,description);
  353. }
  354. float width=std::min(l1,l2);
  355. float length=std::max(l1,l2);
  356. if(width<1400 || width >2000 || length >3300 ||length < 2200)
  357. {
  358. char description[255]={0};
  359. sprintf(description,"width<1400 || width >2100 || wheel_base >3300 ||wheel_base < 2100 l:%.1f,w:%.1f",length,width);
  360. return Error_manager(LOCATER_3DCNN_VERIFY_RECT_FAILED_4,NORMAL,description);
  361. }
  362. double d = distance(pc, points[3]);
  363. cv::Point2f center1 = (ps + pt) * 0.5;
  364. cv::Point2f center2 = (pc + points[3]) * 0.5;
  365. if (fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 150) {
  366. LOG(INFO) << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2;
  367. char description[255]={0};
  368. sprintf(description,"Verify failed-4 fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 150 ");
  369. return Error_manager(LOCATER_3DCNN_VERIFY_RECT_FAILED_4,NORMAL,description);
  370. }
  371. LOG(INFO) << " rectangle verify OK cos angle=" << cosa << " length off=" << fabs(d - max_l)
  372. << " center distance=" << distance(center1, center2);
  373. return SUCCESS;
  374. }
  375. else if(points.size()==3)
  376. {
  377. double L[3] = {0.0};
  378. L[0] = distance(points[0], points[1]);
  379. L[1] = distance(points[1], points[2]);
  380. L[2] = distance(points[0], points[2]);
  381. double max_l = L[0];
  382. double l1 = L[1];
  383. double l2 = L[2];
  384. int max_index = 0;
  385. cv::Point2f ps = points[0], pt = points[1];
  386. cv::Point2f pc = points[2];
  387. for (int i = 1; i < 3; ++i) {
  388. if (L[i] > max_l) {
  389. max_index = i;
  390. max_l = L[i];
  391. l1 = L[abs(i + 1) % 3];
  392. l2 = L[abs(i + 2) % 3];
  393. ps = points[i % 3];
  394. pt = points[(i + 1) % 3];
  395. pc = points[(i + 2) % 3];
  396. }
  397. }
  398. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  399. if (fabs(cosa) >= 0.12) {
  400. char description[255]={0};
  401. sprintf(description,"3 wheels angle cos value(%.2f) >0.12 ",cosa);
  402. return Error_manager(LOCATER_3DCNN_VERIFY_RECT_FAILED_3,NORMAL,description);
  403. }
  404. double l=std::max(l1,l2);
  405. double w=std::min(l1,l2);
  406. if(l>2100 && l<3300 && w>1400 && w<2100)
  407. {
  408. //生成第四个点
  409. cv::Point2f vec1=ps-pc;
  410. cv::Point2f vec2=pt-pc;
  411. cv::Point2f point4=(vec1+vec2)+pc;
  412. points.push_back(point4);
  413. LOG(INFO) << "3 wheels rectangle verify OK cos angle=" << cosa << " L=" << l
  414. << " w=" << w;
  415. return SUCCESS;
  416. }
  417. else
  418. {
  419. char description[255]={0};
  420. sprintf(description,"3 wheels rectangle verify Failed cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  421. return Error_manager(LOCATER_3DCNN_VERIFY_RECT_FAILED_3,NORMAL,description);
  422. }
  423. }
  424. }
  425. void save_cloudT(std::string txt, pcl::PointCloud<pcl::PointXYZ>& pCloud)
  426. {
  427. std::ofstream os;
  428. os.open(txt, std::ios::out);
  429. for (int i = 0; i < pCloud.points.size(); i++)
  430. {
  431. pcl::PointXYZ point = pCloud.points[i];
  432. char buf[255];
  433. memset(buf, 0, 255);
  434. sprintf(buf, "%f %f %f\n", point.x, point.y, point.z);
  435. os.write(buf, strlen(buf));
  436. }
  437. os.close();
  438. }
  439. Error_manager Cnn3d_segmentation::predict(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
  440. float& center_x,float& center_y,float& wheel_base,
  441. float& width,float& angle,std::string cluster_file_path)
  442. {
  443. if(cloud.get()==NULL)
  444. {
  445. return Error_manager(LOCATER_3DCNN_INPUT_CLOUD_EMPTY,NORMAL,"3dcnn predict input cloud uninit");
  446. }
  447. if(cloud->size()==0)
  448. {
  449. return Error_manager(LOCATER_3DCNN_INPUT_CLOUD_EMPTY,NORMAL,"3dcnn predict input cloud empty");
  450. }
  451. clock_t clock1 = clock();
  452. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloudout(new pcl::PointCloud<pcl::PointXYZRGB>);
  453. pcl::copyPointCloud(*cloud,*cloudout);
  454. pcl::PointCloud<pcl::PointXYZRGB>::Ptr last_cloud(new pcl::PointCloud<pcl::PointXYZRGB>);
  455. if (cloudout->size() == 0)
  456. {
  457. return Error_manager(LOCATER_3DCNN_PREDICT_FAILED,NORMAL,"tf pred class[wheel].points size ==0");
  458. }
  459. //离群点过滤
  460. pcl::StatisticalOutlierRemoval<pcl::PointXYZRGB> sorfilter(true); // Initializing with true will allow us to extract the removed indices
  461. sorfilter.setInputCloud(cloudout);
  462. sorfilter.setMeanK(20);
  463. sorfilter.setStddevMulThresh(2.0);
  464. sorfilter.filter(*cloudout);
  465. if (cloudout->size() < 4 )
  466. {
  467. return Error_manager(LOCATER_3DCNN_PREDICT_FAILED,NORMAL,"tf pred wheel points size <4");
  468. }
  469. //kmeans
  470. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> kmeans_out_clouds = kmeans(cloudout, cluster_file_path);
  471. //对kmeans结果点云作pca filter
  472. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> pca_filter_clouds;
  473. for(int i=0;i<4;++i)
  474. {
  475. pcl::PointCloud<pcl::PointXYZ>::Ptr t_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  476. pca_filter_clouds.push_back(t_cloud);
  477. }
  478. for(int i=0;i<kmeans_out_clouds.size();++i)
  479. {
  480. pca_minist_axis_filter(kmeans_out_clouds[i],pca_filter_clouds[i]);
  481. char buf[255]={0};
  482. sprintf(buf,"%s/pca_wheel_%d.txt",cluster_file_path.c_str(),i);
  483. save_cloudT(buf,*pca_filter_clouds[i]);
  484. }
  485. //计算pca filter点云中心
  486. std::vector<cv::Point2f> centers;
  487. for(int i=0;i<pca_filter_clouds.size();++i)
  488. {
  489. if(pca_filter_clouds[i]->size()!=0) {
  490. Eigen::Vector4f centroid;
  491. pcl::compute3DCentroid(*pca_filter_clouds[i], centroid);
  492. centers.push_back(cv::Point2f(centroid[0],centroid[1]));
  493. }
  494. }
  495. //将pca过滤后的轮胎点转换成opencv点,用于计算角度与宽
  496. std::vector<cv::Point2f> wheel_points;
  497. for(int i=0;i<pca_filter_clouds.size();++i)
  498. {
  499. for(int j=0;j<pca_filter_clouds[i]->size();++j)
  500. wheel_points.push_back(cv::Point2f(pca_filter_clouds[i]->points[j].x,
  501. pca_filter_clouds[i]->points[j].y));
  502. }
  503. if (centers.size() != 4 && centers.size()!=3)
  504. {
  505. return Error_manager(LOCATER_3DCNN_KMEANS_FAILED,NORMAL,"3dcnn cluster center size != 4 & 3");
  506. }
  507. //取四轮中心计算轴长
  508. Error_manager code=isRect(centers);
  509. if(code!=SUCCESS)
  510. {
  511. return code;
  512. }
  513. if(centers.size()==3)
  514. {
  515. wheel_points.push_back(centers[centers.size()-1]);
  516. }
  517. cv::RotatedRect rect_center = minAreaRect_cloud(centers);
  518. cv::RotatedRect rect_wheels=minAreaRect_cloud(wheel_points);
  519. bool IOU = check_box(rect_center, cloud);
  520. if(IOU==false){
  521. return Error_manager(LOCATER_3DCNN_IIU_FAILED,NORMAL,"IIU check box failed");
  522. }
  523. //开始赋值
  524. center_x=rect_center.center.x;
  525. center_y=rect_center.center.y;
  526. wheel_base=std::max(rect_center.size.height,rect_center.size.width);
  527. width=std::min(rect_center.size.height,rect_center.size.width);
  528. //根据 rect_wheel 计算角度
  529. const double C_PI=3.14159265;
  530. cv::Point2f vec;
  531. cv::Point2f vertice[4];
  532. rect_wheels.points(vertice);
  533. float len1 = pow(vertice[0].x - vertice[1].x, 2.0) + pow(vertice[0].y - vertice[1].y, 2.0);
  534. float len2 = pow(vertice[1].x - vertice[2].x, 2.0) + pow(vertice[1].y - vertice[2].y, 2.0);
  535. if (len1 > len2) {
  536. vec.x = vertice[0].x - vertice[1].x;
  537. vec.y = vertice[0].y - vertice[1].y;
  538. }
  539. else {
  540. vec.x = vertice[1].x - vertice[2].x;
  541. vec.y = vertice[1].y - vertice[2].y;
  542. }
  543. angle = 180.0 / C_PI * acos(vec.x / sqrt(vec.x * vec.x + vec.y * vec.y));
  544. LOG(INFO)<<"3dcnn rotate rect center :"<<rect_center.center<<" size : "<<rect_center.size<<" angle:"<<angle;
  545. return SUCCESS;
  546. }
  547. Error_manager Cnn3d_segmentation::pca_minist_axis_filter(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in,
  548. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_out)
  549. {
  550. if(cloud_in.get()==NULL)
  551. {
  552. return Error_manager(PARAMETER_ERROR,NORMAL,"pca_minist_axis_filter input cloud uninit");
  553. }
  554. if(cloud_in->size()==0)
  555. {
  556. return Error_manager(PARAMETER_ERROR,NORMAL,"pca_minist_axis_filter input cloud empty");
  557. }
  558. //pca寻找主轴
  559. pcl::MomentOfInertiaEstimation <pcl::PointXYZ> feature_extractor;
  560. feature_extractor.setInputCloud (cloud_in);
  561. feature_extractor.compute ();
  562. std::vector <float> moment_of_inertia;
  563. std::vector <float> eccentricity;
  564. pcl::PointXYZ min_point_AABB;
  565. pcl::PointXYZ max_point_AABB;
  566. pcl::PointXYZ min_point_OBB;
  567. pcl::PointXYZ max_point_OBB;
  568. pcl::PointXYZ position_OBB;
  569. Eigen::Matrix3f rotational_matrix_OBB;
  570. float major_value, middle_value, minor_value;
  571. Eigen::Vector3f major_vector, middle_vector, minor_vector;
  572. Eigen::Vector3f mass_center;
  573. feature_extractor.getMomentOfInertia (moment_of_inertia);
  574. feature_extractor.getEccentricity (eccentricity);
  575. feature_extractor.getAABB (min_point_AABB, max_point_AABB);
  576. feature_extractor.getOBB (min_point_OBB, max_point_OBB, position_OBB, rotational_matrix_OBB);
  577. feature_extractor.getEigenValues (major_value, middle_value, minor_value);
  578. feature_extractor.getEigenVectors (major_vector, middle_vector, minor_vector);
  579. feature_extractor.getMassCenter (mass_center);
  580. //根据minor_vector 最小主轴方向,以及中心点, 计算轴所在三维平面
  581. float x=mass_center[0];
  582. float y=mass_center[1];
  583. float z=mass_center[2];
  584. float a=minor_vector[0];
  585. float b=minor_vector[1];
  586. float c=minor_vector[2];
  587. float d=-(a*x+b*y+c*z);
  588. //计算各点距离平面的距离,距离操过轮胎的一半厚,舍弃(100mm)
  589. float S=sqrt(a*a+b*b+c*c);
  590. for(int i=0;i<cloud_in->size();++i)
  591. {
  592. pcl::PointXYZ point=cloud_in->points[i];
  593. if(fabs(point.x*a+point.y*b+point.z*c+d)/S <40 )
  594. {
  595. cloud_out->push_back(point);
  596. }
  597. }
  598. /*if(cloud_out->size()==0)
  599. {
  600. return Error_manager(LOCATER_3DCNN_PCA_OUT_CLOUD_EMPTY,NORMAL,"wheel pca filter out cloud empty");
  601. }*/
  602. return SUCCESS;
  603. }
  604. bool Cnn3d_segmentation::check_box(cv::RotatedRect& box, pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
  605. {
  606. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_projected_XY(new pcl::PointCloud<pcl::PointXYZ>);
  607. pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients());
  608. coefficients->values.resize(4);
  609. coefficients->values[0] = 0.;
  610. coefficients->values[1] = 0.;
  611. coefficients->values[2] = 1.0;
  612. coefficients->values[3] = 0.;
  613. // Create the filtering object
  614. pcl::ProjectInliers<pcl::PointXYZ> proj;
  615. proj.setModelType(pcl::SACMODEL_PLANE);
  616. proj.setInputCloud(cloud);
  617. proj.setModelCoefficients(coefficients);
  618. proj.filter(*cloud_projected_XY);
  619. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_convexhull(new pcl::PointCloud<pcl::PointXYZ>);
  620. pcl::ConvexHull<pcl::PointXYZ> cconvexhull;
  621. cconvexhull.setInputCloud(cloud_projected_XY);
  622. cconvexhull.setDimension(2);
  623. cconvexhull.reconstruct(*cloud_convexhull);
  624. //����IOU
  625. pcl::PointXYZ minPt, maxPt;
  626. pcl::getMinMax3D(*cloud_convexhull, minPt, maxPt);
  627. cv::Point2f vertice[4];
  628. box.points(vertice);
  629. std::vector<cv::Point> poly;
  630. poly.push_back(vertice[0]);
  631. poly.push_back(vertice[1]);
  632. poly.push_back(vertice[2]);
  633. poly.push_back(vertice[3]);
  634. std::vector<cv::Point> poly1;
  635. for (int i = 0; i < cloud_convexhull->points.size(); ++i)
  636. {
  637. pcl::PointXYZ pt = cloud_convexhull->points[i];
  638. cv::Point2f point(pt.x, pt.y);
  639. poly1.push_back(point);
  640. }
  641. //double area_percent = IIU(poly, poly1, maxPt.x, maxPt.y);
  642. if (/*area_percent < 0.95 ||*/ std::min(box.size.width, box.size.height)>2000.0 || std::min(box.size.width, box.size.height)<1200.0)
  643. {
  644. return false;
  645. }
  646. if (std::max(box.size.width, box.size.height) < 1900 || std::max(box.size.width, box.size.height) > 3600)
  647. {
  648. LOG(ERROR) << "\tlen not in 1900-3400";
  649. return false;
  650. }
  651. return true;
  652. }