point_sift_segmentation.cpp 25 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790
  1. #include "point_sift_segmentation.h"
  2. #include <glog/logging.h>
  3. #include <fstream>
  4. #include <algorithm>
  5. #include <pcl/filters//voxel_grid.h>
  6. #include <pcl/filters/passthrough.h>
  7. #include <time.h>
  8. #include <sys/time.h>
  9. #include <chrono>
  10. #include <thread>
  11. void save_rgb_cloud_txt(std::string txt, pcl::PointCloud<pcl::PointXYZRGB>& cloud)
  12. {
  13. std::ofstream os;
  14. os.open(txt, std::ios::out);
  15. for (int i = 0; i < cloud.points.size(); i++)
  16. {
  17. pcl::PointXYZRGB point = cloud.points[i];
  18. char buf[255];
  19. memset(buf, 0, 255);
  20. sprintf(buf, "%f %f %f %d %d %d\n", point.x, point.y, point.z, point.r, point.g, point.b);
  21. os.write(buf, strlen(buf));
  22. }
  23. os.close();
  24. }
  25. void save_rgb_cloud_txt(std::string txt, pcl::PointCloud<pcl::PointXYZ>& cloud)
  26. {
  27. std::ofstream os;
  28. os.open(txt, std::ios::out);
  29. for (int i = 0; i < cloud.points.size(); i++)
  30. {
  31. pcl::PointXYZ point = cloud.points[i];
  32. char buf[255];
  33. memset(buf, 0, 255);
  34. sprintf(buf, "%f %f %f \n", point.x, point.y, point.z);
  35. os.write(buf, strlen(buf));
  36. }
  37. os.close();
  38. }
  39. void save_rgb_cloud_txt(std::string txt, std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& cloud_vector)
  40. {
  41. std::ofstream os;
  42. os.open(txt, std::ios::out);
  43. for (int j = 0; j < cloud_vector.size(); ++j)
  44. {
  45. for (int i = 0; i < cloud_vector[j]->points.size(); i++)
  46. {
  47. pcl::PointXYZRGB point = cloud_vector[j]->points[i];
  48. char buf[255];
  49. memset(buf, 0, 255);
  50. sprintf(buf, "%f %f %f %d %d %d\n", point.x, point.y, point.z, point.r, point.g, point.b);
  51. os.write(buf, strlen(buf));
  52. }
  53. }
  54. os.close();
  55. }
  56. Point_sift_segmentation::Point_sift_segmentation(int point_size, int cls, float freq, pcl::PointXYZ minp, pcl::PointXYZ maxp)
  57. :PointSifter(point_size, cls)
  58. {
  59. m_point_num = point_size;
  60. m_cls_num = cls;
  61. m_freq = freq;
  62. m_minp = minp;
  63. m_maxp = maxp;
  64. }
  65. Point_sift_segmentation::Point_sift_segmentation(int point_size,int cls,float freq, Cloud_box cloud_box)
  66. :PointSifter(point_size, cls)
  67. {
  68. m_point_num = point_size;
  69. m_cls_num = cls;
  70. m_freq = freq;
  71. m_cloud_box_limit = cloud_box;
  72. }
  73. Point_sift_segmentation::~Point_sift_segmentation()
  74. {
  75. }
  76. Error_manager Point_sift_segmentation::init(std::string graph, std::string cpkt)
  77. {
  78. if (!Load(graph, cpkt))
  79. {
  80. std::string error_string="pointSIFT Init ERROR:";
  81. error_string+=LastError();
  82. return Error_manager(LOCATER_SIFT_INIT_FAILED,MINOR_ERROR,error_string);
  83. }
  84. //创建空数据,第一次初始化后空跑
  85. float* cloud_data = (float*)malloc(m_point_num * 3 * sizeof(float));
  86. float* output = (float*)malloc(m_point_num * m_cls_num * sizeof(float));
  87. auto start = std::chrono::system_clock::now();
  88. if (false == Predict(cloud_data, output))
  89. {
  90. free(cloud_data);
  91. free(output);
  92. std::string error_string="pointSIFT int first predict ERROR:";
  93. error_string+=LastError();
  94. return Error_manager(LOCATER_SIFT_PREDICT_FAILED,MINOR_ERROR,error_string);
  95. }
  96. else
  97. {
  98. free(cloud_data);
  99. free(output);
  100. }
  101. auto end = std::chrono::system_clock::now();
  102. auto duration = std::chrono::duration_cast<std::chrono::microseconds>(end - start);
  103. std::cout << "花费了"
  104. << double(duration.count()) * std::chrono::microseconds::period::num / std::chrono::microseconds::period::den << "秒" << std::endl;
  105. return SUCCESS;
  106. }
  107. //分割函数,输入点云,输出各类的点云,并保存中间文件方便查看识别结果.
  108. //cloud:输入点云
  109. //clouds:输出分类好的多个点云(附带颜色,红色为杂物,绿色为车,白色为地面)(此时里面没有内存)
  110. Error_manager Point_sift_segmentation::segmentation(int lidar_id, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud_in,
  111. std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& cloud_vector,
  112. bool save_flag, std::string save_dir)
  113. {
  114. if(p_cloud_in.get()==NULL)
  115. {
  116. return Error_manager(LOCATER_SIFT_INPUT_CLOUD_UNINIT,MINOR_ERROR,"sift input cloud uninit");
  117. }
  118. if(p_cloud_in->size()<=0)
  119. {
  120. return Error_manager(LOCATER_SIFT_INPUT_CLOUD_EMPTY,MINOR_ERROR,"locate_sift input cloud empty");
  121. }
  122. Error_manager t_error;
  123. std::cout << "p_cloud_in = "<<p_cloud_in->size() << std::endl;
  124. //第一步
  125. // 使用体素网格, 抽稀点云, //将点云空间分为小方格,每个小方格只保留一个点.
  126. t_error = filter_cloud_with_voxel_grid(p_cloud_in);
  127. if ( t_error != Error_code::SUCCESS )
  128. {
  129. return t_error;
  130. }
  131. std::cout << "p_cloud_in = "<<p_cloud_in->size() << std::endl;
  132. //第二步
  133. // 使用box限定点云范围,只保留box范围内部的点, 剔除外部的点云
  134. t_error = filter_cloud_with_box(p_cloud_in);
  135. if ( t_error != Error_code::SUCCESS )
  136. {
  137. return t_error;
  138. }
  139. std::cout << "p_cloud_in = "<<p_cloud_in->size() << std::endl;
  140. //第三步 /
  141. // /通过输入点云,更新区域范围, 范围不一定是box的边界,可能比box要小.
  142. t_error = update_region(p_cloud_in);
  143. if ( t_error != Error_code::SUCCESS )
  144. {
  145. return t_error;
  146. }
  147. std::cout << "p_cloud_in = "<<p_cloud_in->size() << std::endl;
  148. //第四步
  149. // 抽稀点云, //自己写的算法, 重新生成新的点云.
  150. t_error = filter_cloud_with_my_grid(p_cloud_in);
  151. if ( t_error != Error_code::SUCCESS )
  152. {
  153. return t_error;
  154. }
  155. std::cout << "p_cloud_in = "<<p_cloud_in->size() << std::endl;
  156. //第五步
  157. pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud_select(new pcl::PointCloud<pcl::PointXYZ>);
  158. //从点云中选出固定数量的随机点, 默认8192个点
  159. t_error = filter_cloud_with_select(p_cloud_in, p_cloud_select);
  160. if ( t_error != Error_code::SUCCESS )
  161. {
  162. return t_error;
  163. }
  164. std::cout << "p_cloud_select = "<<p_cloud_select->size() << std::endl;
  165. /*
  166. //第六步
  167. //把pcl点云转化为float, 因为TensorFlow算法只能识别float
  168. //提前分配内存, 后续记得回收....
  169. float* p_data_point = (float*)malloc(m_point_num * 3 * sizeof(float)); //8192*3 float, 8192个三维点
  170. float* p_data_type = (float*)malloc(m_point_num*m_cls_num*sizeof(float)); //8192*2 float, 8192个类别百分比(车轮和车身2类)
  171. memset(p_data_point, 0, m_point_num * 3 * sizeof(float));
  172. memset(p_data_type, 0, m_point_num*m_cls_num * sizeof(float));
  173. //将点云数据转换到float*
  174. t_error = translate_cloud_to_float(p_cloud_select, p_data_point);
  175. if ( t_error != Error_code::SUCCESS )
  176. {
  177. free(p_data_point);
  178. free(p_data_type);
  179. return t_error;
  180. }
  181. //第七步
  182. //tensonflow预测点云, 计算出每个三维点的类别百分比,
  183. auto start = system_clock::now();
  184. if (!Predict(p_data_point, p_data_type))
  185. {
  186. free(p_data_point);
  187. free(p_data_type);
  188. return Error_manager(LOCATER_SIFT_PREDICT_FAILED,MINOR_ERROR,"pointSIFT predict ERROR");
  189. }
  190. auto end = system_clock::now();
  191. auto duration = duration_cast<microseconds>(end - start);
  192. cout << "花费了"
  193. << double(duration.count()) * microseconds::period::num / microseconds::period::den << "秒" << endl;
  194. cout << double(duration.count()) << " "
  195. << microseconds::period::num << " " << microseconds::period::den << "秒" << endl;
  196. */
  197. std::string sift_in = save_dir + "/SIFT_cls_8192.txt";
  198. save_rgb_cloud_txt(sift_in, *p_cloud_select);
  199. //重写6和7步, 将TensorFlow算法放在服务器上, 使用socket通信去发送点云并获取结果
  200. //第六步
  201. //把pcl点云转化为float, 因为TensorFlow算法只能识别float
  202. //提前分配内存, 后续记得回收....
  203. float* p_data_point = (float*)malloc(m_point_num * 3 * sizeof(float)); //8192*3 float, 8192个三维点
  204. int* p_data_type = (int*)malloc(m_point_num*sizeof(int)); //8192*2 float, 8192个类别百分比(车轮和车身2类)
  205. memset(p_data_point, 0, m_point_num * 3 * sizeof(float));
  206. memset(p_data_type, 0, m_point_num * sizeof(int));
  207. //将点云数据转换到float*
  208. t_error = translate_cloud_to_float(p_cloud_select, p_data_point);
  209. if ( t_error != Error_code::SUCCESS )
  210. {
  211. free(p_data_point);
  212. free(p_data_type);
  213. return t_error;
  214. }
  215. //第七步
  216. //tensonflow预测点云, 计算出每个三维点的类别百分比,
  217. auto start = std::chrono::system_clock::now();
  218. //预测, 发送socket通信, 在服务器上进行点云算法
  219. t_error = m_predict_with_network.predict_for_send(lidar_id, p_data_point);
  220. if ( t_error != Error_code::SUCCESS )
  221. {
  222. free(p_data_point);
  223. free(p_data_type);
  224. return t_error;
  225. }
  226. //循环接受, 超时等待5000ms, (后续可以在这里加上强制取消)
  227. while (std::chrono::system_clock::now() - start < std::chrono::milliseconds(5000))
  228. {
  229. t_error = m_predict_with_network.predict_for_receive(lidar_id, p_data_type);
  230. if ( t_error == Error_code::SUCCESS )
  231. {
  232. //算法成功, 直接退出循环即可
  233. break;
  234. }
  235. else if ( t_error == Error_code::NODATA )
  236. {
  237. //继续循环, 延迟1us
  238. std::this_thread::yield();
  239. std::this_thread::sleep_for(std::chrono::microseconds(1));
  240. continue;
  241. }
  242. else
  243. {
  244. free(p_data_point);
  245. free(p_data_type);
  246. return t_error;
  247. }
  248. }
  249. if ( std::chrono::system_clock::now() - start >= std::chrono::milliseconds(5000) )
  250. {
  251. free(p_data_point);
  252. free(p_data_type);
  253. return Error_manager(Error_code::LOCATER_SIFT_PREDICT_TIMEOUT, Error_level::MINOR_ERROR,
  254. " m_predict_with_network.predict_for_receive error ");
  255. }
  256. auto end = std::chrono::system_clock::now();
  257. auto duration = std::chrono::duration_cast<std::chrono::microseconds>(end - start);
  258. std::cout << "花费了"
  259. << double(duration.count()) * std::chrono::microseconds::period::num / std::chrono::microseconds::period::den << "秒" << std::endl;
  260. std::cout << double(duration.count()) << " "
  261. << std::chrono::microseconds::period::num << " " << std::chrono::microseconds::period::den << "秒" << std::endl;
  262. //第八步
  263. //恢复点云,并填充到cloud_vector
  264. t_error = recovery_float_to_cloud(p_data_type, p_data_point, cloud_vector);
  265. if ( t_error != Error_code::SUCCESS )
  266. {
  267. free(p_data_point);
  268. free(p_data_type);
  269. return t_error;
  270. }
  271. //第九步
  272. //保存点云数据
  273. if ( save_flag )
  274. {
  275. t_error = save_cloud(cloud_vector,save_dir);
  276. if ( t_error != Error_code::SUCCESS )
  277. {
  278. free(p_data_point);
  279. free(p_data_type);
  280. return t_error;
  281. }
  282. }
  283. //第十步
  284. free(p_data_point);
  285. free(p_data_type);
  286. return Error_code::SUCCESS;
  287. }
  288. Predict_with_network& Point_sift_segmentation::get_predict_with_network()
  289. {
  290. return m_predict_with_network;
  291. }
  292. //使用体素网格, 抽稀点云, //将点云空间分为小方格,每个小方格只保留一个点.
  293. Error_manager Point_sift_segmentation::filter_cloud_with_voxel_grid(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud)
  294. {
  295. if(p_cloud.get()==0)
  296. {
  297. return Error_manager(LOCATER_SIFT_INPUT_CLOUD_UNINIT,MINOR_ERROR,"sift input cloud uninit");
  298. }
  299. if(p_cloud->size()<=0)
  300. {
  301. return Error_manager(LOCATER_SIFT_INPUT_CLOUD_EMPTY,MINOR_ERROR,"locate_sift input cloud empty");
  302. }
  303. //体素网格 下采样
  304. pcl::VoxelGrid<pcl::PointXYZ> vgfilter;
  305. vgfilter.setInputCloud(p_cloud);
  306. vgfilter.setLeafSize(0.02f, 0.02f, 0.02f);
  307. vgfilter.filter(*p_cloud);
  308. return Error_code::SUCCESS;
  309. }
  310. //使用box限定点云范围,只保留box范围内部的点, 剔除外部的点云
  311. Error_manager Point_sift_segmentation::filter_cloud_with_box(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud)
  312. {
  313. if(p_cloud.get()==0)
  314. {
  315. return Error_manager(LOCATER_SIFT_INPUT_CLOUD_UNINIT,MINOR_ERROR,"sift input cloud uninit");
  316. }
  317. if(p_cloud->size()<=0)
  318. {
  319. return Error_manager(LOCATER_SIFT_INPUT_CLOUD_EMPTY,MINOR_ERROR,"locate_sift input cloud empty");
  320. }
  321. //限制 x y
  322. pcl::PassThrough<pcl::PointXYZ> passX;
  323. pcl::PassThrough<pcl::PointXYZ> passY;
  324. pcl::PassThrough<pcl::PointXYZ> passZ;
  325. passX.setInputCloud(p_cloud);
  326. passX.setFilterFieldName("x");
  327. passX.setFilterLimits(m_cloud_box_limit.x_min, m_cloud_box_limit.x_max);
  328. passX.filter(*p_cloud);
  329. passY.setInputCloud(p_cloud);
  330. passY.setFilterFieldName("y");
  331. passY.setFilterLimits(m_cloud_box_limit.y_min, m_cloud_box_limit.y_max);
  332. passY.filter(*p_cloud);
  333. passZ.setInputCloud(p_cloud);
  334. passZ.setFilterFieldName("z");
  335. passZ.setFilterLimits(m_cloud_box_limit.z_min, m_cloud_box_limit.z_max);
  336. passZ.filter(*p_cloud);
  337. return Error_code::SUCCESS;
  338. }
  339. //通过输入点云,更新边界区域范围
  340. Error_manager Point_sift_segmentation::update_region(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud)
  341. {
  342. pcl::PointXYZ min_point,max_point;
  343. pcl::getMinMax3D(*p_cloud,min_point,max_point);
  344. if(max_point.x<=min_point.x || max_point.y<=min_point.y)
  345. {
  346. return Error_manager(LOCATER_SIFT_INPUT_BOX_PARAMETER_FAILED,MINOR_ERROR,
  347. "Point sift update_region errror :m_maxp.x<=m_minp.x || m_maxp.y<=m_minp.y ");
  348. }
  349. m_minp = min_point;
  350. m_maxp = max_point;
  351. return Error_code::SUCCESS;
  352. }
  353. //抽稀点云, //自己写的算法, 重新生成新的点云.
  354. Error_manager Point_sift_segmentation::filter_cloud_with_my_grid(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud)
  355. {
  356. if(p_cloud.get()==NULL)
  357. {
  358. return Error_manager(LOCATER_SIFT_INPUT_CLOUD_UNINIT,MINOR_ERROR,"sift input cloud uninit");
  359. }
  360. if(p_cloud->size()<=0)
  361. {
  362. return Error_manager(LOCATER_SIFT_INPUT_CLOUD_EMPTY,MINOR_ERROR,"locate_sift input cloud empty");
  363. }
  364. Error_manager t_error;
  365. //可以按照输入点云的数量, 然后动态修改 m_freq , 让其在抽稀之后,点云数量接近8192
  366. //以后在写.
  367. //按照m_freq的分辨率, 将点云拆分为很多网格
  368. //网格大小 m_freq 的3次方, 网格总数 grid_number
  369. int t_grid_length = int((m_maxp.x - m_minp.x) / m_freq) + 1;
  370. int t_grid_width = int((m_maxp.y - m_minp.y) / m_freq) + 1;
  371. int t_grid_height = int((m_maxp.z - m_minp.z) / m_freq) + 1;
  372. int t_grid_number = t_grid_length * t_grid_width * t_grid_height;
  373. // std::cout << " t_grid_length = "<<t_grid_length << " t_grid_width = "<<t_grid_width<< " t_grid_height = "<<t_grid_height<< std::endl;
  374. // std::cout << "---------------------------"<< std::endl;
  375. //创建网格->三维点的map, 每个网格里面只保留一个点,
  376. std::map<int, pcl::PointXYZ> grid_point_map;
  377. //遍历输入点云, 将每个点的索引编号写入对应的网格.
  378. for (int i = 0; i < p_cloud->size(); ++i)
  379. {
  380. //找到对应的网格.
  381. pcl::PointXYZ point = p_cloud->points[i];
  382. int id_x = (point.x - m_minp.x) / m_freq;
  383. int id_y = (point.y - m_minp.y) / m_freq;
  384. int id_z = (point.z - m_minp.z) / m_freq;
  385. // std::cout << "------------point:"<< point << std::endl;
  386. // std::cout << "------------m_minp:"<< m_minp << std::endl;
  387. // std::cout << "------------m_freq:"<< m_freq << std::endl;
  388. // std::cout << " id_x = "<<id_x << " id_y = "<<id_y<< " id_y = "<<id_y<< std::endl;
  389. if (id_x < 0 || id_x >= t_grid_length || id_y < 0 || id_y >= t_grid_width || id_z < 0 || id_z >= t_grid_height)
  390. {
  391. //无效点.不要.
  392. continue;
  393. }
  394. grid_point_map[id_x + id_y*t_grid_length + id_z*t_grid_length*t_grid_width] = point;
  395. //注:如果有多个点属于同一个网格, 那个后者就会覆盖前者, 最终保留一个点.
  396. }
  397. //检查map
  398. if ( grid_point_map.size() >0 )
  399. {
  400. //清空点云, 然后将map里面的点 重新加入p_cloud
  401. p_cloud->clear();
  402. for ( auto iter = grid_point_map.begin(); iter != grid_point_map.end(); iter++ )
  403. {
  404. p_cloud->push_back(iter->second);
  405. }
  406. }
  407. else
  408. {
  409. return Error_manager(Error_code::LOCATER_SIFT_GRID_ERROR, Error_level::MINOR_ERROR,
  410. " filter_cloud_with_my_grid error ");
  411. }
  412. /*
  413. //创建网格的数据, 内存大小为t_grid_number, 储存内容为是否存在点云的标记位.
  414. bool* tp_grid = (bool*)malloc(t_grid_number*sizeof(bool));
  415. memset(tp_grid, 0, t_grid_number*sizeof(bool));
  416. //遍历输入点云, 将每个点映射到输入网格, 每个网格最多保留一个点,多余的删除.
  417. for(pcl::PointCloud<pcl::PointXYZ>::iterator iter = p_cloud->begin(); iter !=p_cloud->end(); )
  418. {
  419. //找到对应的网格.
  420. int id_x = (iter->x - m_minp.x) / m_freq;
  421. int id_y = (iter->y - m_minp.y) / m_freq;
  422. int id_z = (iter->z - m_minp.z) / m_freq;
  423. if (id_x < 0 || id_x >= t_grid_length || id_y < 0 || id_y >= t_grid_width || id_z < 0 || id_z >= t_grid_height)
  424. {
  425. //无效点, 直接删除
  426. iter = p_cloud->erase(iter);//删除当前节点,自动指向下一个节点
  427. }
  428. else if(*(tp_grid + id_x + id_y*t_grid_length + id_z*t_grid_length*t_grid_width) == true)
  429. {
  430. //标记位为true,就表示这个网格已经有点了, 那么直接删除后者,保留前者
  431. iter = p_cloud->erase(iter);//删除当前节点,自动指向下一个节点
  432. }
  433. else
  434. {
  435. *(tp_grid + id_x + id_y*t_grid_length + id_z*t_grid_length*t_grid_width) = true;
  436. iter++;
  437. }
  438. }
  439. free(tp_grid);
  440. */
  441. return Error_code::SUCCESS;
  442. }
  443. //从点云中选出固定数量的随机点, 默认8192个点
  444. Error_manager Point_sift_segmentation::filter_cloud_with_select(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud_in, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud_out)
  445. {
  446. if(p_cloud_in.get()==NULL || p_cloud_out.get()==NULL)
  447. {
  448. return Error_manager(LOCATER_SIFT_INPUT_CLOUD_UNINIT,MINOR_ERROR,"sift input cloud uninit");
  449. }
  450. if(p_cloud_in->size()<=0)
  451. {
  452. return Error_manager(LOCATER_SIFT_INPUT_CLOUD_EMPTY,MINOR_ERROR,"locate_sift input cloud empty");
  453. }
  454. Error_manager t_error;
  455. //从输入点云 p_cloud_in 里面选出 m_point_num 个点, 然后加入 p_cloud_out
  456. //输入个数大于8192
  457. if (p_cloud_in->size() > m_point_num)
  458. {
  459. //将点云随机打乱
  460. std::random_shuffle(p_cloud_in->points.begin(), p_cloud_in->points.end());
  461. //选出输入点云前面8192个点.
  462. p_cloud_out->points.assign(p_cloud_in->points.begin(), p_cloud_in->points.begin() + m_point_num);
  463. }
  464. //输入个数小鱼8192
  465. else if (p_cloud_in->size() < m_point_num)
  466. {
  467. int add = m_point_num - p_cloud_in->size();
  468. //注意了, 输入点云不能少于4096, 否则点云分布太少, 会严重影响到TensorFlow的图像识别.
  469. if (add > p_cloud_in->size())
  470. {
  471. return Error_manager(Error_code::LOCATER_SIFT_CLOUD_VERY_LITTLE, Error_level::MINOR_ERROR,
  472. " filter_cloud_with_select p_cloud_in->size() very little ");
  473. }
  474. //将点云随机打乱
  475. std::random_shuffle(p_cloud_in->points.begin(), p_cloud_in->points.end());
  476. //选出输入点云8192个点, 不够的在加一次,
  477. p_cloud_out->points.assign(p_cloud_in->points.begin(), p_cloud_in->points.begin() + add);
  478. p_cloud_out->points.insert(p_cloud_out->points.begin(), p_cloud_in->points.begin(), p_cloud_in->points.end());
  479. }
  480. //输入个数等于8192
  481. else
  482. {
  483. //此时就不需要打乱了, 直接全部复制.
  484. p_cloud_out->points.assign(p_cloud_in->points.begin(), p_cloud_in->points.end());
  485. }
  486. if (p_cloud_out->points.size() != m_point_num)
  487. {
  488. return Error_manager(Error_code::LOCATER_SIFT_SELECT_ERROR, Error_level::MINOR_ERROR,
  489. " Point_sift_segmentation::filter_cloud_with_select error ");
  490. }
  491. return Error_code::SUCCESS;
  492. }
  493. //将点云数据转换到float*
  494. Error_manager Point_sift_segmentation::translate_cloud_to_float(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud_in, float* p_data_out)
  495. {
  496. if(p_cloud_in.get()==NULL)
  497. {
  498. return Error_manager(LOCATER_SIFT_INPUT_CLOUD_UNINIT,MINOR_ERROR,"sift input cloud uninit");
  499. }
  500. if(p_cloud_in->size() != m_point_num)
  501. {
  502. return Error_manager(Error_code::PARAMETER_ERROR, Error_level::MINOR_ERROR,
  503. " Point_sift_segmentation::translate_cloud_to_float p_cloud_in->size() error ");
  504. }
  505. if ( p_data_out == NULL )
  506. {
  507. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  508. " translate_cloud_to_float p_data_out POINTER_IS_NULL ");
  509. }
  510. //将点云的中心平移到原点,
  511. pcl::PointXYZ center;
  512. center.x = (m_minp.x + m_maxp.x) / 2.0;
  513. center.y = (m_minp.y + m_maxp.y) / 2.0;
  514. for (int i = 0; i < m_point_num; ++i)
  515. {
  516. pcl::PointXYZ point = p_cloud_in->points[i];
  517. *(p_data_out + i * 3) = point.x-center.x;
  518. *(p_data_out + i * 3+1) = point.y-center.y;
  519. *(p_data_out + i * 3+2) = point.z ;
  520. //注:三维点云的数据 不用做缩放和平移,
  521. // 这个在雷达扫描时就进行了标定和转化, 雷达传输过来的坐标就已经是公共坐标系了, (单位米)
  522. }
  523. return Error_code::SUCCESS;
  524. }
  525. //恢复点云, 将float*转换成点云
  526. //p_data_type:输入点云对应的类别, 大小为 点数*m_cls_num*float
  527. //p_data_point:输入点云数据(xyz)
  528. //cloud_vector::输出带颜色的点云vector
  529. Error_manager Point_sift_segmentation::recovery_float_to_cloud(float* p_data_type, float* p_data_point, std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& cloud_vector)
  530. {
  531. if ( p_data_type == NULL || p_data_point == NULL )
  532. {
  533. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  534. " recovery_float_to_cloud p_data_type or p_data_point POINTER_IS_NULL ");
  535. }
  536. //为cloud_vector 添加m_cls_num个点云, 提前分配内存
  537. for (int k = 0; k < m_cls_num; ++k)
  538. {
  539. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_rgb(new pcl::PointCloud<pcl::PointXYZRGB>);
  540. cloud_vector.push_back(cloud_rgb);
  541. }
  542. //遍历data数据,
  543. for (int i = 0; i < m_point_num; ++i)
  544. {
  545. pcl::PointXYZRGB t_point;
  546. t_point.x = *(p_data_point + i * 3);
  547. t_point.y = *(p_data_point + i * 3 + 1);
  548. t_point.z = *(p_data_point + i * 3 + 2);
  549. if (t_point.x > m_maxp.x || t_point.x<m_minp.x
  550. || t_point.y>m_maxp.y || t_point.y<m_minp.y
  551. || t_point.z>m_maxp.z || t_point.z < m_minp.z)
  552. {
  553. continue;
  554. }
  555. //当前点 的类别百分比的指针
  556. float* tp_type_percent = p_data_type + i*m_cls_num;
  557. //当前点 的类别, 初始化为0
  558. int t_cls = 0;
  559. //当前点 的类别, 百分比的最大值
  560. float t_type_percent_max = tp_type_percent[0];
  561. //循环比较, 找出百分比最大的类别
  562. for (int j = 1; j < m_cls_num; j++) //前面已经把第0个用来初始化了, 后续从第下一个开始比较
  563. {
  564. if (tp_type_percent[j] > t_type_percent_max)
  565. {
  566. t_type_percent_max = tp_type_percent[j];
  567. t_cls = j;
  568. }
  569. }
  570. //根据点的类别, 添加颜色, 并且分别加入到各自的点云里面
  571. switch ( t_cls )
  572. {
  573. case 0: //第0类, 绿色, 轮胎
  574. t_point.r = 0;
  575. t_point.g = 255;
  576. t_point.b = 0;
  577. break;
  578. case 1://第1类, 白色, 车身
  579. t_point.r = 255;
  580. t_point.g = 255;
  581. t_point.b = 255;
  582. break;
  583. // case 2:
  584. // ;
  585. // break;
  586. default:
  587. break;
  588. }
  589. cloud_vector[t_cls]->push_back(t_point);
  590. }
  591. //校验点云的数量, 要求size>0
  592. if(cloud_vector[0]->size() <=0)
  593. {
  594. return Error_manager(Error_code::LOCATER_SIFT_PREDICT_NO_WHEEL_POINT, Error_level::MINOR_ERROR,
  595. " recovery_float_to_cloud NO_WHEEL_POINT ");
  596. }
  597. if(cloud_vector[1]->size() <=0)
  598. {
  599. return Error_manager(Error_code::LOCATER_SIFT_PREDICT_NO_CAR_POINT, Error_level::MINOR_ERROR,
  600. " recovery_float_to_cloud NO_CAR_POINT ");
  601. }
  602. return Error_code::SUCCESS;
  603. }
  604. //恢复点云, 将float*转换成点云
  605. //p_data_type:输入点云对应的类别(取值 0 ~ m_cls_num-1 ),大小为 点数*int
  606. //p_data_point:输入点云数据(xyz)
  607. //cloud_vector::输出带颜色的点云vector
  608. Error_manager Point_sift_segmentation::recovery_float_to_cloud(int* p_data_type, float* p_data_point, std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& cloud_vector)
  609. {
  610. if ( p_data_type == NULL || p_data_point == NULL )
  611. {
  612. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  613. " recovery_float_to_cloud p_data_type or p_data_point POINTER_IS_NULL ");
  614. }
  615. //为cloud_vector 添加m_cls_num个点云, 提前分配内存
  616. for (int k = 0; k < m_cls_num; ++k)
  617. {
  618. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_rgb(new pcl::PointCloud<pcl::PointXYZRGB>);
  619. cloud_vector.push_back(cloud_rgb);
  620. }
  621. pcl::PointXYZ center;
  622. center.x = (m_minp.x + m_maxp.x) / 2.0;
  623. center.y = (m_minp.y + m_maxp.y) / 2.0;
  624. //将点云从原点移动到原处
  625. for (int i = 0; i < m_point_num; ++i)
  626. {
  627. pcl::PointXYZRGB t_point;
  628. t_point.x = *(p_data_point + i * 3)+center.x;
  629. t_point.y = *(p_data_point + i * 3 + 1)+center.y;
  630. t_point.z = *(p_data_point + i * 3 + 2);
  631. if (t_point.x > m_maxp.x || t_point.x<m_minp.x
  632. || t_point.y>m_maxp.y || t_point.y<m_minp.y
  633. || t_point.z>m_maxp.z || t_point.z < m_minp.z)
  634. {
  635. continue;
  636. }
  637. //当前点 的类别, 初始化为0
  638. int t_cls = p_data_type[i];
  639. //根据点的类别, 添加颜色, 并且分别加入到各自的点云里面
  640. switch ( t_cls )
  641. {
  642. case 0: //第0类, 绿色, 轮胎
  643. t_point.r = 0;
  644. t_point.g = 255;
  645. t_point.b = 0;
  646. cloud_vector[0]->push_back(t_point);
  647. break;
  648. case 1://第1类, 白色, 车身
  649. // t_point.r = 255;
  650. // t_point.g = 255;
  651. // t_point.b = 255;
  652. // cloud_vector[t_cls]->push_back(t_point);
  653. break;
  654. case 2://第1类, 白色, 车身
  655. t_point.r = 255;
  656. t_point.g = 255;
  657. t_point.b = 255;
  658. cloud_vector[1]->push_back(t_point);
  659. default:
  660. break;
  661. }
  662. }
  663. //校验点云的数量, 要求size>0
  664. if(cloud_vector[0]->size() <=0)
  665. {
  666. return Error_manager(Error_code::LOCATER_SIFT_PREDICT_NO_WHEEL_POINT, Error_level::MINOR_ERROR,
  667. " recovery_float_to_cloud NO_WHEEL_POINT ");
  668. }
  669. if(cloud_vector[1]->size() <=0)
  670. {
  671. return Error_manager(Error_code::LOCATER_SIFT_PREDICT_NO_CAR_POINT, Error_level::MINOR_ERROR,
  672. " recovery_float_to_cloud NO_CAR_POINT ");
  673. }
  674. return Error_code::SUCCESS;
  675. }
  676. //保存点云数据
  677. Error_manager Point_sift_segmentation::save_cloud(std::vector<pcl::PointCloud<pcl::PointXYZRGB>::Ptr>& cloud_vector,std::string save_dir)
  678. {
  679. if(cloud_vector.size()>0) {
  680. std::string sift_in = save_dir + "/SIFT_cls_0.txt";
  681. save_rgb_cloud_txt(sift_in, *cloud_vector[0]);
  682. }
  683. if(cloud_vector.size()>1) {
  684. std::string sift_in = save_dir + "/SIFT_cls_1.txt";
  685. save_rgb_cloud_txt(sift_in, *cloud_vector[1]);
  686. }
  687. if(cloud_vector.size()>2) {
  688. std::string sift_in = save_dir + "/SIFT_cls_2.txt";
  689. save_rgb_cloud_txt(sift_in, *cloud_vector[2]);
  690. }
  691. std::string sift_in = save_dir + "/SIFT_TOTAL.txt";
  692. save_rgb_cloud_txt(sift_in, cloud_vector);
  693. return Error_code::SUCCESS;
  694. }