grab_point_rs.cpp 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666
  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. viewer_cloud_debug(cloud_cand_demo, selected_pt, std::string("cloud_cand_demo"));
  202. }
  203. return 0;
  204. }
  205. int CRootStockGrabPoint::read_ply_file(const char* fn)
  206. {
  207. m_raw_cloud.reset( new pcl::PointCloud<pcl::PointXYZ>);
  208. if (pcl::io::loadPLYFile<pcl::PointXYZ>(fn, *m_raw_cloud) == -1) {
  209. if (m_pLogger) {
  210. m_pLogger->ERRORINFO("could not load file: "+std::string(fn));
  211. }
  212. return (-1);
  213. }
  214. if (m_pLogger) {
  215. stringstream buff;
  216. buff << "load raw point cloud " << m_raw_cloud->width * m_raw_cloud->height << " data points";
  217. m_pLogger->INFO(buff.str());
  218. }
  219. return m_raw_cloud->width * m_raw_cloud->height;
  220. }
  221. double CRootStockGrabPoint::compute_nearest_neighbor_distance(pcl::PointCloud<pcl::PointXYZ>::Ptr pcd)
  222. {
  223. pcl::KdTreeFLANN<pcl::PointXYZ> tree;
  224. tree.setInputCloud(pcd);
  225. int k = 2;
  226. double res = 0.0;
  227. int n_points = 0;
  228. for (size_t i = 0; i < pcd->size(); ++i) {
  229. std::vector<int> idx(k);
  230. std::vector<float> sqr_distances(k);
  231. if (tree.nearestKSearch(i, k, idx, sqr_distances) == k) {
  232. for (int id = 1; id < k; ++id) {
  233. res += sqrt(sqr_distances[id]);
  234. ++n_points;
  235. }
  236. }
  237. }
  238. if (n_points > 0) {
  239. res /= (double)n_points;
  240. }
  241. return res;
  242. }
  243. void CRootStockGrabPoint::find_seedling_position(
  244. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  245. std::vector<int> &first_seedling_cloud_idx,
  246. pcl::PointXYZ&xz_center
  247. )
  248. {
  249. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2d(new pcl::PointCloud < pcl::PointXYZ>);
  250. pcl::copyPointCloud(*in_cloud, *cloud2d);
  251. for (auto&pt : *cloud2d) {
  252. pt.y = 0.0;
  253. }
  254. if(m_cparam.image_show){
  255. viewer_cloud(cloud2d, std::string("cloud2d"));
  256. }
  257. double radius = m_cparam.rs_grab_stem_diameter;
  258. std::vector<int> counter;
  259. pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
  260. kdtree.setInputCloud(cloud2d);
  261. std::vector<int>idx;
  262. std::vector<float>dist_sqr;
  263. for (size_t i = 0; i < cloud2d->points.size(); ++i) {
  264. int k = kdtree.radiusSearch(cloud2d->points[i], radius, idx, dist_sqr);
  265. counter.push_back(k);
  266. }
  267. int th = (int)(otsu(counter));
  268. std::vector<int> index;
  269. for (size_t i = 0; i < counter.size(); ++i) {
  270. if (counter[i] >= th) {
  271. index.push_back(i);
  272. }
  273. }
  274. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2d_pos(new pcl::PointCloud < pcl::PointXYZ>);
  275. pcl::copyPointCloud(*cloud2d, index, *cloud2d_pos);
  276. if (m_pLogger) {
  277. stringstream buff;
  278. buff << "get 2d seedling seed point cloud " << index.size()<< " data points with thrreshold "<<th;
  279. m_pLogger->INFO(buff.str());
  280. }
  281. if (m_cparam.image_show) {
  282. viewer_cloud(cloud2d_pos, std::string("cloud2d_pos"));
  283. }
  284. //clustering
  285. double d1 = m_cparam.rs_grab_stem_diameter;
  286. double d2 = m_cparam.rs_grab_stem_diameter * 3.0;
  287. std::vector<pcl::PointXYZ>cluster_center;
  288. std::vector<std::vector<int>> cluster_member;
  289. euclidean_clustering_ttsas(cloud2d_pos, d1, d2, cluster_center, cluster_member);
  290. if (m_pLogger) {
  291. stringstream buff;
  292. buff << "euclidean_clustering_ttsas: " << cluster_center.size() << " t1=" << d1
  293. << " t2=" << d2;
  294. m_pLogger->INFO(buff.str());
  295. }
  296. //sort cluster center, get the frontest leftest one
  297. std::vector<float> cluster_index;
  298. for (auto&pt : cluster_center) {
  299. float idx = pt.x - pt.z;
  300. cluster_index.push_back(idx);
  301. }
  302. int first_idx = std::min_element(cluster_index.begin(), cluster_index.end()) - cluster_index.begin();
  303. first_seedling_cloud_idx.clear();
  304. for (auto&v : cluster_member[first_idx]) {
  305. size_t i = index[v];
  306. first_seedling_cloud_idx.push_back(i);
  307. }
  308. xz_center.x = cluster_center[first_idx].x;
  309. xz_center.y = cluster_center[first_idx].y;
  310. xz_center.z = cluster_center[first_idx].z;
  311. if (m_pLogger) {
  312. stringstream buff;
  313. buff << "euclidean_clustering_ttsas, find cluster center(" << xz_center.x
  314. <<", "<< xz_center.y<<", "<< xz_center.z<<")";
  315. m_pLogger->INFO(buff.str());
  316. }
  317. }
  318. void CRootStockGrabPoint::crop_nn_analysis(
  319. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  320. pcl::PointCloud<pcl::PointXYZ>::Ptr seed_cloud,
  321. double dist_mean,
  322. std::vector<double>&mass_indices,
  323. std::vector<int>& candidate_idx
  324. )
  325. {
  326. candidate_idx.clear();
  327. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  328. pcl::CropBox<pcl::PointXYZ> box_filter;
  329. box_filter.setNegative(false);
  330. box_filter.setInputCloud(in_cloud);
  331. double radius = 5;
  332. double rx = 0.8;
  333. double ry = 1.0;
  334. double rz = 0.8;
  335. double cx, cy, cz;
  336. double dz;
  337. for (size_t i = 0; i < seed_cloud->points.size(); ++i) {
  338. cx = seed_cloud->points[i].x;
  339. cy = seed_cloud->points[i].y;
  340. cz = seed_cloud->points[i].z;
  341. box_filter.setMin(Eigen::Vector4f(cx - rx*radius, cy - ry*radius, cz - rz*radius, 1));
  342. box_filter.setMax(Eigen::Vector4f(cx + rx*radius, cy + ry*radius, cz + rz*radius, 1));
  343. box_filter.filter(*cloud_inbox);
  344. //dz
  345. Eigen::Vector4f min_point;
  346. Eigen::Vector4f max_point;
  347. pcl::getMinMax3D(*cloud_inbox, min_point, max_point);
  348. dz = max_point(2) - min_point(2);
  349. //project to xy-plane
  350. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox_xy(new pcl::PointCloud<pcl::PointXYZ>);
  351. pcl::copyPointCloud(*cloud_inbox, *cloud_inbox_xy);
  352. for (auto&pt : *cloud_inbox_xy) { pt.z = 0.0; }
  353. //pca
  354. double dx_obb;
  355. double dy_obb;
  356. double angle_obb;
  357. cal_obb_2d(cloud_inbox_xy, 0, dx_obb, dy_obb, angle_obb);
  358. try {
  359. double dx_grid = dx_obb / dist_mean;
  360. double dy_grid = dy_obb / dist_mean;
  361. double dz_grid = dz / dist_mean;
  362. double fill_ratio = cloud_inbox->points.size() / dx_grid / dy_grid / dz_grid;
  363. double y_ratio = dy_obb / dx_obb/2;
  364. y_ratio = pow(y_ratio, 2);
  365. double a_ratio = cos((angle_obb - 90)*PI / 180.0);
  366. a_ratio = pow(a_ratio, 3);
  367. double mass_index = fill_ratio*y_ratio*a_ratio;
  368. mass_indices.push_back(mass_index);
  369. if (m_pLogger) {
  370. stringstream buff;
  371. buff << i << "/" << seed_cloud->points.size() << " dx=" << dx_obb << ", dy=" << dy_obb << ", fill_ratio=" << fill_ratio
  372. << ", y_ratio=" << y_ratio << ", a_ratio=" << a_ratio << ", mass_index=" << mass_index;
  373. m_pLogger->INFO(buff.str());
  374. }
  375. }
  376. catch (...) {
  377. mass_indices.push_back(0);
  378. }
  379. }
  380. // sort by mass_indices
  381. std::vector<size_t> sort_idx = sort_indexes_e(mass_indices, false);
  382. for (auto&v : sort_idx) { candidate_idx.push_back((int)v); }
  383. }
  384. void CRootStockGrabPoint::euclidean_clustering_ttsas(
  385. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  386. double d1, double d2,
  387. std::vector<pcl::PointXYZ>&cluster_center,
  388. std::vector<std::vector<int>> &clustr_member
  389. )
  390. {
  391. std::vector<int> cluster_weight;
  392. std::vector<int> data_stat;
  393. for (size_t i = 0; i < in_cloud->points.size(); ++i) { data_stat.push_back(0); }
  394. size_t data_len = in_cloud->points.size();
  395. int exists_change = 0;
  396. int prev_change = 0;
  397. int cur_change = 0;
  398. int m = 0;
  399. while (std::find(data_stat.begin(), data_stat.end(), 0) != data_stat.end()) {
  400. bool new_while_first = true;
  401. for (size_t i = 0; i < data_len; ++i) {
  402. if (data_stat[i] == 0 && new_while_first && exists_change == 0) {
  403. new_while_first = false;
  404. std::vector<int> idx;
  405. idx.push_back(i);
  406. clustr_member.push_back(idx);
  407. pcl::PointXYZ center;
  408. center.x = in_cloud->points[i].x;
  409. center.y = in_cloud->points[i].y;
  410. center.z = in_cloud->points[i].z;
  411. cluster_center.push_back(center);
  412. data_stat[i] = 1;
  413. cur_change += 1;
  414. cluster_weight.push_back(1);
  415. m += 1;
  416. }
  417. else if (data_stat[i] == 0) {
  418. std::vector<float> distances;
  419. for (size_t j = 0; j < clustr_member.size(); ++j) {
  420. std::vector<float> distances_sub;
  421. for (size_t jj = 0; jj < clustr_member[j].size(); ++jj) {
  422. size_t ele_idx = clustr_member[j][jj];
  423. double d = sqrt(
  424. (in_cloud->points[i].x - in_cloud->points[ele_idx].x) * (in_cloud->points[i].x - in_cloud->points[ele_idx].x) +
  425. (in_cloud->points[i].y - in_cloud->points[ele_idx].y) * (in_cloud->points[i].y - in_cloud->points[ele_idx].y) +
  426. (in_cloud->points[i].z - in_cloud->points[ele_idx].z) * (in_cloud->points[i].z - in_cloud->points[ele_idx].z));
  427. distances_sub.push_back(d);
  428. }
  429. double min_dist = *std::min_element(distances_sub.begin(), distances_sub.end());
  430. distances.push_back(min_dist);
  431. }
  432. int min_idx = std::min_element(distances.begin(), distances.end()) - distances.begin();
  433. if (distances[min_idx] < d1) {
  434. data_stat[i] = 1;
  435. double w = cluster_weight[min_idx];
  436. cluster_weight[min_idx] += 1;
  437. clustr_member[min_idx].push_back(i);
  438. cluster_center[min_idx].x = (cluster_center[min_idx].x * w + in_cloud->points[i].x) / (w + 1);
  439. cluster_center[min_idx].y = (cluster_center[min_idx].y * w + in_cloud->points[i].y) / (w + 1);
  440. cluster_center[min_idx].z = (cluster_center[min_idx].z * w + in_cloud->points[i].z) / (w + 1);
  441. cur_change += 1;
  442. }
  443. else if (distances[min_idx] > d2) {
  444. std::vector<int> idx;
  445. idx.push_back(i);
  446. clustr_member.push_back(idx);
  447. pcl::PointXYZ center;
  448. center.x = in_cloud->points[i].x;
  449. center.y = in_cloud->points[i].y;
  450. center.z = in_cloud->points[i].z;
  451. cluster_center.push_back(center);
  452. data_stat[i] = 1;
  453. cur_change += 1;
  454. cluster_weight.push_back(1);
  455. m += 1;
  456. }
  457. }
  458. else if (data_stat[i] == 1) {
  459. cur_change += 1;
  460. }
  461. }
  462. exists_change = fabs(cur_change - prev_change);
  463. prev_change = cur_change;
  464. cur_change = 0;
  465. }
  466. }
  467. void CRootStockGrabPoint::cal_obb_2d(
  468. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  469. int axis, //0--xy, 1--zy
  470. double &dx_obb,
  471. double &dy_obb,
  472. double &angle_obb
  473. )
  474. {
  475. // asign value
  476. Eigen::MatrixXd pts(in_cloud->points.size(), 2);
  477. for (size_t i = 0; i < in_cloud->points.size(); ++i) {
  478. if (axis == 0) {
  479. pts(i, 0) = in_cloud->points[i].x;
  480. }
  481. else {
  482. pts(i, 0) = in_cloud->points[i].z;
  483. }
  484. pts(i, 1) = in_cloud->points[i].y;
  485. }
  486. // centerlize
  487. Eigen::MatrixXd mu = pts.colwise().mean();
  488. Eigen::RowVectorXd mu_row = mu;
  489. pts.rowwise() -= mu_row;
  490. //calculate covariance
  491. Eigen::MatrixXd C = pts.adjoint()*pts;
  492. C = C.array() / (pts.cols() - 1);
  493. //compute eig
  494. Eigen::SelfAdjointEigenSolver<Eigen::MatrixXd> eig(C);
  495. Eigen::MatrixXd d = eig.eigenvalues();
  496. Eigen::MatrixXd v = eig.eigenvectors();
  497. //projection
  498. Eigen::MatrixXd p = pts * v;
  499. Eigen::VectorXd minv = p.colwise().minCoeff();
  500. Eigen::VectorXd maxv = p.colwise().maxCoeff();
  501. Eigen::VectorXd range = maxv - minv;
  502. dy_obb = range(1);
  503. dx_obb = range(0);
  504. angle_obb = std::atan2(v(1, 1), v(0, 1));
  505. if (angle_obb < 0) { angle_obb = PI + angle_obb; }
  506. angle_obb = angle_obb * 180 / PI;
  507. }
  508. void CRootStockGrabPoint::get_optimal_seed(
  509. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  510. pcl::PointXYZ&pt,
  511. int &pt_idx)
  512. {
  513. double d1 = m_cparam.rs_grab_stem_diameter;
  514. double d2 = m_cparam.rs_grab_stem_diameter * 4.0;
  515. std::vector<pcl::PointXYZ>cluster_center;
  516. std::vector<std::vector<int>> cluster_member;
  517. euclidean_clustering_ttsas(in_cloud, d1, d2, cluster_center, cluster_member);
  518. float max_y = -1.0e6;
  519. int max_idx = -1;
  520. int member_size = 5;
  521. for (int i = 0; i < cluster_member.size(); ++i) {
  522. if (cluster_member[i].size() < member_size) {
  523. continue;
  524. }
  525. if (cluster_center[i].y > max_y) {
  526. max_y = cluster_center[i].y;
  527. max_idx = i;
  528. }
  529. }
  530. //find nearest pt
  531. float nearest_dist = 1.0e6;
  532. int nearest_idx = -1;
  533. for (int i = 0; i < cluster_member[max_idx].size(); ++i) {
  534. int idx = cluster_member[max_idx][i];
  535. float dist = fabs(in_cloud->points[idx].x - cluster_center[max_idx].x) +
  536. fabs(in_cloud->points[idx].y - cluster_center[max_idx].y) +
  537. fabs(in_cloud->points[idx].z - cluster_center[max_idx].z);
  538. if (dist < nearest_dist) {
  539. nearest_dist = dist;
  540. nearest_idx = idx;
  541. }
  542. }
  543. pt.x = in_cloud->points[nearest_idx].x;
  544. pt.y = in_cloud->points[nearest_idx].y;
  545. pt.z = in_cloud->points[nearest_idx].z;
  546. pt_idx = nearest_idx;
  547. }
  548. void CRootStockGrabPoint::viewer_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, std::string&winname)
  549. {
  550. pcl::visualization::CloudViewer viewer(winname);
  551. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  552. viewer.showCloud(cloud);
  553. while (!viewer.wasStopped()) {
  554. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  555. }
  556. }
  557. void CRootStockGrabPoint::viewer_cloud(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud, std::string&winname)
  558. {
  559. pcl::visualization::CloudViewer viewer(winname);
  560. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  561. viewer.showCloud(cloud);
  562. while (!viewer.wasStopped()) {
  563. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  564. }
  565. }
  566. void CRootStockGrabPoint::viewer_cloud_debug(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud, pcl::PointXYZ &p, std::string&winname)
  567. {
  568. pcl::visualization::PCLVisualizer viewer(winname);
  569. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  570. viewer.addPointCloud(cloud);
  571. viewer.addCoordinateSystem();
  572. pcl::PointXYZ p0, x1, y1,p00,x0,y0;
  573. p0.x = p.x;
  574. p0.y = p.y;
  575. p0.z = p.z;
  576. x1.x = p.x + 400.0;
  577. x1.y = p.y;
  578. x1.z = p.z;
  579. y1.x = p.x;
  580. y1.y = p.y + 200.0;
  581. y1.z = p.z;
  582. p00.x = 0.0;
  583. p00.y = 0.0;
  584. p00.z = p.z;
  585. x0.x = 600.0;
  586. x0.y = 0;
  587. x0.z = p.z;
  588. y0.x = 0.0;
  589. y0.y = 300.0;
  590. y0.z = p.z;
  591. viewer.addLine(p0, x1, 255, 0, 0, "x");
  592. viewer.addLine(p0, y1, 0, 255, 0, "y");
  593. viewer.addLine(p00, x0, 255, 0, 0, "x0");
  594. viewer.addLine(p00, y0, 0, 255, 0, "y0");
  595. while (!viewer.wasStopped()) {
  596. viewer.spinOnce(100);
  597. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  598. }
  599. }
  600. };