grab_point_rs.cpp 25 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823
  1. /*
  2. 通过点云数据识别抓取位置信息
  3. 1)获取点云
  4. 2)剔除离群点
  5. 3)降采样
  6. 4)植株检测
  7. 5)选出最前,最右侧植株
  8. 6)植株抓取位置检测
  9. */
  10. #include <pcl\io\ply_io.h>
  11. #include <pcl\visualization\cloud_viewer.h>
  12. #include <pcl\filters\crop_box.h>
  13. #include <pcl\filters\radius_outlier_removal.h>
  14. #include <pcl\filters\voxel_grid.h>
  15. #include <pcl\common\common.h>
  16. #include <math.h>
  17. #include "grab_point_rs.h"
  18. #include "utils.h"
  19. #define PI std::acos(-1)
  20. namespace graft_cv {
  21. CRootStockGrabPoint::CRootStockGrabPoint(ConfigParam&cp, CGcvLogger*pLog/*=0*/)
  22. :m_cparam(cp),
  23. m_pLogger(pLog),
  24. m_dtype(0)
  25. {
  26. }
  27. CRootStockGrabPoint::~CRootStockGrabPoint() {}
  28. float* CRootStockGrabPoint::get_raw_point_cloud(int &data_size)
  29. {
  30. data_size = m_raw_cloud->width * m_raw_cloud->height;
  31. if (data_size == 0) {
  32. return 0;
  33. }
  34. else {
  35. pcl::PointXYZ* pp = m_raw_cloud->points.data();
  36. return (float*)pp->data;
  37. }
  38. }
  39. int CRootStockGrabPoint::load_data(
  40. float*pPoint,
  41. int pixel_size,
  42. int pt_size,
  43. const char* fn/* = 0*/)
  44. {
  45. int rst = 0;
  46. //1 get point cloud data
  47. if (pPoint != 0 && pt_size>0) {
  48. //read point
  49. m_raw_cloud.reset(new pcl::PointCloud<pcl::PointXYZ>);
  50. int step = pixel_size;
  51. for (int i = 0; i < pt_size; ++i) {
  52. pcl::PointXYZ pt = { pPoint[i*step], pPoint[i*step + 1] , pPoint[i*step + 2] };
  53. m_raw_cloud->push_back(pt);
  54. }
  55. rst = m_raw_cloud->width * m_raw_cloud->height;
  56. if (m_pLogger) {
  57. stringstream buff;
  58. buff << "load raw point cloud " << rst << " data points";
  59. m_pLogger->INFO(buff.str());
  60. }
  61. }
  62. else if (fn != 0) {
  63. //read file
  64. rst = this->read_ply_file(fn);
  65. }
  66. else {//error
  67. if (m_pLogger) {
  68. m_pLogger->ERRORINFO("no valid input");
  69. return (-1);
  70. }
  71. }
  72. if (m_cparam.image_show) {
  73. viewer_cloud(m_raw_cloud, std::string("raw point cloud"));
  74. }
  75. return rst;
  76. }
  77. int CRootStockGrabPoint::grab_point_detect(
  78. int dtype,
  79. PositionInfo& posinfo
  80. )
  81. {
  82. // dtype == 0, scion
  83. // dtype != 0, rootstock
  84. // 输入,穗苗--0, 砧木--1
  85. if (m_raw_cloud->width * m_raw_cloud->height < 1) {
  86. if (m_pLogger) {
  87. stringstream buff;
  88. buff << "m_raw_cloud point cloud " << m_raw_cloud->width * m_raw_cloud->height << " data points";
  89. m_pLogger->ERRORINFO(buff.str());
  90. }
  91. return 1;
  92. }
  93. //2 crop filter
  94. if (m_pLogger) {
  95. m_pLogger->INFO("begin crop");
  96. }
  97. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  98. pcl::CropBox<pcl::PointXYZ> box_filter;
  99. m_dtype = dtype;
  100. if (dtype != 0) {//rootstock
  101. box_filter.setMin(Eigen::Vector4f(m_cparam.rs_grab_xmin, m_cparam.rs_grab_ymin, m_cparam.rs_grab_zmin, 1));
  102. box_filter.setMax(Eigen::Vector4f(m_cparam.rs_grab_xmax, m_cparam.rs_grab_ymax, m_cparam.rs_grab_zmax, 1));
  103. }
  104. else {//scion
  105. box_filter.setMin(Eigen::Vector4f(m_cparam.sc_grab_xmin, m_cparam.sc_grab_ymin, m_cparam.sc_grab_zmin, 1));
  106. box_filter.setMax(Eigen::Vector4f(m_cparam.sc_grab_xmax, m_cparam.sc_grab_ymax, m_cparam.sc_grab_zmax, 1));
  107. }
  108. box_filter.setNegative(false);
  109. box_filter.setInputCloud(m_raw_cloud);
  110. box_filter.filter(*cloud_inbox);
  111. if (m_pLogger) {
  112. stringstream buff;
  113. buff << "CropBox croped point cloud " << cloud_inbox->width * cloud_inbox->height << " data points";
  114. m_pLogger->INFO(buff.str());
  115. }
  116. if (cloud_inbox->width * cloud_inbox->height < 1) {
  117. return 1;
  118. }
  119. if (m_cparam.image_show) {
  120. viewer_cloud(cloud_inbox, std::string("cloud_inbox"));
  121. }
  122. if (m_pLogger) {
  123. m_pLogger->INFO("end crop");
  124. }
  125. //3 filtler with radius remove
  126. if (m_pLogger) {
  127. m_pLogger->INFO("begin ror");
  128. }
  129. int nb_points = 20;
  130. double stem_radius = m_cparam.rs_grab_stem_diameter / 2.0;
  131. if(dtype == 0){
  132. stem_radius = m_cparam.sc_grab_stem_diameter / 2.0;
  133. }
  134. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ror(new pcl::PointCloud<pcl::PointXYZ>);
  135. pcl::RadiusOutlierRemoval<pcl::PointXYZ> ror;
  136. ror.setInputCloud(cloud_inbox);
  137. ror.setRadiusSearch(stem_radius);
  138. ror.setMinNeighborsInRadius(nb_points);
  139. ror.filter(*cloud_ror);
  140. if (m_pLogger) {
  141. stringstream buff;
  142. buff << "RadiusOutlierRemoval filtered point cloud " << cloud_ror->width * cloud_ror->height << " data points. param stem_radius="<<
  143. stem_radius<<", nb_points="<< nb_points;
  144. m_pLogger->INFO(buff.str());
  145. }
  146. if (cloud_ror->width * cloud_ror->height < 1) {
  147. return 1;
  148. }
  149. if (m_cparam.image_show) {
  150. viewer_cloud(cloud_ror, std::string("cloud_ror"));
  151. }
  152. if (m_pLogger) {
  153. m_pLogger->INFO("end ror");
  154. }
  155. //3 voxel grid down sampling
  156. if (m_pLogger) {
  157. m_pLogger->INFO("begin down");
  158. }
  159. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_dowm_sampled(new pcl::PointCloud<pcl::PointXYZ>);
  160. pcl::VoxelGrid<pcl::PointXYZ> outrem;
  161. outrem.setInputCloud(cloud_ror);
  162. outrem.setLeafSize(stem_radius, stem_radius, stem_radius);
  163. outrem.filter(*cloud_dowm_sampled);
  164. if (m_pLogger) {
  165. stringstream buff;
  166. buff << "VoxelGrid dowm_sampled point cloud " << cloud_dowm_sampled->width * cloud_dowm_sampled->height << " data points";
  167. m_pLogger->INFO(buff.str());
  168. }
  169. if (cloud_dowm_sampled->width * cloud_dowm_sampled->height < 1) {
  170. return 1;
  171. }
  172. if (m_cparam.image_show) {
  173. viewer_cloud(cloud_dowm_sampled, std::string("cloud_dowm_sampled"));
  174. }
  175. if (m_pLogger) {
  176. m_pLogger->INFO("end down");
  177. }
  178. //4 seedling position
  179. std::vector<int> first_seedling_cloud_idx;
  180. pcl::PointXYZ xz_center;
  181. if (m_pLogger) {
  182. m_pLogger->INFO("begin find seedling position");
  183. }
  184. find_seedling_position(cloud_dowm_sampled, first_seedling_cloud_idx, xz_center);
  185. if (m_pLogger) {
  186. stringstream buff;
  187. buff << "after find_seedling_position(), foud first seedling seeds points size " << first_seedling_cloud_idx .size();
  188. m_pLogger->INFO(buff.str());
  189. }
  190. if (m_pLogger) {
  191. m_pLogger->INFO("end find seedling position");
  192. }
  193. //5 nearest seedling grab point selection
  194. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_seedling_seed(new pcl::PointCloud<pcl::PointXYZ>);
  195. pcl::copyPointCloud(*cloud_dowm_sampled, first_seedling_cloud_idx, *cloud_seedling_seed);
  196. std::vector<int>mass_idx;
  197. double dist_mean = compute_nearest_neighbor_distance(cloud_dowm_sampled);
  198. std::vector<double> mass_indices;
  199. if (m_pLogger) {
  200. m_pLogger->INFO("begin crop nn_analysis");
  201. }
  202. crop_nn_analysis(cloud_ror, cloud_seedling_seed, dist_mean, mass_indices, mass_idx);
  203. if (m_pLogger) {
  204. m_pLogger->INFO("end crop nn_analysis");
  205. }
  206. double candidate_th = otsu(mass_indices);
  207. std::vector<int> optimal_seeds_idx;
  208. for (size_t j = 0; j < mass_idx.size(); ++j) {
  209. if (mass_indices.at(mass_idx.at(j)) >= candidate_th) {
  210. optimal_seeds_idx.push_back(mass_idx.at(j));
  211. }
  212. }
  213. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_optimal_seed(new pcl::PointCloud<pcl::PointXYZ>);
  214. pcl::copyPointCloud(*cloud_seedling_seed, optimal_seeds_idx, *cloud_optimal_seed);
  215. pcl::PointXYZ selected_pt;
  216. int selected_pt_idx;
  217. if (m_pLogger) {
  218. m_pLogger->INFO("begin get_optimal_seed");
  219. }
  220. get_optimal_seed(cloud_optimal_seed, selected_pt, selected_pt_idx);
  221. if (selected_pt_idx < 0) {
  222. return 1;
  223. }
  224. if (m_pLogger) {
  225. m_pLogger->INFO("end get_optimal_seed");
  226. }
  227. posinfo.rs_grab_x = selected_pt.x;
  228. posinfo.rs_grab_y = selected_pt.y;
  229. posinfo.rs_grab_z = selected_pt.z;
  230. ////////////////////////////////////////////////////////////////////
  231. //debug
  232. if (m_cparam.image_show) {
  233. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_cand_demo(new pcl::PointCloud<pcl::PointXYZRGB>);
  234. pcl::copyPointCloud(*cloud_dowm_sampled, *cloud_cand_demo);
  235. for (auto& pt : *cloud_cand_demo) {
  236. pt.r = 255;
  237. pt.g = 255;
  238. pt.b = 255;
  239. }
  240. int cnt = 0;
  241. for (auto& idx : mass_idx) {
  242. int p_idx = first_seedling_cloud_idx.at(idx);
  243. /*if (p_idx == optimal_seeds_idx[selected_pt_idx]) {
  244. cloud_cand_demo->points[p_idx].r = 0;
  245. cloud_cand_demo->points[p_idx].g = 255;
  246. cloud_cand_demo->points[p_idx].b = 0;
  247. }
  248. else {*/
  249. cloud_cand_demo->points.at(p_idx).r = 255;
  250. cloud_cand_demo->points.at(p_idx).g = 0;
  251. cloud_cand_demo->points.at(p_idx).b = 0;
  252. /*} */
  253. if (cnt > optimal_seeds_idx.size()) { break; }
  254. cnt++;
  255. }
  256. pcl::PointXYZRGB pt_grab = {0,255,0};
  257. pt_grab.x = selected_pt.x;
  258. pt_grab.y = selected_pt.y;
  259. pt_grab.z = selected_pt.z;
  260. pcl::PointXYZRGB pt_grab_ = { 0,255,120 };
  261. pt_grab_.x = selected_pt.x;
  262. pt_grab_.y = selected_pt.y+0.2;
  263. pt_grab_.z = selected_pt.z;
  264. cloud_cand_demo->push_back(pt_grab);
  265. //viewer_cloud(cloud_cand_demo, std::string("cloud_cand_demo"));
  266. viewer_cloud_debug(cloud_cand_demo, selected_pt, std::string("cloud_cand_demo"));
  267. }
  268. return 0;
  269. }
  270. int CRootStockGrabPoint::read_ply_file(const char* fn)
  271. {
  272. m_raw_cloud.reset( new pcl::PointCloud<pcl::PointXYZ>);
  273. if (pcl::io::loadPLYFile<pcl::PointXYZ>(fn, *m_raw_cloud) == -1) {
  274. if (m_pLogger) {
  275. m_pLogger->ERRORINFO("could not load file: "+std::string(fn));
  276. }
  277. return (-1);
  278. }
  279. if (m_pLogger) {
  280. stringstream buff;
  281. buff << "load raw point cloud " << m_raw_cloud->width * m_raw_cloud->height << " data points";
  282. m_pLogger->INFO(buff.str());
  283. }
  284. return m_raw_cloud->width * m_raw_cloud->height;
  285. }
  286. double CRootStockGrabPoint::compute_nearest_neighbor_distance(pcl::PointCloud<pcl::PointXYZ>::Ptr pcd)
  287. {
  288. pcl::KdTreeFLANN<pcl::PointXYZ> tree;
  289. tree.setInputCloud(pcd);
  290. int k = 2;
  291. double res = 0.0;
  292. int n_points = 0;
  293. for (size_t i = 0; i < pcd->size(); ++i) {
  294. std::vector<int> idx(k);
  295. std::vector<float> sqr_distances(k);
  296. if (tree.nearestKSearch(i, k, idx, sqr_distances) == k) {
  297. for (int id = 1; id < k; ++id) {
  298. res += sqrt(sqr_distances.at(id));
  299. ++n_points;
  300. }
  301. }
  302. }
  303. if (n_points > 0) {
  304. res /= (double)n_points;
  305. }
  306. return res;
  307. }
  308. void CRootStockGrabPoint::find_seedling_position(
  309. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  310. std::vector<int> &first_seedling_cloud_idx,
  311. pcl::PointXYZ&xz_center
  312. )
  313. {
  314. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2d(new pcl::PointCloud < pcl::PointXYZ>);
  315. pcl::copyPointCloud(*in_cloud, *cloud2d);
  316. for (auto&pt : *cloud2d) {
  317. pt.y = 0.0;
  318. }
  319. if(m_cparam.image_show){
  320. viewer_cloud(cloud2d, std::string("cloud2d"));
  321. }
  322. double radius = m_cparam.rs_grab_stem_diameter;
  323. if (m_dtype == 0) {
  324. radius = m_cparam.sc_grab_stem_diameter;
  325. }
  326. std::vector<int> counter;
  327. pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
  328. kdtree.setInputCloud(cloud2d);
  329. std::vector<int>idx;
  330. std::vector<float>dist_sqr;
  331. for (size_t i = 0; i < cloud2d->points.size(); ++i) {
  332. int k = kdtree.radiusSearch(cloud2d->points.at(i), radius, idx, dist_sqr);
  333. counter.push_back(k);
  334. }
  335. int th = (int)(otsu(counter));
  336. std::vector<int> index;
  337. for (size_t i = 0; i < counter.size(); ++i) {
  338. if (counter.at(i) >= th) {
  339. index.push_back(i);
  340. }
  341. }
  342. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2d_pos(new pcl::PointCloud < pcl::PointXYZ>);
  343. pcl::copyPointCloud(*cloud2d, index, *cloud2d_pos);
  344. if (m_pLogger) {
  345. stringstream buff;
  346. buff << "get 2d seedling seed point cloud " << index.size()<< " data points with thrreshold "<<th;
  347. m_pLogger->INFO(buff.str());
  348. }
  349. if (m_cparam.image_show) {
  350. viewer_cloud(cloud2d_pos, std::string("cloud2d_pos"));
  351. }
  352. //clustering
  353. double d1 = m_cparam.rs_grab_stem_diameter;
  354. double d2 = m_cparam.rs_grab_stem_diameter * 3.0;
  355. if (m_dtype == 0) {
  356. d1 = m_cparam.sc_grab_stem_diameter;
  357. d2 = m_cparam.sc_grab_stem_diameter * 3.0;
  358. }
  359. std::vector<pcl::PointXYZ>cluster_center;
  360. std::vector<std::vector<int>> cluster_member;
  361. euclidean_clustering_ttsas(cloud2d_pos, d1, d2, cluster_center, cluster_member);
  362. if (m_pLogger) {
  363. stringstream buff;
  364. buff << "euclidean_clustering_ttsas: " << cluster_center.size() << " t1=" << d1
  365. << " t2=" << d2;
  366. m_pLogger->INFO(buff.str());
  367. }
  368. //sort cluster center, get the frontest leftest one
  369. std::vector<float> cluster_index;
  370. for (auto&pt : cluster_center) {
  371. float idx = pt.x - pt.z;
  372. cluster_index.push_back(idx);
  373. }
  374. int first_idx = std::min_element(cluster_index.begin(), cluster_index.end()) - cluster_index.begin();
  375. if (m_dtype == 0) {
  376. first_idx = std::max_element(cluster_index.begin(), cluster_index.end()) - cluster_index.begin();
  377. }
  378. first_seedling_cloud_idx.clear();
  379. for (auto&v : cluster_member.at(first_idx)) {
  380. size_t i = index.at(v);
  381. first_seedling_cloud_idx.push_back(i);
  382. }
  383. xz_center.x = cluster_center.at(first_idx).x;
  384. xz_center.y = cluster_center.at(first_idx).y;
  385. xz_center.z = cluster_center.at(first_idx).z;
  386. if (m_pLogger) {
  387. stringstream buff;
  388. buff << "euclidean_clustering_ttsas, find cluster center(" << xz_center.x
  389. <<", "<< xz_center.y<<", "<< xz_center.z<<")";
  390. m_pLogger->INFO(buff.str());
  391. }
  392. }
  393. void CRootStockGrabPoint::crop_nn_analysis(
  394. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  395. pcl::PointCloud<pcl::PointXYZ>::Ptr seed_cloud,
  396. double dist_mean,
  397. std::vector<double>&mass_indices,
  398. std::vector<int>& candidate_idx
  399. )
  400. {
  401. candidate_idx.clear();
  402. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  403. pcl::CropBox<pcl::PointXYZ> box_filter;
  404. box_filter.setNegative(false);
  405. box_filter.setInputCloud(in_cloud);
  406. double radius = 5;
  407. double rx = 0.8;
  408. double ry = 1.0;
  409. double rz = 0.8;
  410. double cx, cy, cz;
  411. double dz;
  412. for (size_t i = 0; i < seed_cloud->points.size(); ++i) {
  413. cx = seed_cloud->points.at(i).x;
  414. cy = seed_cloud->points.at(i).y;
  415. cz = seed_cloud->points.at(i).z;
  416. box_filter.setMin(Eigen::Vector4f(cx - rx*radius, cy - ry*radius, cz - rz*radius, 1));
  417. box_filter.setMax(Eigen::Vector4f(cx + rx*radius, cy + ry*radius, cz + rz*radius, 1));
  418. box_filter.filter(*cloud_inbox);
  419. //dz
  420. Eigen::Vector4f min_point;
  421. Eigen::Vector4f max_point;
  422. pcl::getMinMax3D(*cloud_inbox, min_point, max_point);
  423. dz = max_point(2) - min_point(2);
  424. //project to xy-plane
  425. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox_xy(new pcl::PointCloud<pcl::PointXYZ>);
  426. pcl::copyPointCloud(*cloud_inbox, *cloud_inbox_xy);
  427. for (auto&pt : *cloud_inbox_xy) { pt.z = 0.0; }
  428. //pca
  429. double dx_obb;
  430. double dy_obb;
  431. double angle_obb;
  432. cal_obb_2d(cloud_inbox_xy, 0, dx_obb, dy_obb, angle_obb);
  433. try {
  434. double dx_grid = dx_obb / dist_mean;
  435. double dy_grid = dy_obb / dist_mean;
  436. double dz_grid = dz / dist_mean;
  437. double fill_ratio = cloud_inbox->points.size() / dx_grid / dy_grid / dz_grid;
  438. double y_ratio = dy_obb / dx_obb/2;
  439. y_ratio = pow(y_ratio, 2);
  440. double a_ratio = cos((angle_obb - 90)*PI / 180.0);
  441. a_ratio = pow(a_ratio, 3);
  442. double mass_index = fill_ratio*y_ratio*a_ratio;
  443. mass_indices.push_back(mass_index);
  444. if (m_pLogger) {
  445. stringstream buff;
  446. buff << i << "/" << seed_cloud->points.size() << " dx=" << dx_obb << ", dy=" << dy_obb << ", fill_ratio=" << fill_ratio
  447. << ", y_ratio=" << y_ratio << ", a_ratio=" << a_ratio << ", mass_index=" << mass_index;
  448. m_pLogger->INFO(buff.str());
  449. }
  450. }
  451. catch (...) {
  452. mass_indices.push_back(0);
  453. }
  454. }
  455. // sort by mass_indices
  456. std::vector<size_t> sort_idx = sort_indexes_e(mass_indices, false);
  457. for (auto&v : sort_idx) { candidate_idx.push_back((int)v); }
  458. }
  459. void CRootStockGrabPoint::euclidean_clustering_ttsas(
  460. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  461. double d1, double d2,
  462. std::vector<pcl::PointXYZ>&cluster_center,
  463. std::vector<std::vector<int>> &clustr_member
  464. )
  465. {
  466. if (m_pLogger) {
  467. stringstream buff;
  468. buff << "euclidean_clustering_ttsas() begin...";
  469. m_pLogger->INFO(buff.str());
  470. }
  471. std::vector<int> cluster_weight;
  472. std::vector<int> data_stat;
  473. for (size_t i = 0; i < in_cloud->points.size(); ++i) { data_stat.push_back(0); }
  474. size_t data_len = in_cloud->points.size();
  475. int exists_change = 0;
  476. int prev_change = 0;
  477. int cur_change = 0;
  478. int m = 0;
  479. while (std::find(data_stat.begin(), data_stat.end(), 0) != data_stat.end()) {
  480. bool new_while_first = true;
  481. for (size_t i = 0; i < data_len; ++i) {
  482. if (data_stat.at(i) == 0 && new_while_first && exists_change == 0) {
  483. new_while_first = false;
  484. std::vector<int> idx;
  485. idx.push_back(i);
  486. clustr_member.push_back(idx);
  487. pcl::PointXYZ center;
  488. center.x = in_cloud->points.at(i).x;
  489. center.y = in_cloud->points.at(i).y;
  490. center.z = in_cloud->points.at(i).z;
  491. cluster_center.push_back(center);
  492. data_stat.at(i) = 1;
  493. cur_change += 1;
  494. cluster_weight.push_back(1);
  495. m += 1;
  496. }
  497. else if (data_stat[i] == 0) {
  498. std::vector<float> distances;
  499. for (size_t j = 0; j < clustr_member.size(); ++j) {
  500. std::vector<float> distances_sub;
  501. for (size_t jj = 0; jj < clustr_member.at(j).size(); ++jj) {
  502. size_t ele_idx = clustr_member.at(j).at(jj);
  503. double d = sqrt(
  504. (in_cloud->points.at(i).x - in_cloud->points.at(ele_idx).x) * (in_cloud->points.at(i).x - in_cloud->points.at(ele_idx).x) +
  505. (in_cloud->points.at(i).y - in_cloud->points.at(ele_idx).y) * (in_cloud->points.at(i).y - in_cloud->points.at(ele_idx).y) +
  506. (in_cloud->points.at(i).z - in_cloud->points.at(ele_idx).z) * (in_cloud->points.at(i).z - in_cloud->points.at(ele_idx).z));
  507. distances_sub.push_back(d);
  508. }
  509. double min_dist = *std::min_element(distances_sub.begin(), distances_sub.end());
  510. distances.push_back(min_dist);
  511. }
  512. int min_idx = std::min_element(distances.begin(), distances.end()) - distances.begin();
  513. if (distances.at(min_idx) < d1) {
  514. data_stat.at(i) = 1;
  515. double w = cluster_weight.at(min_idx);
  516. cluster_weight.at(min_idx) += 1;
  517. clustr_member.at(min_idx).push_back(i);
  518. cluster_center.at(min_idx).x = (cluster_center.at(min_idx).x * w + in_cloud->points.at(i).x) / (w + 1);
  519. cluster_center.at(min_idx).y = (cluster_center.at(min_idx).y * w + in_cloud->points.at(i).y) / (w + 1);
  520. cluster_center.at(min_idx).z = (cluster_center.at(min_idx).z * w + in_cloud->points.at(i).z) / (w + 1);
  521. cur_change += 1;
  522. }
  523. else if (distances.at(min_idx) > d2) {
  524. std::vector<int> idx;
  525. idx.push_back(i);
  526. clustr_member.push_back(idx);
  527. pcl::PointXYZ center;
  528. center.x = in_cloud->points.at(i).x;
  529. center.y = in_cloud->points.at(i).y;
  530. center.z = in_cloud->points.at(i).z;
  531. cluster_center.push_back(center);
  532. data_stat.at(i) = 1;
  533. cur_change += 1;
  534. cluster_weight.push_back(1);
  535. m += 1;
  536. }
  537. }
  538. else if (data_stat.at(i)== 1) {
  539. cur_change += 1;
  540. }
  541. }
  542. exists_change = fabs(cur_change - prev_change);
  543. prev_change = cur_change;
  544. cur_change = 0;
  545. }
  546. if (m_pLogger) {
  547. stringstream buff;
  548. buff << "euclidean_clustering_ttsas() end";
  549. m_pLogger->INFO(buff.str());
  550. }
  551. }
  552. void CRootStockGrabPoint::cal_obb_2d(
  553. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  554. int axis, //0--xy, 1--zy
  555. double &dx_obb,
  556. double &dy_obb,
  557. double &angle_obb
  558. )
  559. {
  560. // asign value
  561. Eigen::MatrixXd pts(in_cloud->points.size(), 2);
  562. for (size_t i = 0; i < in_cloud->points.size(); ++i) {
  563. if (axis == 0) {
  564. pts(i, 0) = in_cloud->points.at(i).x;
  565. }
  566. else {
  567. pts(i, 0) = in_cloud->points.at(i).z;
  568. }
  569. pts(i, 1) = in_cloud->points.at(i).y;
  570. }
  571. // centerlize
  572. Eigen::MatrixXd mu = pts.colwise().mean();
  573. Eigen::RowVectorXd mu_row = mu;
  574. pts.rowwise() -= mu_row;
  575. //calculate covariance
  576. Eigen::MatrixXd C = pts.adjoint()*pts;
  577. C = C.array() / (pts.cols() - 1);
  578. //compute eig
  579. Eigen::SelfAdjointEigenSolver<Eigen::MatrixXd> eig(C);
  580. Eigen::MatrixXd d = eig.eigenvalues();
  581. Eigen::MatrixXd v = eig.eigenvectors();
  582. //projection
  583. Eigen::MatrixXd p = pts * v;
  584. Eigen::VectorXd minv = p.colwise().minCoeff();
  585. Eigen::VectorXd maxv = p.colwise().maxCoeff();
  586. Eigen::VectorXd range = maxv - minv;
  587. dy_obb = range(1);
  588. dx_obb = range(0);
  589. angle_obb = std::atan2(v(1, 1), v(0, 1));
  590. if (angle_obb < 0) { angle_obb = PI + angle_obb; }
  591. angle_obb = angle_obb * 180 / PI;
  592. }
  593. //void CRootStockGrabPoint::get_optimal_seed(
  594. // pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  595. // pcl::PointXYZ&pt,
  596. // int &pt_idx)
  597. //{
  598. // double d1 = m_cparam.rs_grab_stem_diameter;
  599. // double d2 = m_cparam.rs_grab_stem_diameter * 4.0;
  600. // if (m_dtype != 0) {
  601. // d1 = m_cparam.sc_grab_stem_diameter;
  602. // d2 = m_cparam.sc_grab_stem_diameter * 4.0;
  603. // }
  604. // std::vector<pcl::PointXYZ>cluster_center;
  605. // std::vector<std::vector<int>> cluster_member;
  606. // euclidean_clustering_ttsas(in_cloud, d1, d2, cluster_center, cluster_member);
  607. // float min_y_dist = 1.0e6;
  608. // int opt_idx = -1;
  609. // int member_size = 5;
  610. // float y_opt = m_cparam.rs_grab_y_opt;
  611. // if (m_dtype != 0) {
  612. // y_opt = m_cparam.sc_grab_y_opt;
  613. // }
  614. // for (int i = 0; i < cluster_member.size(); ++i) {
  615. // if (cluster_member.at(i).size() < member_size) {
  616. // continue;
  617. // }
  618. // if (fabs(cluster_center.at(i).y -y_opt) < min_y_dist) {
  619. // min_y_dist = fabs(cluster_center.at(i).y - y_opt);
  620. // opt_idx = i;
  621. // }
  622. // }
  623. // if (opt_idx < 0) {
  624. // if (m_pLogger) {
  625. // stringstream buff;
  626. // buff << "get_optimal_seed failed, get invalid optimal cluster id";
  627. // m_pLogger->ERRORINFO(buff.str());
  628. // }
  629. // return;
  630. // }
  631. // //find nearest pt
  632. // float nearest_dist = 1.0e6;
  633. // int nearest_idx = -1;
  634. // for (int i = 0; i < cluster_member.at(opt_idx).size(); ++i) {
  635. // int idx = cluster_member.at(opt_idx).at(i);
  636. // float dist = fabs(in_cloud->points.at(idx).x - cluster_center.at(opt_idx).x) +
  637. // fabs(in_cloud->points.at(idx).y - cluster_center.at(opt_idx).y) +
  638. // fabs(in_cloud->points.at(idx).z - cluster_center.at(opt_idx).z);
  639. // if (dist < nearest_dist) {
  640. // nearest_dist = dist;
  641. // nearest_idx = idx;
  642. // }
  643. // }
  644. // pt.x = in_cloud->points.at(nearest_idx).x;
  645. // pt.y = in_cloud->points.at(nearest_idx).y;
  646. // pt.z = in_cloud->points.at(nearest_idx).z;
  647. // pt_idx = nearest_idx;
  648. //}
  649. void CRootStockGrabPoint::get_optimal_seed(
  650. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  651. pcl::PointXYZ&pt,
  652. int &pt_idx)
  653. {
  654. /*double d1 = m_cparam.rs_grab_stem_diameter;
  655. double d2 = m_cparam.rs_grab_stem_diameter * 4.0;
  656. if (m_dtype != 0) {
  657. d1 = m_cparam.sc_grab_stem_diameter;
  658. d2 = m_cparam.sc_grab_stem_diameter * 4.0;
  659. }
  660. std::vector<pcl::PointXYZ>cluster_center;
  661. std::vector<std::vector<int>> cluster_member;
  662. euclidean_clustering_ttsas(in_cloud, d1, d2, cluster_center, cluster_member);*/
  663. float min_y_dist = 1.0e6;
  664. int opt_idx = -1;
  665. int member_size = 5;
  666. float y_opt = m_cparam.rs_grab_y_opt;
  667. if (m_dtype == 0) {
  668. y_opt = m_cparam.sc_grab_y_opt;
  669. }
  670. for (int i = 0; i < in_cloud->points.size(); ++i) {
  671. /*if (cluster_member.at(i).size() < member_size) {
  672. continue;
  673. }*/
  674. if (fabs(in_cloud->points.at(i).y - y_opt) < min_y_dist) {
  675. min_y_dist = fabs(in_cloud->points.at(i).y - y_opt);
  676. opt_idx = i;
  677. }
  678. }
  679. if (opt_idx < 0) {
  680. if (m_pLogger) {
  681. stringstream buff;
  682. buff << "get_optimal_seed failed, get invalid optimal cluster id";
  683. m_pLogger->ERRORINFO(buff.str());
  684. }
  685. return;
  686. }
  687. //find nearest pt
  688. /*float nearest_dist = 1.0e6;
  689. int nearest_idx = -1;
  690. for (int i = 0; i < cluster_member.at(opt_idx).size(); ++i) {
  691. int idx = cluster_member.at(opt_idx).at(i);
  692. float dist = fabs(in_cloud->points.at(idx).x - cluster_center.at(opt_idx).x) +
  693. fabs(in_cloud->points.at(idx).y - cluster_center.at(opt_idx).y) +
  694. fabs(in_cloud->points.at(idx).z - cluster_center.at(opt_idx).z);
  695. if (dist < nearest_dist) {
  696. nearest_dist = dist;
  697. nearest_idx = idx;
  698. }
  699. }*/
  700. pt.x = in_cloud->points.at(opt_idx).x;
  701. pt.y = in_cloud->points.at(opt_idx).y;
  702. pt.z = in_cloud->points.at(opt_idx).z;
  703. pt_idx = opt_idx;
  704. }
  705. void CRootStockGrabPoint::viewer_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, std::string&winname)
  706. {
  707. pcl::visualization::CloudViewer viewer(winname);
  708. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  709. viewer.showCloud(cloud);
  710. while (!viewer.wasStopped()) {
  711. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  712. }
  713. }
  714. void CRootStockGrabPoint::viewer_cloud(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud, std::string&winname)
  715. {
  716. pcl::visualization::CloudViewer viewer(winname);
  717. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  718. viewer.showCloud(cloud);
  719. while (!viewer.wasStopped()) {
  720. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  721. }
  722. }
  723. void CRootStockGrabPoint::viewer_cloud_debug(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud, pcl::PointXYZ &p, std::string&winname)
  724. {
  725. pcl::visualization::PCLVisualizer viewer(winname);
  726. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  727. viewer.addPointCloud(cloud);
  728. viewer.addCoordinateSystem();
  729. pcl::PointXYZ p0, x1, y1,p00,x0,y0;
  730. p0.x = p.x;
  731. p0.y = p.y;
  732. p0.z = p.z;
  733. x1.x = p.x + 400.0;
  734. x1.y = p.y;
  735. x1.z = p.z;
  736. y1.x = p.x;
  737. y1.y = p.y + 200.0;
  738. y1.z = p.z;
  739. p00.x = 0.0;
  740. p00.y = 0.0;
  741. p00.z = p.z;
  742. x0.x = 600.0;
  743. x0.y = 0;
  744. x0.z = p.z;
  745. y0.x = 0.0;
  746. y0.y = 300.0;
  747. y0.z = p.z;
  748. viewer.addLine(p0, x1, 255, 0, 0, "x");
  749. viewer.addLine(p0, y1, 0, 255, 0, "y");
  750. viewer.addLine(p00, x0, 255, 0, 0, "x0");
  751. viewer.addLine(p00, y0, 0, 255, 0, "y0");
  752. while (!viewer.wasStopped()) {
  753. viewer.spinOnce(100);
  754. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  755. }
  756. }
  757. };