grab_point_rs.cpp 19 KB

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