grab_point_rs.cpp 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621
  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. {
  25. }
  26. CRootStockGrabPoint::~CRootStockGrabPoint() {}
  27. float* CRootStockGrabPoint::get_raw_point_cloud(int &data_size)
  28. {
  29. data_size = m_raw_cloud->width * m_raw_cloud->height;
  30. if (data_size == 0) {
  31. return 0;
  32. }
  33. else {
  34. pcl::PointXYZ* pp = m_raw_cloud->points.data();
  35. return (float*)pp->data;
  36. }
  37. }
  38. int CRootStockGrabPoint::load_data(
  39. float*pPoint,
  40. int pixel_size,
  41. int pt_size,
  42. const char* fn/* = 0*/)
  43. {
  44. int rst = 0;
  45. //1 get point cloud data
  46. if (pPoint != 0 && pt_size>0) {
  47. //read point
  48. m_raw_cloud.reset(new pcl::PointCloud<pcl::PointXYZ>);
  49. int step = pixel_size;
  50. for (int i = 0; i < pt_size; ++i) {
  51. pcl::PointXYZ pt = { pPoint[i*step], pPoint[i*step + 1] , pPoint[i*step + 2] };
  52. m_raw_cloud->push_back(pt);
  53. }
  54. rst = m_raw_cloud->width * m_raw_cloud->height;
  55. if (m_pLogger) {
  56. stringstream buff;
  57. buff << "load raw point cloud " << rst << " data points";
  58. m_pLogger->INFO(buff.str());
  59. }
  60. }
  61. else if (fn != 0) {
  62. //read file
  63. rst = this->read_ply_file(fn);
  64. }
  65. else {//error
  66. if (m_pLogger) {
  67. m_pLogger->ERRORINFO("no valid input");
  68. return (-1);
  69. }
  70. }
  71. if (m_cparam.image_show) {
  72. viewer_cloud(m_raw_cloud, std::string("raw point cloud"));
  73. }
  74. return rst;
  75. }
  76. int CRootStockGrabPoint::grab_point_detect(
  77. PositionInfo& posinfo
  78. )
  79. {
  80. //2 crop filter
  81. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  82. pcl::CropBox<pcl::PointXYZ> box_filter;
  83. box_filter.setMin(Eigen::Vector4f(m_cparam.rs_grab_xmin, m_cparam.rs_grab_ymin, m_cparam.rs_grab_zmin, 1));
  84. box_filter.setMax(Eigen::Vector4f(m_cparam.rs_grab_xmax, m_cparam.rs_grab_ymax, m_cparam.rs_grab_zmax, 1));
  85. box_filter.setNegative(false);
  86. box_filter.setInputCloud(m_raw_cloud);
  87. box_filter.filter(*cloud_inbox);
  88. if (m_pLogger) {
  89. stringstream buff;
  90. buff << "CropBox croped point cloud " << cloud_inbox->width * cloud_inbox->height << " data points";
  91. m_pLogger->INFO(buff.str());
  92. }
  93. if (m_cparam.image_show) {
  94. viewer_cloud(cloud_inbox, std::string("cloud_inbox"));
  95. }
  96. //3 filtler with radius remove
  97. int nb_points = 20;
  98. double stem_radius = m_cparam.rs_grab_stem_diameter / 2.0;
  99. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ror(new pcl::PointCloud<pcl::PointXYZ>);
  100. pcl::RadiusOutlierRemoval<pcl::PointXYZ> ror;
  101. ror.setInputCloud(cloud_inbox);
  102. ror.setRadiusSearch(stem_radius);
  103. ror.setMinNeighborsInRadius(nb_points);
  104. ror.filter(*cloud_ror);
  105. if (m_pLogger) {
  106. stringstream buff;
  107. buff << "RadiusOutlierRemoval filtered point cloud " << cloud_ror->width * cloud_ror->height << " data points. param stem_radius="<<
  108. stem_radius<<", nb_points="<< nb_points;
  109. m_pLogger->INFO(buff.str());
  110. }
  111. if (m_cparam.image_show) {
  112. viewer_cloud(cloud_ror, std::string("cloud_ror"));
  113. }
  114. //3 voxel grid down sampling
  115. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_dowm_sampled(new pcl::PointCloud<pcl::PointXYZ>);
  116. pcl::VoxelGrid<pcl::PointXYZ> outrem;
  117. outrem.setInputCloud(cloud_ror);
  118. outrem.setLeafSize(stem_radius, stem_radius, stem_radius);
  119. outrem.filter(*cloud_dowm_sampled);
  120. if (m_pLogger) {
  121. stringstream buff;
  122. buff << "VoxelGrid dowm_sampled point cloud " << cloud_dowm_sampled->width * cloud_dowm_sampled->height << " data points";
  123. m_pLogger->INFO(buff.str());
  124. }
  125. if (m_cparam.image_show) {
  126. viewer_cloud(cloud_dowm_sampled, std::string("cloud_dowm_sampled"));
  127. }
  128. //4 seedling position
  129. std::vector<int> first_seedling_cloud_idx;
  130. pcl::PointXYZ xz_center;
  131. find_seedling_position(cloud_dowm_sampled, first_seedling_cloud_idx, xz_center);
  132. if (m_pLogger) {
  133. stringstream buff;
  134. buff << "after find_seedling_position(), foud first seedling seeds points size " << first_seedling_cloud_idx .size();
  135. m_pLogger->INFO(buff.str());
  136. }
  137. //5 nearest seedling grab point selection
  138. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_seedling_seed(new pcl::PointCloud<pcl::PointXYZ>);
  139. pcl::copyPointCloud(*cloud_dowm_sampled, first_seedling_cloud_idx, *cloud_seedling_seed);
  140. std::vector<int>mass_idx;
  141. double dist_mean = compute_nearest_neighbor_distance(cloud_dowm_sampled);
  142. std::vector<double> mass_indices;
  143. crop_nn_analysis(cloud_ror, cloud_seedling_seed, dist_mean, mass_indices, mass_idx);
  144. double candidate_th = otsu(mass_indices);
  145. std::vector<int> optimal_seeds_idx;
  146. for (size_t j = 0; j < mass_idx.size(); ++j) {
  147. if (mass_indices[mass_idx[j]] >= candidate_th) {
  148. optimal_seeds_idx.push_back(mass_idx[j]);
  149. }
  150. }
  151. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_optimal_seed(new pcl::PointCloud<pcl::PointXYZ>);
  152. pcl::copyPointCloud(*cloud_seedling_seed, optimal_seeds_idx, *cloud_optimal_seed);
  153. pcl::PointXYZ selected_pt;
  154. int selected_pt_idx;
  155. get_optimal_seed(cloud_optimal_seed, selected_pt, selected_pt_idx);
  156. posinfo.rs_grab_x = selected_pt.x;
  157. posinfo.rs_grab_y = selected_pt.y;
  158. posinfo.rs_grab_z = selected_pt.z;
  159. ////////////////////////////////////////////////////////////////////
  160. //debug
  161. if (m_cparam.image_show) {
  162. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_cand_demo(new pcl::PointCloud<pcl::PointXYZRGB>);
  163. pcl::copyPointCloud(*cloud_dowm_sampled, *cloud_cand_demo);
  164. for (auto& pt : *cloud_cand_demo) {
  165. pt.r = 255;
  166. pt.g = 255;
  167. pt.b = 255;
  168. }
  169. int cnt = 0;
  170. for (auto& idx : mass_idx) {
  171. int p_idx = first_seedling_cloud_idx[idx];
  172. /*if (p_idx == optimal_seeds_idx[selected_pt_idx]) {
  173. cloud_cand_demo->points[p_idx].r = 0;
  174. cloud_cand_demo->points[p_idx].g = 255;
  175. cloud_cand_demo->points[p_idx].b = 0;
  176. }
  177. else {*/
  178. cloud_cand_demo->points[p_idx].r = 255;
  179. cloud_cand_demo->points[p_idx].g = 0;
  180. cloud_cand_demo->points[p_idx].b = 0;
  181. /*} */
  182. if (cnt > optimal_seeds_idx.size()) { break; }
  183. cnt++;
  184. }
  185. pcl::PointXYZRGB pt_grab = {0,255,0};
  186. pt_grab.x = selected_pt.x;
  187. pt_grab.y = selected_pt.y;
  188. pt_grab.z = selected_pt.z;
  189. pcl::PointXYZRGB pt_grab_ = { 0,255,120 };
  190. pt_grab_.x = selected_pt.x;
  191. pt_grab_.y = selected_pt.y+0.2;
  192. pt_grab_.z = selected_pt.z;
  193. cloud_cand_demo->push_back(pt_grab);
  194. viewer_cloud(cloud_cand_demo, std::string("cloud_cand_demo"));
  195. }
  196. return 0;
  197. }
  198. int CRootStockGrabPoint::read_ply_file(const char* fn)
  199. {
  200. m_raw_cloud.reset( new pcl::PointCloud<pcl::PointXYZ>);
  201. if (pcl::io::loadPLYFile<pcl::PointXYZ>(fn, *m_raw_cloud) == -1) {
  202. if (m_pLogger) {
  203. m_pLogger->ERRORINFO("could not load file: "+std::string(fn));
  204. }
  205. return (-1);
  206. }
  207. if (m_pLogger) {
  208. stringstream buff;
  209. buff << "load raw point cloud " << m_raw_cloud->width * m_raw_cloud->height << " data points";
  210. m_pLogger->INFO(buff.str());
  211. }
  212. return m_raw_cloud->width * m_raw_cloud->height;
  213. }
  214. double CRootStockGrabPoint::compute_nearest_neighbor_distance(pcl::PointCloud<pcl::PointXYZ>::Ptr pcd)
  215. {
  216. pcl::KdTreeFLANN<pcl::PointXYZ> tree;
  217. tree.setInputCloud(pcd);
  218. int k = 2;
  219. double res = 0.0;
  220. int n_points = 0;
  221. for (size_t i = 0; i < pcd->size(); ++i) {
  222. std::vector<int> idx(k);
  223. std::vector<float> sqr_distances(k);
  224. if (tree.nearestKSearch(i, k, idx, sqr_distances) == k) {
  225. for (int id = 1; id < k; ++id) {
  226. res += sqrt(sqr_distances[id]);
  227. ++n_points;
  228. }
  229. }
  230. }
  231. if (n_points > 0) {
  232. res /= (double)n_points;
  233. }
  234. return res;
  235. }
  236. void CRootStockGrabPoint::find_seedling_position(
  237. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  238. std::vector<int> &first_seedling_cloud_idx,
  239. pcl::PointXYZ&xz_center
  240. )
  241. {
  242. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2d(new pcl::PointCloud < pcl::PointXYZ>);
  243. pcl::copyPointCloud(*in_cloud, *cloud2d);
  244. for (auto&pt : *cloud2d) {
  245. pt.y = 0.0;
  246. }
  247. if(m_cparam.image_show){
  248. viewer_cloud(cloud2d, std::string("cloud2d"));
  249. }
  250. double radius = m_cparam.rs_grab_stem_diameter;
  251. std::vector<int> counter;
  252. pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
  253. kdtree.setInputCloud(cloud2d);
  254. std::vector<int>idx;
  255. std::vector<float>dist_sqr;
  256. for (size_t i = 0; i < cloud2d->points.size(); ++i) {
  257. int k = kdtree.radiusSearch(cloud2d->points[i], radius, idx, dist_sqr);
  258. counter.push_back(k);
  259. }
  260. int th = (int)(otsu(counter));
  261. std::vector<int> index;
  262. for (size_t i = 0; i < counter.size(); ++i) {
  263. if (counter[i] >= th) {
  264. index.push_back(i);
  265. }
  266. }
  267. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2d_pos(new pcl::PointCloud < pcl::PointXYZ>);
  268. pcl::copyPointCloud(*cloud2d, index, *cloud2d_pos);
  269. if (m_pLogger) {
  270. stringstream buff;
  271. buff << "get 2d seedling seed point cloud " << index.size()<< " data points with thrreshold "<<th;
  272. m_pLogger->INFO(buff.str());
  273. }
  274. if (m_cparam.image_show) {
  275. viewer_cloud(cloud2d_pos, std::string("cloud2d_pos"));
  276. }
  277. //clustering
  278. double d1 = m_cparam.rs_grab_stem_diameter;
  279. double d2 = m_cparam.rs_grab_stem_diameter * 3.0;
  280. std::vector<pcl::PointXYZ>cluster_center;
  281. std::vector<std::vector<int>> cluster_member;
  282. euclidean_clustering_ttsas(cloud2d_pos, d1, d2, cluster_center, cluster_member);
  283. if (m_pLogger) {
  284. stringstream buff;
  285. buff << "euclidean_clustering_ttsas: " << cluster_center.size() << " t1=" << d1
  286. << " t2=" << d2;
  287. m_pLogger->INFO(buff.str());
  288. }
  289. //sort cluster center, get the frontest leftest one
  290. std::vector<float> cluster_index;
  291. for (auto&pt : cluster_center) {
  292. float idx = pt.x - pt.z;
  293. cluster_index.push_back(idx);
  294. }
  295. int first_idx = std::min_element(cluster_index.begin(), cluster_index.end()) - cluster_index.begin();
  296. first_seedling_cloud_idx.clear();
  297. for (auto&v : cluster_member[first_idx]) {
  298. size_t i = index[v];
  299. first_seedling_cloud_idx.push_back(i);
  300. }
  301. xz_center.x = cluster_center[first_idx].x;
  302. xz_center.y = cluster_center[first_idx].y;
  303. xz_center.z = cluster_center[first_idx].z;
  304. if (m_pLogger) {
  305. stringstream buff;
  306. buff << "euclidean_clustering_ttsas, find cluster center(" << xz_center.x
  307. <<", "<< xz_center.y<<", "<< xz_center.z<<")";
  308. m_pLogger->INFO(buff.str());
  309. }
  310. }
  311. void CRootStockGrabPoint::crop_nn_analysis(
  312. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  313. pcl::PointCloud<pcl::PointXYZ>::Ptr seed_cloud,
  314. double dist_mean,
  315. std::vector<double>&mass_indices,
  316. std::vector<int>& candidate_idx
  317. )
  318. {
  319. candidate_idx.clear();
  320. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  321. pcl::CropBox<pcl::PointXYZ> box_filter;
  322. box_filter.setNegative(false);
  323. box_filter.setInputCloud(in_cloud);
  324. double radius = 5;
  325. double rx = 0.8;
  326. double ry = 1.0;
  327. double rz = 0.8;
  328. double cx, cy, cz;
  329. double dz;
  330. for (size_t i = 0; i < seed_cloud->points.size(); ++i) {
  331. cx = seed_cloud->points[i].x;
  332. cy = seed_cloud->points[i].y;
  333. cz = seed_cloud->points[i].z;
  334. box_filter.setMin(Eigen::Vector4f(cx - rx*radius, cy - ry*radius, cz - rz*radius, 1));
  335. box_filter.setMax(Eigen::Vector4f(cx + rx*radius, cy + ry*radius, cz + rz*radius, 1));
  336. box_filter.filter(*cloud_inbox);
  337. //dz
  338. Eigen::Vector4f min_point;
  339. Eigen::Vector4f max_point;
  340. pcl::getMinMax3D(*cloud_inbox, min_point, max_point);
  341. dz = max_point(2) - min_point(2);
  342. //project to xy-plane
  343. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox_xy(new pcl::PointCloud<pcl::PointXYZ>);
  344. pcl::copyPointCloud(*cloud_inbox, *cloud_inbox_xy);
  345. for (auto&pt : *cloud_inbox_xy) { pt.z = 0.0; }
  346. //pca
  347. double dx_obb;
  348. double dy_obb;
  349. double angle_obb;
  350. cal_obb_2d(cloud_inbox_xy, 0, dx_obb, dy_obb, angle_obb);
  351. try {
  352. double dx_grid = dx_obb / dist_mean;
  353. double dy_grid = dy_obb / dist_mean;
  354. double dz_grid = dz / dist_mean;
  355. double fill_ratio = cloud_inbox->points.size() / dx_grid / dy_grid / dz_grid;
  356. double y_ratio = dy_obb / dx_obb/2;
  357. y_ratio = pow(y_ratio, 2);
  358. double a_ratio = cos((angle_obb - 90)*PI / 180.0);
  359. a_ratio = pow(a_ratio, 3);
  360. double mass_index = fill_ratio*y_ratio*a_ratio;
  361. mass_indices.push_back(mass_index);
  362. if (m_pLogger) {
  363. stringstream buff;
  364. buff << i << "/" << seed_cloud->points.size() << " dx=" << dx_obb << ", dy=" << dy_obb << ", fill_ratio=" << fill_ratio
  365. << ", y_ratio=" << y_ratio << ", a_ratio=" << a_ratio << ", mass_index=" << mass_index;
  366. m_pLogger->INFO(buff.str());
  367. }
  368. }
  369. catch (...) {
  370. mass_indices.push_back(0);
  371. }
  372. }
  373. // sort by mass_indices
  374. std::vector<size_t> sort_idx = sort_indexes_e(mass_indices, false);
  375. for (auto&v : sort_idx) { candidate_idx.push_back((int)v); }
  376. }
  377. void CRootStockGrabPoint::euclidean_clustering_ttsas(
  378. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  379. double d1, double d2,
  380. std::vector<pcl::PointXYZ>&cluster_center,
  381. std::vector<std::vector<int>> &clustr_member
  382. )
  383. {
  384. std::vector<int> cluster_weight;
  385. std::vector<int> data_stat;
  386. for (size_t i = 0; i < in_cloud->points.size(); ++i) { data_stat.push_back(0); }
  387. size_t data_len = in_cloud->points.size();
  388. int exists_change = 0;
  389. int prev_change = 0;
  390. int cur_change = 0;
  391. int m = 0;
  392. while (std::find(data_stat.begin(), data_stat.end(), 0) != data_stat.end()) {
  393. bool new_while_first = true;
  394. for (size_t i = 0; i < data_len; ++i) {
  395. if (data_stat[i] == 0 && new_while_first && exists_change == 0) {
  396. new_while_first = false;
  397. std::vector<int> idx;
  398. idx.push_back(i);
  399. clustr_member.push_back(idx);
  400. pcl::PointXYZ center;
  401. center.x = in_cloud->points[i].x;
  402. center.y = in_cloud->points[i].y;
  403. center.z = in_cloud->points[i].z;
  404. cluster_center.push_back(center);
  405. data_stat[i] = 1;
  406. cur_change += 1;
  407. cluster_weight.push_back(1);
  408. m += 1;
  409. }
  410. else if (data_stat[i] == 0) {
  411. std::vector<float> distances;
  412. for (size_t j = 0; j < clustr_member.size(); ++j) {
  413. std::vector<float> distances_sub;
  414. for (size_t jj = 0; jj < clustr_member[j].size(); ++jj) {
  415. size_t ele_idx = clustr_member[j][jj];
  416. double d = sqrt(
  417. (in_cloud->points[i].x - in_cloud->points[ele_idx].x) * (in_cloud->points[i].x - in_cloud->points[ele_idx].x) +
  418. (in_cloud->points[i].y - in_cloud->points[ele_idx].y) * (in_cloud->points[i].y - in_cloud->points[ele_idx].y) +
  419. (in_cloud->points[i].z - in_cloud->points[ele_idx].z) * (in_cloud->points[i].z - in_cloud->points[ele_idx].z));
  420. distances_sub.push_back(d);
  421. }
  422. double min_dist = *std::min_element(distances_sub.begin(), distances_sub.end());
  423. distances.push_back(min_dist);
  424. }
  425. int min_idx = std::min_element(distances.begin(), distances.end()) - distances.begin();
  426. if (distances[min_idx] < d1) {
  427. data_stat[i] = 1;
  428. double w = cluster_weight[min_idx];
  429. cluster_weight[min_idx] += 1;
  430. clustr_member[min_idx].push_back(i);
  431. cluster_center[min_idx].x = (cluster_center[min_idx].x * w + in_cloud->points[i].x) / (w + 1);
  432. cluster_center[min_idx].y = (cluster_center[min_idx].y * w + in_cloud->points[i].y) / (w + 1);
  433. cluster_center[min_idx].z = (cluster_center[min_idx].z * w + in_cloud->points[i].z) / (w + 1);
  434. cur_change += 1;
  435. }
  436. else if (distances[min_idx] > d2) {
  437. std::vector<int> idx;
  438. idx.push_back(i);
  439. clustr_member.push_back(idx);
  440. pcl::PointXYZ center;
  441. center.x = in_cloud->points[i].x;
  442. center.y = in_cloud->points[i].y;
  443. center.z = in_cloud->points[i].z;
  444. cluster_center.push_back(center);
  445. data_stat[i] = 1;
  446. cur_change += 1;
  447. cluster_weight.push_back(1);
  448. m += 1;
  449. }
  450. }
  451. else if (data_stat[i] == 1) {
  452. cur_change += 1;
  453. }
  454. }
  455. exists_change = fabs(cur_change - prev_change);
  456. prev_change = cur_change;
  457. cur_change = 0;
  458. }
  459. }
  460. void CRootStockGrabPoint::cal_obb_2d(
  461. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  462. int axis, //0--xy, 1--zy
  463. double &dx_obb,
  464. double &dy_obb,
  465. double &angle_obb
  466. )
  467. {
  468. // asign value
  469. Eigen::MatrixXd pts(in_cloud->points.size(), 2);
  470. for (size_t i = 0; i < in_cloud->points.size(); ++i) {
  471. if (axis == 0) {
  472. pts(i, 0) = in_cloud->points[i].x;
  473. }
  474. else {
  475. pts(i, 0) = in_cloud->points[i].z;
  476. }
  477. pts(i, 1) = in_cloud->points[i].y;
  478. }
  479. // centerlize
  480. Eigen::MatrixXd mu = pts.colwise().mean();
  481. Eigen::RowVectorXd mu_row = mu;
  482. pts.rowwise() -= mu_row;
  483. //calculate covariance
  484. Eigen::MatrixXd C = pts.adjoint()*pts;
  485. C = C.array() / (pts.cols() - 1);
  486. //compute eig
  487. Eigen::SelfAdjointEigenSolver<Eigen::MatrixXd> eig(C);
  488. Eigen::MatrixXd d = eig.eigenvalues();
  489. Eigen::MatrixXd v = eig.eigenvectors();
  490. //projection
  491. Eigen::MatrixXd p = pts * v;
  492. Eigen::VectorXd minv = p.colwise().minCoeff();
  493. Eigen::VectorXd maxv = p.colwise().maxCoeff();
  494. Eigen::VectorXd range = maxv - minv;
  495. dy_obb = range(1);
  496. dx_obb = range(0);
  497. angle_obb = std::atan2(v(1, 1), v(0, 1));
  498. if (angle_obb < 0) { angle_obb = PI + angle_obb; }
  499. angle_obb = angle_obb * 180 / PI;
  500. }
  501. void CRootStockGrabPoint::get_optimal_seed(
  502. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  503. pcl::PointXYZ&pt,
  504. int &pt_idx)
  505. {
  506. double d1 = m_cparam.rs_grab_stem_diameter;
  507. double d2 = m_cparam.rs_grab_stem_diameter * 4.0;
  508. std::vector<pcl::PointXYZ>cluster_center;
  509. std::vector<std::vector<int>> cluster_member;
  510. euclidean_clustering_ttsas(in_cloud, d1, d2, cluster_center, cluster_member);
  511. float max_y = -1.0e6;
  512. int max_idx = -1;
  513. int member_size = 5;
  514. for (int i = 0; i < cluster_member.size(); ++i) {
  515. if (cluster_member[i].size() < member_size) {
  516. continue;
  517. }
  518. if (cluster_center[i].y > max_y) {
  519. max_y = cluster_center[i].y;
  520. max_idx = i;
  521. }
  522. }
  523. //find nearest pt
  524. float nearest_dist = 1.0e6;
  525. int nearest_idx = -1;
  526. for (int i = 0; i < cluster_member[max_idx].size(); ++i) {
  527. int idx = cluster_member[max_idx][i];
  528. float dist = fabs(in_cloud->points[idx].x - cluster_center[max_idx].x) +
  529. fabs(in_cloud->points[idx].y - cluster_center[max_idx].y) +
  530. fabs(in_cloud->points[idx].z - cluster_center[max_idx].z);
  531. if (dist < nearest_dist) {
  532. nearest_dist = dist;
  533. nearest_idx = idx;
  534. }
  535. }
  536. pt.x = in_cloud->points[nearest_idx].x;
  537. pt.y = in_cloud->points[nearest_idx].y;
  538. pt.z = in_cloud->points[nearest_idx].z;
  539. pt_idx = nearest_idx;
  540. }
  541. void CRootStockGrabPoint::viewer_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, std::string&winname)
  542. {
  543. pcl::visualization::CloudViewer viewer(winname);
  544. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  545. viewer.showCloud(cloud);
  546. while (!viewer.wasStopped()) {
  547. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  548. }
  549. }
  550. void CRootStockGrabPoint::viewer_cloud(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud, std::string&winname)
  551. {
  552. pcl::visualization::CloudViewer viewer(winname);
  553. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  554. viewer.showCloud(cloud);
  555. while (!viewer.wasStopped()) {
  556. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  557. }
  558. }
  559. };