point_sift_segmentation.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392
  1. #include "point_sift_segmentation.h"
  2. #include <glog/logging.h>
  3. #include <fstream>
  4. void save_rgb_cloud_txt(std::string txt, pcl::PointCloud<pcl::PointXYZRGB>& pCloud)
  5. {
  6. std::ofstream os;
  7. os.open(txt, std::ios::out);
  8. for (int i = 0; i < pCloud.points.size(); i++)
  9. {
  10. pcl::PointXYZRGB point = pCloud.points[i];
  11. char buf[255];
  12. memset(buf, 0, 255);
  13. sprintf(buf, "%f %f %f %d %d %d\n", point.x, point.y, point.z, point.r, point.g, point.b);
  14. os.write(buf, strlen(buf));
  15. }
  16. os.close();
  17. }
  18. Point_sift_segmentation::Point_sift_segmentation(int point_size, int cls, float freq, pcl::PointXYZ minp, pcl::PointXYZ maxp)
  19. :PointSifter(point_size, cls)
  20. {
  21. m_point_num = point_size;
  22. m_cls_num = cls;
  23. m_freq = freq;
  24. m_minp = minp;
  25. m_maxp = maxp;
  26. }
  27. Error_manager Point_sift_segmentation::set_region(pcl::PointXYZ minp, pcl::PointXYZ maxp)
  28. {
  29. m_minp = minp;
  30. m_maxp = maxp;
  31. if(m_maxp.x<=m_minp.x || m_maxp.y<=m_minp.y)
  32. {
  33. return Error_manager(LOCATER_SIFT_INPUT_BOX_PARAMETER_FAILED,NORMAL,
  34. "Point sift set region invalid :m_maxp.x<=m_minp.x || m_maxp.y<=m_minp.y ");
  35. }
  36. return SUCCESS;
  37. }
  38. Point_sift_segmentation::~Point_sift_segmentation()
  39. {
  40. }
  41. Error_manager Point_sift_segmentation::init(std::string graph, std::string cpkt)
  42. {
  43. if (!Load(graph, cpkt))
  44. {
  45. std::string error_string="pointSIFT Init ERROR:";
  46. error_string+=LastError();
  47. return Error_manager(LOCATER_SIFT_INIT_FAILED,NORMAL,error_string);
  48. }
  49. //创建空数据,第一次初始化后空跑
  50. float* cloud_data = (float*)malloc(m_point_num * 3 * sizeof(float));
  51. float* output = (float*)malloc(m_point_num * m_cls_num * sizeof(float));
  52. if (false == Predict(cloud_data, output))
  53. {
  54. free(cloud_data);
  55. free(output);
  56. std::string error_string="pointSIFT int first predict ERROR:";
  57. error_string+=LastError();
  58. return Error_manager(LOCATER_SIFT_PREDICT_FAILED,NORMAL,error_string);
  59. }
  60. else
  61. {
  62. free(cloud_data);
  63. free(output);
  64. }
  65. return SUCCESS;
  66. }
  67. #include <algorithm>
  68. bool Point_sift_segmentation::Create_data(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, float* output)
  69. {
  70. if (cloud->size() == 0)
  71. return false;
  72. ////������άС����
  73. pcl::getMinMax3D(*cloud, m_minp, m_maxp);
  74. pcl::PointXYZ center;
  75. center.x = (m_minp.x + m_maxp.x) / 2.0;
  76. center.y = (m_minp.y + m_maxp.y) / 2.0;
  77. int l = int((m_maxp.x - m_minp.x) / m_freq) + 1;
  78. int w = int((m_maxp.y - m_minp.y) / m_freq) + 1;
  79. int h = int((m_maxp.z - m_minp.z) / m_freq) + 1;
  80. float* grid = (float*)malloc(l*w*h*sizeof(float));
  81. memset(grid, 0, l*w*h*sizeof(float));
  82. for (int i = 0; i < cloud->size(); ++i)
  83. {
  84. pcl::PointXYZ point = cloud->points[i];
  85. int idx = (point.x - m_minp.x) / m_freq;
  86. int idy = (point.y - m_minp.y) / m_freq;
  87. int idz = (point.z - m_minp.z) / m_freq;
  88. if (idx < 0 || idy < 0 || idz < 0)
  89. continue;
  90. *(grid + idx + idy*l + idz*l*w) = i+1;
  91. }
  92. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_grid(new pcl::PointCloud<pcl::PointXYZ>);
  93. for (int i = 0; i < l*w*h; ++i)
  94. {
  95. if (*(grid + i) > 0)
  96. {
  97. int id = *(grid + i);
  98. if (id <= cloud->size())
  99. {
  100. pcl::PointXYZ point = cloud->points[id-1];
  101. cloud_grid->push_back(point);
  102. }
  103. }
  104. }
  105. free(grid);
  106. ////ɸѡ�� m_point_num����
  107. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_select(new pcl::PointCloud<pcl::PointXYZ>);
  108. if (cloud_grid->size()>m_point_num)
  109. {
  110. //����˳�� ȡǰm_point_num ����
  111. std::random_shuffle(cloud_grid->points.begin(), cloud_grid->points.end()); //����˳��
  112. cloud_select->points.assign(cloud_grid->points.begin(), cloud_grid->points.begin() + m_point_num);
  113. }
  114. else if (cloud_grid->size() < m_point_num)
  115. {
  116. int add = m_point_num - cloud_grid->size();
  117. if (add > cloud_grid->size())
  118. return false;
  119. std::random_shuffle(cloud_grid->points.begin(), cloud_grid->points.end()); //����˳��
  120. cloud_select->points.assign(cloud_grid->points.begin(), cloud_grid->points.begin() + add);
  121. cloud_select->points.insert(cloud_select->points.begin(), cloud_grid->points.begin(), cloud_grid->points.end());
  122. }
  123. else
  124. {
  125. cloud_select->points.assign(cloud_grid->points.begin(), cloud_grid->points.end());
  126. }
  127. if (cloud_select->points.size() != m_point_num)
  128. {
  129. LOG(ERROR) << "\tpointSIFT input select cloud is not " << m_point_num;
  130. return false;
  131. }
  132. for (int i = 0; i < m_point_num; ++i)
  133. {
  134. pcl::PointXYZ point = cloud_select->points[i];
  135. *(output + i * 3) = (point.x-center.x) / 1000.0;
  136. *(output + i * 3+1) = (point.y-center.y) / 1000.0;
  137. *(output + i * 3+2) = point.z / 1000.0;
  138. }
  139. return true;
  140. }
  141. Error_manager Point_sift_segmentation::seg(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
  142. std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& cloud_seg, std::string save_dir)
  143. {
  144. if(cloud->size()==0)
  145. {
  146. return Error_manager(LOCATER_SIFT_INPUT_CLOUD_EMPTY,NORMAL,"PointSift input cloud empty ");
  147. }
  148. float* data = (float*)malloc(m_point_num * 3 * sizeof(float));
  149. float* output = (float*)malloc(m_point_num*m_cls_num*sizeof(float));
  150. memset(data, 0, m_point_num * 3 * sizeof(float));
  151. memset(output, 0, m_point_num*m_cls_num * sizeof(float));
  152. LOG(INFO) << "cloud size:" << cloud->size()<<" / "<<m_point_num;
  153. if (!Create_data(cloud, data))
  154. {
  155. free(data);
  156. free(output);
  157. return Error_manager(LOCATER_SIFT_CREATE_INPUT_DATA_FAILED,NORMAL,"pointSIFT Create input data ERROR");
  158. }
  159. if (!Predict(data, output))
  160. {
  161. free(data);
  162. free(output);
  163. return Error_manager(LOCATER_SIFT_PREDICT_FAILED,NORMAL,"pointSIFT predict ERROR");
  164. }
  165. ////������
  166. RecoveryCloud(output, data, cloud_seg);
  167. if (!FilterObs(cloud_seg,save_dir))
  168. {
  169. free(data);
  170. free(output);
  171. return Error_manager(LOCATER_SIFT_FILTE_OBS_FAILED,NORMAL,"FilterObs failed");
  172. }
  173. free(output);
  174. free(data);
  175. //确保有车辆点云及轮胎存在,车辆类别 2,轮胎类别0
  176. int segmentation_class_size=cloud_seg.size();
  177. if(segmentation_class_size<3)
  178. {
  179. return Error_manager(LOCATER_SIFT_PREDICT_NO_CAR_POINT,NORMAL,"PointSift detect no car point");
  180. }
  181. ///保存中间文件
  182. pcl::PointCloud<pcl::PointXYZRGB>::Ptr seg(new pcl::PointCloud<pcl::PointXYZRGB>);
  183. for (int i = 0; i < segmentation_class_size; ++i)
  184. {
  185. seg->operator +=(*cloud_seg[i]);
  186. }
  187. static int count = 0;
  188. count = (count + 1) % m_cls_num;
  189. char buf[64] = { 0 };
  190. sprintf(buf, "%s/SIFT_%d.txt", save_dir.c_str(), count);
  191. save_rgb_cloud_txt(buf, *seg);
  192. return SUCCESS;
  193. }
  194. bool Point_sift_segmentation::RecoveryCloud(float* output, float* cloud, std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& cloud_seg)
  195. {
  196. pcl::PointXYZ center;
  197. center.x = (m_minp.x + m_maxp.x) / 2.0;
  198. center.y = (m_minp.y + m_maxp.y) / 2.0;
  199. for (int k = 0; k < m_cls_num; ++k)
  200. {
  201. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_rgb(new pcl::PointCloud<pcl::PointXYZRGB>);
  202. cloud_seg.push_back(cloud_rgb);
  203. }
  204. for (int i = 0; i < m_point_num; ++i)
  205. {
  206. pcl::PointXYZ point;
  207. point.x = *(cloud + i * 3)*1000.+center.x;
  208. point.y = *(cloud + i * 3 + 1)*1000.+center.y;
  209. point.z = *(cloud + i * 3 + 2)*1000.;
  210. if (point.x > m_maxp.x || point.x<m_minp.x
  211. || point.y>m_maxp.y || point.y<m_minp.y
  212. || point.z>m_maxp.z || point.z < m_minp.z)
  213. {
  214. continue;
  215. }
  216. float* prob = output + i*m_cls_num;
  217. int cls = 0;
  218. float max = prob[0];
  219. for (int j = 1; j < m_cls_num; j++)
  220. {
  221. if (prob[j] > max)
  222. {
  223. max = prob[j];
  224. cls = j;
  225. }
  226. }
  227. int r = 255, g = 255, b = 255;
  228. if (cls == 1)
  229. {
  230. r = 0;
  231. b = 0;
  232. }
  233. if (cls == 2)
  234. {
  235. b = 0;
  236. g = 0;
  237. }
  238. if (cls < m_cls_num)
  239. {
  240. pcl::PointXYZRGB point_rgb;
  241. point_rgb.x = point.x;
  242. point_rgb.y = point.y;
  243. point_rgb.z = point.z;
  244. point_rgb.r = r;
  245. point_rgb.g = g;
  246. point_rgb.b = b;
  247. cloud_seg[cls]->push_back(point_rgb);
  248. }
  249. }
  250. return true;
  251. }
  252. bool Point_sift_segmentation::FilterObs(std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& cloud_seg,std::string save_dir)
  253. {
  254. /*if (cloud_seg.size() != m_cls_num)
  255. {
  256. LOG(ERROR) << "\t cloud_seg.size() != m_cls_num";
  257. return false;
  258. }*/
  259. const int obs_id = m_cls_num - 1;
  260. const int target_id = 1;
  261. pcl::PointCloud<pcl::PointXYZRGB>::Ptr obs_cloud = cloud_seg[obs_id];
  262. if(cloud_seg.size()>0) {
  263. std::string sift_in = save_dir + "/c0.txt";
  264. save_rgb_cloud_txt(sift_in, *cloud_seg[0]);
  265. }
  266. if(cloud_seg.size()>1) {
  267. std::string sift_in = save_dir + "/c1.txt";
  268. save_rgb_cloud_txt(sift_in, *cloud_seg[1]);
  269. }
  270. if(cloud_seg.size()>2) {
  271. std::string sift_in = save_dir + "/c2.txt";
  272. save_rgb_cloud_txt(sift_in, *cloud_seg[2]);
  273. }
  274. return true;
  275. /*if (obs_cloud->size() > 100)
  276. {
  277. ////ŷʽ����
  278. pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree_upground(new pcl::search::KdTree<pcl::PointXYZRGB>);
  279. tree_upground->setInputCloud(obs_cloud);
  280. std::vector<pcl::PointIndices> cluster_indices_upground;
  281. pcl::EuclideanClusterExtraction<pcl::PointXYZRGB> ec;
  282. ec.setClusterTolerance(100); // 10cm
  283. ec.setMinClusterSize(30);
  284. ec.setMaxClusterSize(10000);
  285. ec.setSearchMethod(tree_upground);
  286. ec.setInputCloud(obs_cloud);
  287. ec.extract(cluster_indices_upground);
  288. std::vector<pcl::PointCloud<pcl::PointXYZRGB>> clusters_obs;
  289. for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices_upground.begin(); it != cluster_indices_upground.end(); ++it)
  290. {
  291. pcl::PointCloud<pcl::PointXYZRGB> cloud_cluster;
  292. for (std::vector<int>::const_iterator pit = it->indices.begin(); pit != it->indices.end(); ++pit)
  293. cloud_cluster.push_back(obs_cloud->points[*pit]); //*
  294. cloud_cluster.width = cloud_cluster.size();
  295. cloud_cluster.height = 1;
  296. cloud_cluster.is_dense = true;
  297. clusters_obs.push_back(cloud_cluster);
  298. }
  299. ///// �� obs ���������
  300. std::vector<std::vector<cv::Point2f> > contours;
  301. for (int k = 0; k < clusters_obs.size(); ++k)
  302. {
  303. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_projected_XY(new pcl::PointCloud<pcl::PointXYZRGB>);
  304. pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients());
  305. coefficients->values.resize(4);
  306. coefficients->values[0] = 0.;
  307. coefficients->values[1] = 0.;
  308. coefficients->values[2] = 1.0;
  309. coefficients->values[3] = 0.;
  310. // Create the filtering object
  311. pcl::ProjectInliers<pcl::PointXYZRGB> proj;
  312. proj.setModelType(pcl::SACMODEL_PLANE);
  313. proj.setInputCloud(clusters_obs[k].makeShared());
  314. proj.setModelCoefficients(coefficients);
  315. proj.filter(*cloud_projected_XY);
  316. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_convexhull(new pcl::PointCloud<pcl::PointXYZRGB>);
  317. pcl::ConvexHull<pcl::PointXYZRGB> cconvexhull;
  318. cconvexhull.setInputCloud(cloud_projected_XY);
  319. cconvexhull.setDimension(2);
  320. cconvexhull.reconstruct(*cloud_convexhull);
  321. if (cloud_convexhull->size() > 3)
  322. {
  323. std::vector<cv::Point2f> contour;
  324. for (int j = 0; j < cloud_convexhull->size(); ++j)
  325. {
  326. pcl::PointXYZRGB point = cloud_convexhull->points[j];
  327. cv::Point2f pt(point.x, point.y);
  328. contour.push_back(pt);
  329. }
  330. contours.push_back(contour);
  331. }
  332. }
  333. //// ��Ŀ������
  334. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_target(new pcl::PointCloud<pcl::PointXYZRGB>);
  335. for (int i = 0; i < cloud_seg[target_id]->size(); ++i)
  336. {
  337. pcl::PointXYZRGB point = cloud_seg[target_id]->points[i];
  338. cv::Point2f pt(point.x, point.y);
  339. bool valid = true;
  340. for (int n = 0; n < contours.size(); ++n)
  341. {
  342. if (cv::pointPolygonTest(contours[n], pt, true)>-300.)
  343. {
  344. valid = false;
  345. break;
  346. }
  347. }
  348. if (valid)
  349. {
  350. cloud_target->push_back(point);
  351. }
  352. }
  353. cloud_seg[target_id] = cloud_target;
  354. char buf[255] = { 0 };
  355. static int count = 0;
  356. sprintf(buf, "%s/target_%d.txt", save_dir.c_str(), count++%m_cls_num);
  357. save_rgb_cloud_txt(buf, *cloud_target);
  358. }
  359. return true;*/
  360. }