grab_point_rs.cpp 38 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214
  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\statistical_outlier_removal.h>
  15. #include <pcl\filters\voxel_grid.h>
  16. #include <pcl\common\common.h>
  17. #include <pcl\features\moment_of_inertia_estimation.h>
  18. #include <pcl\segmentation\sac_segmentation.h>
  19. #include <math.h>
  20. #include "grab_point_rs.h"
  21. #include "utils.h"
  22. #define PI std::acos(-1)
  23. namespace graft_cv {
  24. CRootStockGrabPoint::CRootStockGrabPoint(ConfigParam&cp, CGcvLogger*pLog/*=0*/)
  25. :m_cparam(cp),
  26. m_pLogger(pLog),
  27. m_dtype(0),
  28. m_pcdId(""),
  29. m_ppImgSaver(0)
  30. {
  31. }
  32. CRootStockGrabPoint::~CRootStockGrabPoint() {}
  33. float* CRootStockGrabPoint::get_raw_point_cloud(int &data_size)
  34. {
  35. data_size = m_raw_cloud->width * m_raw_cloud->height;
  36. if (data_size == 0) {
  37. return 0;
  38. }
  39. else {
  40. pcl::PointXYZ* pp = m_raw_cloud->points.data();
  41. return (float*)pp->data;
  42. }
  43. }
  44. int CRootStockGrabPoint::load_data(
  45. float*pPoint,
  46. int pixel_size,
  47. int pt_size,
  48. const char* fn/* = 0*/)
  49. {
  50. int rst = 0;
  51. //1 get point cloud data
  52. if (pPoint != 0 && pt_size>0) {
  53. //read point
  54. m_raw_cloud.reset(new pcl::PointCloud<pcl::PointXYZ>);
  55. int step = pixel_size;
  56. for (int i = 0; i < pt_size; ++i) {
  57. pcl::PointXYZ pt = { pPoint[i*step], pPoint[i*step + 1] , pPoint[i*step + 2] };
  58. m_raw_cloud->push_back(pt);
  59. }
  60. rst = m_raw_cloud->width * m_raw_cloud->height;
  61. if (m_pLogger) {
  62. stringstream buff;
  63. buff << "load raw point cloud " << rst << " data points";
  64. m_pLogger->INFO(buff.str());
  65. }
  66. }
  67. else if (fn != 0) {
  68. //read file
  69. rst = this->read_ply_file(fn);
  70. }
  71. else {//error
  72. if (m_pLogger) {
  73. m_pLogger->ERRORINFO("no valid input");
  74. return (-1);
  75. }
  76. }
  77. if (m_dtype == 0) {
  78. m_pcdId = getImgId(img_type::sola_sc_pcd);
  79. }
  80. else {
  81. m_pcdId = getImgId(img_type::sola_rs_pcd);
  82. }
  83. if (m_ppImgSaver && *m_ppImgSaver) {
  84. (*m_ppImgSaver)->saveBinPly(m_raw_cloud, m_pcdId);
  85. }
  86. if (m_cparam.image_show) {
  87. viewer_cloud(m_raw_cloud, std::string("raw point cloud"));
  88. }
  89. return rst;
  90. }
  91. int CRootStockGrabPoint::grab_point_detect(
  92. int dtype,
  93. PositionInfo& posinfo
  94. )
  95. {
  96. // dtype == 0, scion
  97. // dtype != 0, rootstock
  98. // 输入,穗苗--0, 砧木--1
  99. if (m_raw_cloud->width * m_raw_cloud->height < 1) {
  100. if (m_pLogger) {
  101. stringstream buff;
  102. buff << "m_raw_cloud point cloud " << m_raw_cloud->width * m_raw_cloud->height << " data points";
  103. m_pLogger->ERRORINFO(buff.str());
  104. }
  105. return 1;
  106. }
  107. //2 crop filter
  108. if (m_pLogger) {
  109. m_pLogger->INFO("begin crop");
  110. }
  111. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  112. pcl::CropBox<pcl::PointXYZ> box_filter;
  113. m_dtype = dtype;
  114. if (dtype != 0) {//rootstock
  115. box_filter.setMin(Eigen::Vector4f(m_cparam.rs_grab_xmin, m_cparam.rs_grab_ymin, m_cparam.rs_grab_zmin, 1));
  116. box_filter.setMax(Eigen::Vector4f(m_cparam.rs_grab_xmax, m_cparam.rs_grab_ymax, m_cparam.rs_grab_zmax, 1));
  117. }
  118. else {//scion
  119. box_filter.setMin(Eigen::Vector4f(m_cparam.sc_grab_xmin, m_cparam.sc_grab_ymin, m_cparam.sc_grab_zmin, 1));
  120. box_filter.setMax(Eigen::Vector4f(m_cparam.sc_grab_xmax, m_cparam.sc_grab_ymax, m_cparam.sc_grab_zmax, 1));
  121. }
  122. box_filter.setNegative(false);
  123. box_filter.setInputCloud(m_raw_cloud);
  124. box_filter.filter(*cloud_inbox);
  125. if (m_pLogger) {
  126. stringstream buff;
  127. buff << "CropBox croped point cloud " << cloud_inbox->width * cloud_inbox->height << " data points";
  128. m_pLogger->INFO(buff.str());
  129. }
  130. if (cloud_inbox->width * cloud_inbox->height < 1) {
  131. return 1;
  132. }
  133. if (m_cparam.image_show) {
  134. viewer_cloud(cloud_inbox, std::string("cloud_inbox"));
  135. }
  136. if (m_pLogger) {
  137. m_pLogger->INFO("end crop");
  138. }
  139. //3 filtler with radius remove
  140. if (m_pLogger) {
  141. m_pLogger->INFO("begin ror");
  142. }
  143. int nb_points = 20;
  144. double stem_radius = m_cparam.rs_grab_stem_diameter / 2.0;
  145. if(dtype == 0){
  146. stem_radius = m_cparam.sc_grab_stem_diameter / 2.0;
  147. }
  148. double remove_radius = stem_radius * 2.0;
  149. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ror(new pcl::PointCloud<pcl::PointXYZ>);
  150. pcl::RadiusOutlierRemoval<pcl::PointXYZ> ror(false);
  151. ror.setInputCloud(cloud_inbox);
  152. ror.setRadiusSearch(remove_radius);
  153. ror.setMinNeighborsInRadius(nb_points);
  154. ror.filter(*cloud_ror);
  155. if (m_pLogger) {
  156. stringstream buff;
  157. buff << "RadiusOutlierRemoval filtered point cloud " << cloud_ror->width * cloud_ror->height << " data points. param stem_radius="<<
  158. stem_radius<<", nb_points="<< nb_points;
  159. m_pLogger->INFO(buff.str());
  160. }
  161. if (cloud_ror->width * cloud_ror->height < 1) {
  162. return 1;
  163. }
  164. /*if (m_cparam.image_show) {
  165. viewer_cloud(cloud_ror, std::string("cloud_ror"));
  166. }*/
  167. if (m_pLogger) {
  168. m_pLogger->INFO("end ror");
  169. }
  170. ///////////////////////////////////////////////////////////////////////////////
  171. //3 voxel grid down sampling
  172. if (m_pLogger) {
  173. m_pLogger->INFO("begin down");
  174. }
  175. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_dowm_sampled(new pcl::PointCloud<pcl::PointXYZ>);
  176. pcl::VoxelGrid<pcl::PointXYZ> outrem;
  177. outrem.setInputCloud(cloud_ror);
  178. outrem.setLeafSize(stem_radius, stem_radius, stem_radius);
  179. outrem.filter(*cloud_dowm_sampled);
  180. if (m_pLogger) {
  181. stringstream buff;
  182. buff << "VoxelGrid dowm_sampled point cloud " << cloud_dowm_sampled->width * cloud_dowm_sampled->height << " data points (if < 50, return)";
  183. m_pLogger->INFO(buff.str());
  184. }
  185. if (cloud_dowm_sampled->width * cloud_dowm_sampled->height < 50) {
  186. return 1;
  187. }
  188. /*if (m_cparam.image_show) {
  189. viewer_cloud(cloud_dowm_sampled, std::string("cloud_dowm_sampled"));
  190. }*/
  191. if (m_pLogger) {
  192. m_pLogger->INFO("end down");
  193. }
  194. ///////////////////////////////////////////////////////////////////////////////
  195. //4 seedling position
  196. std::vector<int> first_seedling_cloud_idx;
  197. pcl::PointXYZ xz_center;
  198. if (m_pLogger) {
  199. m_pLogger->INFO("begin find seedling position");
  200. }
  201. //find_seedling_position_line_based(cloud_ror, first_seedling_cloud_idx, xz_center);
  202. find_seedling_position(cloud_dowm_sampled, first_seedling_cloud_idx, xz_center);
  203. if (m_pLogger) {
  204. stringstream buff;
  205. buff << "after find_seedling_position(), foud first seedling seeds points size " << first_seedling_cloud_idx.size();
  206. m_pLogger->INFO(buff.str());
  207. }
  208. if (m_pLogger) {
  209. m_pLogger->INFO("end find seedling position");
  210. }
  211. ///////////////////////////////////////////////////////////////////////////////
  212. //5 nearest seedling grab point selection
  213. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_seedling_seed(new pcl::PointCloud<pcl::PointXYZ>);
  214. pcl::copyPointCloud(*cloud_dowm_sampled, first_seedling_cloud_idx, *cloud_seedling_seed);
  215. std::vector<int>mass_idx;
  216. double dist_mean = compute_nearest_neighbor_distance(cloud_dowm_sampled);
  217. std::vector<double> mass_indices;
  218. if (m_pLogger) {
  219. m_pLogger->INFO("begin crop nn_analysis");
  220. }
  221. crop_nn_analysis(cloud_ror, cloud_seedling_seed, dist_mean, mass_indices, mass_idx);
  222. if (m_pLogger) {
  223. m_pLogger->INFO("end crop nn_analysis");
  224. }
  225. double candidate_th = otsu(mass_indices);
  226. std::vector<int> optimal_seeds_idx;
  227. for (size_t j = 0; j < mass_idx.size(); ++j) {
  228. if (mass_indices.at(mass_idx.at(j)) >= candidate_th) {
  229. optimal_seeds_idx.push_back(mass_idx.at(j));
  230. }
  231. }
  232. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_optimal_seed(new pcl::PointCloud<pcl::PointXYZ>);
  233. pcl::copyPointCloud(*cloud_seedling_seed, optimal_seeds_idx, *cloud_optimal_seed);
  234. pcl::PointXYZ selected_pt;
  235. int selected_pt_idx;
  236. if (m_pLogger) {
  237. m_pLogger->INFO("begin get_optimal_seed");
  238. }
  239. get_optimal_seed(cloud_optimal_seed, selected_pt, selected_pt_idx);
  240. if (selected_pt_idx < 0) {
  241. return 1;
  242. }
  243. if (m_pLogger) {
  244. m_pLogger->INFO("end get_optimal_seed");
  245. }
  246. posinfo.rs_grab_x = selected_pt.x;
  247. posinfo.rs_grab_y = selected_pt.y;
  248. posinfo.rs_grab_z = selected_pt.z;
  249. ////////////////////////////////////////////////////////////////////
  250. //debug
  251. if (m_cparam.image_show) {
  252. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_cand_demo(new pcl::PointCloud<pcl::PointXYZRGB>);
  253. pcl::copyPointCloud(*cloud_dowm_sampled, *cloud_cand_demo);
  254. for (auto& pt : *cloud_cand_demo) {
  255. pt.r = 255;
  256. pt.g = 255;
  257. pt.b = 255;
  258. }
  259. int cnt = 0;
  260. for (auto& idx : mass_idx) {
  261. int p_idx = first_seedling_cloud_idx.at(idx);
  262. /*if (p_idx == optimal_seeds_idx[selected_pt_idx]) {
  263. cloud_cand_demo->points[p_idx].r = 0;
  264. cloud_cand_demo->points[p_idx].g = 255;
  265. cloud_cand_demo->points[p_idx].b = 0;
  266. }
  267. else {*/
  268. cloud_cand_demo->points.at(p_idx).r = 255;
  269. cloud_cand_demo->points.at(p_idx).g = 0;
  270. cloud_cand_demo->points.at(p_idx).b = 0;
  271. /*} */
  272. if (cnt > optimal_seeds_idx.size()) { break; }
  273. cnt++;
  274. }
  275. pcl::PointXYZRGB pt_grab = {0,255,0};
  276. pt_grab.x = selected_pt.x;
  277. pt_grab.y = selected_pt.y;
  278. pt_grab.z = selected_pt.z;
  279. pcl::PointXYZRGB pt_grab_ = { 0,255,120 };
  280. pt_grab_.x = selected_pt.x;
  281. pt_grab_.y = selected_pt.y+0.2;
  282. pt_grab_.z = selected_pt.z;
  283. cloud_cand_demo->push_back(pt_grab);
  284. //viewer_cloud(cloud_cand_demo, std::string("cloud_cand_demo"));
  285. viewer_cloud_debug(cloud_cand_demo, selected_pt, xz_center, std::string("cloud_cand_demo"));
  286. }
  287. return 0;
  288. }
  289. int CRootStockGrabPoint::read_ply_file(const char* fn)
  290. {
  291. m_raw_cloud.reset( new pcl::PointCloud<pcl::PointXYZ>);
  292. if (pcl::io::loadPLYFile<pcl::PointXYZ>(fn, *m_raw_cloud) == -1) {
  293. if (m_pLogger) {
  294. m_pLogger->ERRORINFO("could not load file: "+std::string(fn));
  295. }
  296. return (-1);
  297. }
  298. if (m_pLogger) {
  299. stringstream buff;
  300. buff << "load raw point cloud " << m_raw_cloud->width * m_raw_cloud->height << " data points";
  301. m_pLogger->INFO(buff.str());
  302. }
  303. return m_raw_cloud->width * m_raw_cloud->height;
  304. }
  305. double CRootStockGrabPoint::compute_nearest_neighbor_distance(pcl::PointCloud<pcl::PointXYZ>::Ptr pcd)
  306. {
  307. pcl::KdTreeFLANN<pcl::PointXYZ> tree;
  308. tree.setInputCloud(pcd);
  309. int k = 2;
  310. double res = 0.0;
  311. int n_points = 0;
  312. for (size_t i = 0; i < pcd->size(); ++i) {
  313. std::vector<int> idx(k);
  314. std::vector<float> sqr_distances(k);
  315. if (tree.nearestKSearch(i, k, idx, sqr_distances) == k) {
  316. for (int id = 1; id < k; ++id) {
  317. res += sqrt(sqr_distances.at(id));
  318. ++n_points;
  319. }
  320. }
  321. }
  322. if (n_points > 0) {
  323. res /= (double)n_points;
  324. }
  325. return res;
  326. }
  327. //void CRootStockGrabPoint::find_tray_top_edge(
  328. //pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  329. //float & tray_top_edge_y
  330. //)
  331. //{
  332. // tray_top_edge_y = -1000.0;
  333. // //以毫米为单位构建vector
  334. // pcl::PointXYZ min_point_aabb;
  335. // pcl::PointXYZ max_point_aabb;
  336. // pcl::MomentOfInertiaEstimation<pcl::PointXYZ> feature_extractor;
  337. // feature_extractor.setInputCloud(in_cloud);
  338. // feature_extractor.compute();
  339. // feature_extractor.getAABB(min_point_aabb, max_point_aabb);
  340. // float miny = min_point_aabb.y;
  341. // float maxy = max_point_aabb.y;
  342. // if(maxy - miny <5.0){
  343. // tray_top_edge_y = maxy;
  344. // return;
  345. // }
  346. // std::vector<int> y_cnt_hist(int(maxy - miny), 0);
  347. // for(auto& pt : in_cloud->points){
  348. // int idx = (int)(pt.y - miny);
  349. // if(idx<0){continue;}
  350. // if (idx >= y_cnt_hist.size()) { continue; }
  351. // y_cnt_hist.at(idx) += 1;
  352. // }
  353. // //从上半部分找到最大值,作为平面上沿
  354. // int idx_part = (int)(y_cnt_hist.size() / 2);
  355. // int idx_edge = std::max_element(y_cnt_hist.begin(), y_cnt_hist.begin() + idx_part) - y_cnt_hist.begin();
  356. // tray_top_edge_y = miny + (float)(idx_edge + 2.0);
  357. //}
  358. //void CRootStockGrabPoint::find_seedling_position_line_based(
  359. // pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  360. // std::vector<int> &first_seedling_cloud_idx,
  361. // pcl::PointXYZ&xz_center
  362. //)
  363. //{
  364. // //找到穴盘上沿z,最优抓取的z,再在最优抓取的z基础上加上3作为有效范围
  365. // float tray_y = -1000.0;
  366. // float top_y = 0.0;
  367. // find_tray_top_edge(in_cloud, tray_y);
  368. // if (tray_y < -500.0) {
  369. // if (m_dtype == 0) {
  370. // //scion
  371. // tray_y = m_cparam.sc_grab_y_opt-2.0;
  372. // }
  373. // else {
  374. // tray_y = m_cparam.rs_grab_y_opt-2.0;
  375. // }
  376. // }
  377. // //up limit
  378. // if (m_dtype == 0) {
  379. // top_y = m_cparam.sc_grab_zmax;
  380. // if (top_y > m_cparam.sc_grab_y_opt + 3.0) {
  381. // top_y = m_cparam.sc_grab_y_opt + 3.0;
  382. // }
  383. // }
  384. // else {
  385. // top_y = m_cparam.rs_grab_zmax;
  386. // if (top_y > m_cparam.rs_grab_y_opt + 3.0) {
  387. // top_y = m_cparam.rs_grab_y_opt + 3.0;
  388. // }
  389. // }
  390. // //sub cloud
  391. // pcl::PointCloud<pcl::PointXYZ>::Ptr sub_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  392. // pcl::CropBox<pcl::PointXYZ> box_filter;
  393. // if (m_dtype != 0) {//rootstock
  394. // box_filter.setMin(Eigen::Vector4f(m_cparam.rs_grab_xmin, tray_y, m_cparam.rs_grab_zmin, 1));
  395. // box_filter.setMax(Eigen::Vector4f(m_cparam.rs_grab_xmax, top_y, m_cparam.rs_grab_zmax, 1));
  396. // }
  397. // else {//scion
  398. // box_filter.setMin(Eigen::Vector4f(m_cparam.sc_grab_xmin, tray_y, m_cparam.sc_grab_zmin, 1));
  399. // box_filter.setMax(Eigen::Vector4f(m_cparam.sc_grab_xmax, top_y, m_cparam.sc_grab_zmax, 1));
  400. // }
  401. // box_filter.setNegative(false);
  402. // box_filter.setInputCloud(in_cloud);
  403. // box_filter.filter(*sub_cloud);
  404. // if (m_cparam.image_show) {
  405. // viewer_cloud(sub_cloud, std::string("sub inbox"));
  406. // }
  407. // //在sub_cloud中进行直线检测
  408. // segement_line(sub_cloud);
  409. //}
  410. //void CRootStockGrabPoint::segement_line(
  411. // pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud
  412. //)
  413. //{
  414. // pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
  415. // pcl::PointIndices::Ptr inliers(new pcl::PointIndices);
  416. // pcl::SACSegmentation<pcl::PointXYZ> seg;
  417. // seg.setOptimizeCoefficients(true);
  418. // seg.setModelType(pcl::SACMODEL_LINE);
  419. // seg.setMethodType(pcl::SAC_RANSAC);
  420. // seg.setDistanceThreshold(0.5);
  421. // seg.setInputCloud(in_cloud);
  422. // seg.segment(*inliers, *coefficients);
  423. // if (m_cparam.image_show) {
  424. // pcl::PointCloud<pcl::PointXYZ>::Ptr line_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  425. // pcl::copyPointCloud(*in_cloud, *inliers, *line_cloud);
  426. // viewer_cloud(line_cloud, std::string("cloud_line"));
  427. // }
  428. //}
  429. ////////////////////////////////////////////////////////////
  430. void CRootStockGrabPoint::find_seedling_position(
  431. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  432. std::vector<int> &first_seedling_cloud_idx,
  433. pcl::PointXYZ&xz_center
  434. )
  435. {
  436. float hole_step = 40.0; //穴盘中穴间距
  437. float hole_step_radius = hole_step / 2.0;
  438. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2d(new pcl::PointCloud < pcl::PointXYZ>);
  439. pcl::copyPointCloud(*in_cloud, *cloud2d);
  440. for (auto&pt : *cloud2d) {
  441. pt.y = 0.0;
  442. }
  443. /*if(m_cparam.image_show){
  444. viewer_cloud(cloud2d, std::string("cloud2d"));
  445. } */
  446. double radius = m_cparam.rs_grab_stem_diameter;
  447. if (m_dtype == 0) {
  448. radius = m_cparam.sc_grab_stem_diameter;
  449. }
  450. std::vector<int> counter;
  451. pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
  452. kdtree.setInputCloud(cloud2d);
  453. std::vector<int>idx;
  454. std::vector<float>dist_sqr;
  455. for (size_t i = 0; i < cloud2d->points.size(); ++i) {
  456. int k = kdtree.radiusSearch(cloud2d->points.at(i), radius, idx, dist_sqr);
  457. counter.push_back(k);
  458. }
  459. int th = (int)(otsu(counter));
  460. std::vector<int> index;
  461. for (size_t i = 0; i < counter.size(); ++i) {
  462. if (counter.at(i) >= th) {
  463. index.push_back(i);
  464. }
  465. }
  466. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2d_pos(new pcl::PointCloud < pcl::PointXYZ>);
  467. pcl::copyPointCloud(*cloud2d, index, *cloud2d_pos);
  468. if (m_pLogger) {
  469. stringstream buff;
  470. buff << "get 2d seedling seed point cloud " << index.size()<< " data points with thrreshold "<<th;
  471. m_pLogger->INFO(buff.str());
  472. }
  473. if (m_cparam.image_show) {
  474. viewer_cloud(cloud2d_pos, std::string("cloud2d_pos"));
  475. }
  476. //clustering
  477. double d1 = m_cparam.rs_grab_stem_diameter;
  478. double d2 = m_cparam.rs_grab_stem_diameter * 3.0;
  479. if (m_dtype == 0) {
  480. d1 = m_cparam.sc_grab_stem_diameter;
  481. d2 = m_cparam.sc_grab_stem_diameter * 3.0;
  482. }
  483. std::vector<pcl::PointXYZ>cluster_center;
  484. std::vector<std::vector<int>> cluster_member;
  485. euclidean_clustering_ttsas(cloud2d_pos, d1, d2, cluster_center, cluster_member);
  486. if (m_pLogger) {
  487. stringstream buff;
  488. buff << "euclidean_clustering_ttsas: " << cluster_center.size() << " t1=" << d1
  489. << " t2=" << d2;
  490. m_pLogger->INFO(buff.str());
  491. }
  492. if (m_cparam.image_show) {
  493. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_cluster(new pcl::PointCloud<pcl::PointXYZRGB>);
  494. pcl::copyPointCloud(*cloud2d_pos, *cloud_cluster);
  495. for (auto& pt : *cloud_cluster) {
  496. pt.r = 255;
  497. pt.g = 255;
  498. pt.b = 255;
  499. }
  500. viewer_cloud_cluster(cloud_cluster, cluster_center, std::string("cloud2d_cluster_pos"));
  501. }
  502. //对每个类别进行检测,剔除不是茎的类别
  503. std::vector<pcl::PointXYZ> clt_root;
  504. std::vector<pcl::PointXYZ> clt_box;
  505. std::vector<std::vector<int> > clt_line_idx;
  506. for (size_t i = 0; i < cluster_center.size(); ++i) {
  507. pcl::PointIndices cluster_idxs;
  508. for (auto idx_clt : cluster_member.at(i)) {
  509. int idx_raw = index.at(idx_clt);
  510. cluster_idxs.indices.push_back(idx_raw);
  511. }
  512. pcl::PointCloud<pcl::PointXYZ>::Ptr clt_cloud(new pcl::PointCloud < pcl::PointXYZ>);
  513. pcl::copyPointCloud(*in_cloud, cluster_idxs, *clt_cloud);
  514. //计算每一个茎的外接矩形
  515. pcl::PointXYZ min_point_aabb;
  516. pcl::PointXYZ max_point_aabb;
  517. pcl::MomentOfInertiaEstimation<pcl::PointXYZ> feature_extractor;
  518. feature_extractor.setInputCloud(clt_cloud);
  519. feature_extractor.compute();
  520. feature_extractor.getAABB(min_point_aabb, max_point_aabb);
  521. //扩展矩形范围
  522. pcl::PointXYZ min_point_aabb_ex;
  523. pcl::PointXYZ max_point_aabb_ex;
  524. min_point_aabb_ex.x = 0.5*(min_point_aabb.x + max_point_aabb.x) - hole_step_radius;
  525. min_point_aabb_ex.y = m_cparam.sc_grab_ymin;
  526. if (m_dtype != 0) { min_point_aabb_ex.y = m_cparam.rs_grab_ymin; }
  527. min_point_aabb_ex.z = 0.5*(min_point_aabb.z + max_point_aabb.z) - hole_step_radius;
  528. max_point_aabb_ex.x = 0.5*(min_point_aabb.x + max_point_aabb.x) + hole_step_radius;
  529. max_point_aabb_ex.y = m_cparam.sc_grab_ymax;
  530. if (m_dtype != 0) { max_point_aabb_ex.y = m_cparam.rs_grab_ymax; }
  531. max_point_aabb_ex.z = 0.5*(min_point_aabb.z + max_point_aabb.z) + hole_step_radius;
  532. /////////////////////////////////
  533. //扩展矩形内直线检测
  534. std::vector<int>line_idx;
  535. find_line_in_cube(in_cloud, min_point_aabb_ex, max_point_aabb_ex, line_idx);
  536. clt_line_idx.push_back(line_idx);
  537. //找到line_idx中y最小的那个点的idx
  538. int line_root_idx = -1;
  539. float line_root_y_min = 10000.0;
  540. for (size_t lidx = 0; lidx < line_idx.size();++lidx) {
  541. int raw_idx = line_idx.at(lidx);
  542. if (in_cloud->at(raw_idx).y < line_root_y_min) {
  543. line_root_y_min = in_cloud->at(raw_idx).y;
  544. line_root_idx = raw_idx;
  545. }
  546. }
  547. //找到底部中心点,然后找到根部坐标
  548. pcl::PointXYZ pt_root;
  549. pt_root = in_cloud->at(line_root_idx);
  550. clt_root.push_back(pt_root);
  551. clt_box.push_back(min_point_aabb_ex);
  552. clt_box.push_back(max_point_aabb_ex);
  553. //viewer_cloud(clt_cloud, std::string("cluster"));
  554. }
  555. if (m_cparam.image_show) {
  556. viewer_cloud_cluster_box(in_cloud, clt_root, clt_box, clt_line_idx, std::string("cloud2d_cluster_box"));
  557. }
  558. //sort cluster center, get the frontest leftest one
  559. std::vector<float> cluster_index;
  560. for (auto&pt : clt_root) {
  561. float idx = pt.x - pt.z;
  562. cluster_index.push_back(idx);
  563. }
  564. int first_idx = std::min_element(cluster_index.begin(), cluster_index.end()) - cluster_index.begin();
  565. if (m_dtype == 0) {
  566. first_idx = std::max_element(cluster_index.begin(), cluster_index.end()) - cluster_index.begin();
  567. }
  568. first_seedling_cloud_idx.clear();
  569. for (auto&v : clt_line_idx.at(first_idx)) {
  570. first_seedling_cloud_idx.push_back(v);
  571. }
  572. xz_center.x = clt_root.at(first_idx).x;
  573. xz_center.y = clt_root.at(first_idx).y;
  574. xz_center.z = clt_root.at(first_idx).z;
  575. if (m_pLogger) {
  576. stringstream buff;
  577. buff << "euclidean_clustering_ttsas, find cluster center(" << xz_center.x
  578. <<", "<< xz_center.y<<", "<< xz_center.z<<")";
  579. m_pLogger->INFO(buff.str());
  580. }
  581. }
  582. void CRootStockGrabPoint::find_line_in_cube(
  583. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, //输入,整体点云
  584. pcl::PointXYZ& min_pt_ex, //输入,
  585. pcl::PointXYZ& max_pt_ex, //输入,
  586. std::vector<int>& out_idx //输出,直线上点的index, 基于输入整体点云
  587. )
  588. {
  589. out_idx.clear();
  590. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  591. pcl::CropBox<pcl::PointXYZ> box_filter;
  592. std::vector<int>inbox_idx;
  593. box_filter.setMin(Eigen::Vector4f(min_pt_ex.x, min_pt_ex.y, min_pt_ex.z, 1));
  594. box_filter.setMax(Eigen::Vector4f(max_pt_ex.x, max_pt_ex.y, max_pt_ex.z, 1));
  595. box_filter.setNegative(false);
  596. box_filter.setInputCloud(in_cloud);
  597. box_filter.filter(inbox_idx);
  598. pcl::copyPointCloud(*in_cloud, inbox_idx, *cloud_inbox);
  599. //找到inbox点云中的直线
  600. float stem_radius = m_cparam.rs_grab_stem_diameter / 2.0;
  601. if (m_dtype == 0) {
  602. stem_radius = m_cparam.sc_grab_stem_diameter / 2.0;
  603. }
  604. pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
  605. pcl::PointIndices::Ptr inliers(new pcl::PointIndices);
  606. pcl::SACSegmentation<pcl::PointXYZ> seg;
  607. seg.setOptimizeCoefficients(true);
  608. seg.setModelType(pcl::SACMODEL_LINE);
  609. seg.setDistanceThreshold(stem_radius);
  610. seg.setInputCloud(cloud_inbox);
  611. seg.segment(*inliers, *coefficients);
  612. int idx_raw = 0;
  613. for (auto& idx : inliers->indices) {
  614. idx_raw = inbox_idx.at(idx);
  615. out_idx.push_back(idx_raw);
  616. }
  617. if (m_cparam.image_show) {
  618. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_line(new pcl::PointCloud<pcl::PointXYZ>);
  619. pcl::copyPointCloud(*cloud_inbox, *inliers, *cloud_line);
  620. pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("line in cluster"));
  621. viewer->addPointCloud<pcl::PointXYZ>(cloud_inbox, "cluster");
  622. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 1, 1, "cluster");
  623. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "cluster");
  624. viewer->addPointCloud(cloud_line, "fit_line");
  625. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 0, 1, 0, "fit_line");
  626. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "fit_line");
  627. while (!viewer->wasStopped()) {
  628. viewer->spinOnce(100);
  629. }
  630. }
  631. }
  632. void CRootStockGrabPoint::crop_nn_analysis(
  633. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  634. pcl::PointCloud<pcl::PointXYZ>::Ptr seed_cloud,
  635. double dist_mean,
  636. std::vector<double>&mass_indices,
  637. std::vector<int>& candidate_idx
  638. )
  639. {
  640. candidate_idx.clear();
  641. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  642. pcl::CropBox<pcl::PointXYZ> box_filter;
  643. box_filter.setNegative(false);
  644. box_filter.setInputCloud(in_cloud);
  645. double radius = 5;
  646. double rx = 0.8;
  647. double ry = 1.0;
  648. double rz = 0.8;
  649. double cx, cy, cz;
  650. double dz;
  651. for (size_t i = 0; i < seed_cloud->points.size(); ++i) {
  652. cx = seed_cloud->points.at(i).x;
  653. cy = seed_cloud->points.at(i).y;
  654. cz = seed_cloud->points.at(i).z;
  655. box_filter.setMin(Eigen::Vector4f(cx - rx*radius, cy - ry*radius, cz - rz*radius, 1));
  656. box_filter.setMax(Eigen::Vector4f(cx + rx*radius, cy + ry*radius, cz + rz*radius, 1));
  657. box_filter.filter(*cloud_inbox);
  658. //dz
  659. Eigen::Vector4f min_point;
  660. Eigen::Vector4f max_point;
  661. pcl::getMinMax3D(*cloud_inbox, min_point, max_point);
  662. dz = max_point(2) - min_point(2);
  663. //project to xy-plane
  664. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox_xy(new pcl::PointCloud<pcl::PointXYZ>);
  665. pcl::copyPointCloud(*cloud_inbox, *cloud_inbox_xy);
  666. for (auto&pt : *cloud_inbox_xy) { pt.z = 0.0; }
  667. //pca
  668. double dx_obb;
  669. double dy_obb;
  670. double angle_obb;
  671. cal_obb_2d(cloud_inbox_xy, 0, dx_obb, dy_obb, angle_obb);
  672. try {
  673. double dx_grid = dx_obb / dist_mean;
  674. double dy_grid = dy_obb / dist_mean;
  675. double dz_grid = dz / dist_mean;
  676. double fill_ratio = cloud_inbox->points.size() / dx_grid / dy_grid / dz_grid;
  677. double y_ratio = dy_obb / dx_obb/2;
  678. y_ratio = pow(y_ratio, 2);
  679. double a_ratio = cos((angle_obb - 90)*PI / 180.0);
  680. a_ratio = pow(a_ratio, 3);
  681. double mass_index = fill_ratio*y_ratio*a_ratio;
  682. mass_indices.push_back(mass_index);
  683. if (m_pLogger) {
  684. stringstream buff;
  685. buff << i << "/" << seed_cloud->points.size() << " dx=" << dx_obb << ", dy=" << dy_obb << ", fill_ratio=" << fill_ratio
  686. << ", y_ratio=" << y_ratio << ", a_ratio=" << a_ratio << ", mass_index=" << mass_index;
  687. m_pLogger->INFO(buff.str());
  688. }
  689. }
  690. catch (...) {
  691. mass_indices.push_back(0);
  692. }
  693. }
  694. // sort by mass_indices
  695. std::vector<size_t> sort_idx = sort_indexes_e(mass_indices, false);
  696. for (auto&v : sort_idx) { candidate_idx.push_back((int)v); }
  697. }
  698. void CRootStockGrabPoint::euclidean_clustering_ttsas(
  699. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  700. double d1, double d2,
  701. std::vector<pcl::PointXYZ>&cluster_center,
  702. std::vector<std::vector<int>> &clustr_member
  703. )
  704. {
  705. if (m_pLogger) {
  706. stringstream buff;
  707. buff << "euclidean_clustering_ttsas() begin...";
  708. m_pLogger->INFO(buff.str());
  709. }
  710. std::vector<int> cluster_weight;
  711. std::vector<int> data_stat;
  712. std::vector<pcl::PointXYZ>cluster_center_raw;
  713. std::vector<std::vector<int>> clustr_member_raw;
  714. for (size_t i = 0; i < in_cloud->points.size(); ++i) { data_stat.push_back(0); }
  715. size_t data_len = in_cloud->points.size();
  716. int exists_change = 0;
  717. int prev_change = 0;
  718. int cur_change = 0;
  719. int m = 0;
  720. while (std::find(data_stat.begin(), data_stat.end(), 0) != data_stat.end()) {
  721. bool new_while_first = true;
  722. for (size_t i = 0; i < data_len; ++i) {
  723. if (data_stat.at(i) == 0 && new_while_first && exists_change == 0) {
  724. new_while_first = false;
  725. std::vector<int> idx;
  726. idx.push_back(i);
  727. clustr_member_raw.push_back(idx);
  728. pcl::PointXYZ center;
  729. center.x = in_cloud->points.at(i).x;
  730. center.y = in_cloud->points.at(i).y;
  731. center.z = in_cloud->points.at(i).z;
  732. cluster_center_raw.push_back(center);
  733. data_stat.at(i) = 1;
  734. cur_change += 1;
  735. cluster_weight.push_back(1);
  736. m += 1;
  737. }
  738. else if (data_stat[i] == 0) {
  739. std::vector<float> distances;
  740. for (size_t j = 0; j < clustr_member_raw.size(); ++j) {
  741. std::vector<float> distances_sub;
  742. for (size_t jj = 0; jj < clustr_member_raw.at(j).size(); ++jj) {
  743. size_t ele_idx = clustr_member_raw.at(j).at(jj);
  744. double d = sqrt(
  745. (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) +
  746. (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) +
  747. (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));
  748. distances_sub.push_back(d);
  749. }
  750. double min_dist = *std::min_element(distances_sub.begin(), distances_sub.end());
  751. distances.push_back(min_dist);
  752. }
  753. int min_idx = std::min_element(distances.begin(), distances.end()) - distances.begin();
  754. if (distances.at(min_idx) < d1) {
  755. data_stat.at(i) = 1;
  756. double w = cluster_weight.at(min_idx);
  757. cluster_weight.at(min_idx) += 1;
  758. clustr_member_raw.at(min_idx).push_back(i);
  759. cluster_center_raw.at(min_idx).x = (cluster_center_raw.at(min_idx).x * w + in_cloud->points.at(i).x) / (w + 1);
  760. cluster_center_raw.at(min_idx).y = (cluster_center_raw.at(min_idx).y * w + in_cloud->points.at(i).y) / (w + 1);
  761. cluster_center_raw.at(min_idx).z = (cluster_center_raw.at(min_idx).z * w + in_cloud->points.at(i).z) / (w + 1);
  762. cur_change += 1;
  763. }
  764. else if (distances.at(min_idx) > d2) {
  765. std::vector<int> idx;
  766. idx.push_back(i);
  767. clustr_member_raw.push_back(idx);
  768. pcl::PointXYZ center;
  769. center.x = in_cloud->points.at(i).x;
  770. center.y = in_cloud->points.at(i).y;
  771. center.z = in_cloud->points.at(i).z;
  772. cluster_center_raw.push_back(center);
  773. data_stat.at(i) = 1;
  774. cur_change += 1;
  775. cluster_weight.push_back(1);
  776. m += 1;
  777. }
  778. }
  779. else if (data_stat.at(i)== 1) {
  780. cur_change += 1;
  781. }
  782. }
  783. exists_change = fabs(cur_change - prev_change);
  784. prev_change = cur_change;
  785. cur_change = 0;
  786. }
  787. // copy result
  788. for (size_t i = 0; i < clustr_member_raw.size(); ++i) {
  789. if (clustr_member_raw.at(i).size() < 20) { continue; }
  790. cluster_center.push_back(cluster_center_raw.at(i));
  791. clustr_member.push_back(clustr_member_raw.at(i));
  792. }
  793. if (m_pLogger) {
  794. stringstream buff;
  795. buff << "euclidean_clustering_ttsas() end";
  796. m_pLogger->INFO(buff.str());
  797. }
  798. }
  799. void CRootStockGrabPoint::cal_obb_2d(
  800. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  801. int axis, //0--xy, 1--zy
  802. double &dx_obb,
  803. double &dy_obb,
  804. double &angle_obb
  805. )
  806. {
  807. // asign value
  808. Eigen::MatrixXd pts(in_cloud->points.size(), 2);
  809. for (size_t i = 0; i < in_cloud->points.size(); ++i) {
  810. if (axis == 0) {
  811. pts(i, 0) = in_cloud->points.at(i).x;
  812. }
  813. else {
  814. pts(i, 0) = in_cloud->points.at(i).z;
  815. }
  816. pts(i, 1) = in_cloud->points.at(i).y;
  817. }
  818. // centerlize
  819. Eigen::MatrixXd mu = pts.colwise().mean();
  820. Eigen::RowVectorXd mu_row = mu;
  821. pts.rowwise() -= mu_row;
  822. //calculate covariance
  823. Eigen::MatrixXd C = pts.adjoint()*pts;
  824. C = C.array() / (pts.cols() - 1);
  825. //compute eig
  826. Eigen::SelfAdjointEigenSolver<Eigen::MatrixXd> eig(C);
  827. Eigen::MatrixXd d = eig.eigenvalues();
  828. Eigen::MatrixXd v = eig.eigenvectors();
  829. //projection
  830. Eigen::MatrixXd p = pts * v;
  831. Eigen::VectorXd minv = p.colwise().minCoeff();
  832. Eigen::VectorXd maxv = p.colwise().maxCoeff();
  833. Eigen::VectorXd range = maxv - minv;
  834. dy_obb = range(1);
  835. dx_obb = range(0);
  836. angle_obb = std::atan2(v(1, 1), v(0, 1));
  837. if (angle_obb < 0) { angle_obb = PI + angle_obb; }
  838. angle_obb = angle_obb * 180 / PI;
  839. }
  840. //void CRootStockGrabPoint::get_optimal_seed(
  841. // pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  842. // pcl::PointXYZ&pt,
  843. // int &pt_idx)
  844. //{
  845. // double d1 = m_cparam.rs_grab_stem_diameter;
  846. // double d2 = m_cparam.rs_grab_stem_diameter * 4.0;
  847. // if (m_dtype != 0) {
  848. // d1 = m_cparam.sc_grab_stem_diameter;
  849. // d2 = m_cparam.sc_grab_stem_diameter * 4.0;
  850. // }
  851. // std::vector<pcl::PointXYZ>cluster_center;
  852. // std::vector<std::vector<int>> cluster_member;
  853. // euclidean_clustering_ttsas(in_cloud, d1, d2, cluster_center, cluster_member);
  854. // float min_y_dist = 1.0e6;
  855. // int opt_idx = -1;
  856. // int member_size = 5;
  857. // float y_opt = m_cparam.rs_grab_y_opt;
  858. // if (m_dtype != 0) {
  859. // y_opt = m_cparam.sc_grab_y_opt;
  860. // }
  861. // for (int i = 0; i < cluster_member.size(); ++i) {
  862. // if (cluster_member.at(i).size() < member_size) {
  863. // continue;
  864. // }
  865. // if (fabs(cluster_center.at(i).y -y_opt) < min_y_dist) {
  866. // min_y_dist = fabs(cluster_center.at(i).y - y_opt);
  867. // opt_idx = i;
  868. // }
  869. // }
  870. // if (opt_idx < 0) {
  871. // if (m_pLogger) {
  872. // stringstream buff;
  873. // buff << "get_optimal_seed failed, get invalid optimal cluster id";
  874. // m_pLogger->ERRORINFO(buff.str());
  875. // }
  876. // return;
  877. // }
  878. // //find nearest pt
  879. // float nearest_dist = 1.0e6;
  880. // int nearest_idx = -1;
  881. // for (int i = 0; i < cluster_member.at(opt_idx).size(); ++i) {
  882. // int idx = cluster_member.at(opt_idx).at(i);
  883. // float dist = fabs(in_cloud->points.at(idx).x - cluster_center.at(opt_idx).x) +
  884. // fabs(in_cloud->points.at(idx).y - cluster_center.at(opt_idx).y) +
  885. // fabs(in_cloud->points.at(idx).z - cluster_center.at(opt_idx).z);
  886. // if (dist < nearest_dist) {
  887. // nearest_dist = dist;
  888. // nearest_idx = idx;
  889. // }
  890. // }
  891. // pt.x = in_cloud->points.at(nearest_idx).x;
  892. // pt.y = in_cloud->points.at(nearest_idx).y;
  893. // pt.z = in_cloud->points.at(nearest_idx).z;
  894. // pt_idx = nearest_idx;
  895. //}
  896. void CRootStockGrabPoint::get_optimal_seed(
  897. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  898. pcl::PointXYZ&pt,
  899. int &pt_idx)
  900. {
  901. /*double d1 = m_cparam.rs_grab_stem_diameter;
  902. double d2 = m_cparam.rs_grab_stem_diameter * 4.0;
  903. if (m_dtype != 0) {
  904. d1 = m_cparam.sc_grab_stem_diameter;
  905. d2 = m_cparam.sc_grab_stem_diameter * 4.0;
  906. }
  907. std::vector<pcl::PointXYZ>cluster_center;
  908. std::vector<std::vector<int>> cluster_member;
  909. euclidean_clustering_ttsas(in_cloud, d1, d2, cluster_center, cluster_member);*/
  910. float min_y_dist = 1.0e6;
  911. int opt_idx = -1;
  912. int member_size = 5;
  913. float y_opt = m_cparam.rs_grab_y_opt;
  914. if (m_dtype == 0) {
  915. y_opt = m_cparam.sc_grab_y_opt;
  916. }
  917. for (int i = 0; i < in_cloud->points.size(); ++i) {
  918. /*if (cluster_member.at(i).size() < member_size) {
  919. continue;
  920. }*/
  921. if (fabs(in_cloud->points.at(i).y - y_opt) < min_y_dist) {
  922. min_y_dist = fabs(in_cloud->points.at(i).y - y_opt);
  923. opt_idx = i;
  924. }
  925. }
  926. if (opt_idx < 0) {
  927. if (m_pLogger) {
  928. stringstream buff;
  929. buff << "get_optimal_seed failed, get invalid optimal cluster id";
  930. m_pLogger->ERRORINFO(buff.str());
  931. }
  932. return;
  933. }
  934. //find nearest pt
  935. /*float nearest_dist = 1.0e6;
  936. int nearest_idx = -1;
  937. for (int i = 0; i < cluster_member.at(opt_idx).size(); ++i) {
  938. int idx = cluster_member.at(opt_idx).at(i);
  939. float dist = fabs(in_cloud->points.at(idx).x - cluster_center.at(opt_idx).x) +
  940. fabs(in_cloud->points.at(idx).y - cluster_center.at(opt_idx).y) +
  941. fabs(in_cloud->points.at(idx).z - cluster_center.at(opt_idx).z);
  942. if (dist < nearest_dist) {
  943. nearest_dist = dist;
  944. nearest_idx = idx;
  945. }
  946. }*/
  947. pt.x = in_cloud->points.at(opt_idx).x;
  948. pt.y = in_cloud->points.at(opt_idx).y;
  949. pt.z = in_cloud->points.at(opt_idx).z;
  950. pt_idx = opt_idx;
  951. }
  952. void CRootStockGrabPoint::viewer_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, std::string&winname)
  953. {
  954. pcl::visualization::CloudViewer viewer(winname);
  955. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  956. viewer.showCloud(cloud);
  957. while (!viewer.wasStopped()) {
  958. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  959. }
  960. }
  961. void CRootStockGrabPoint::viewer_cloud(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud, std::string&winname)
  962. {
  963. pcl::visualization::CloudViewer viewer(winname);
  964. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  965. viewer.showCloud(cloud);
  966. while (!viewer.wasStopped()) {
  967. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  968. }
  969. }
  970. void CRootStockGrabPoint::viewer_cloud_debug(
  971. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
  972. pcl::PointXYZ &p,
  973. pcl::PointXYZ &root_pt,
  974. std::string&winname)
  975. {
  976. pcl::visualization::PCLVisualizer viewer(winname);
  977. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  978. viewer.addPointCloud(cloud);
  979. viewer.addCoordinateSystem();
  980. pcl::PointXYZ p0, x1, y1,p00,x0,y0, root_px0, root_px1, root_py0,root_py1;
  981. p0.x = p.x;
  982. p0.y = p.y;
  983. p0.z = p.z;
  984. x1.x = p.x + 100.0;
  985. x1.y = p.y;
  986. x1.z = p.z;
  987. y1.x = p.x;
  988. y1.y = p.y + 20.0;
  989. y1.z = p.z;
  990. p00.x = 0.0;
  991. p00.y = 0.0;
  992. p00.z = p.z;
  993. x0.x = 600.0;
  994. x0.y = 0;
  995. x0.z = p.z;
  996. y0.x = 0.0;
  997. y0.y = 300.0;
  998. y0.z = p.z;
  999. root_px0.x = root_pt.x - 5.0;
  1000. root_px0.y = root_pt.y;
  1001. root_px0.z = root_pt.z;
  1002. root_px1.x = root_pt.x + 5.0;
  1003. root_px1.y = root_pt.y;
  1004. root_px1.z = root_pt.z;
  1005. root_py0.x = root_pt.x;
  1006. root_py0.y = root_pt.y - 5.0;
  1007. root_py0.z = root_pt.z;
  1008. root_py1.x = root_pt.x;
  1009. root_py1.y = root_pt.y + 5.0;
  1010. root_py1.z = root_pt.z;
  1011. viewer.addLine(p0, x1, 255, 0, 0, "x");
  1012. viewer.addLine(p0, y1, 0, 255, 0, "y");
  1013. viewer.addLine(p00, x0, 255, 0, 0, "x0");
  1014. viewer.addLine(p00, y0, 0, 255, 0, "y0");
  1015. viewer.addLine(root_px0, root_px1, 255, 0, 0, "rootx");
  1016. viewer.addLine(root_py0, root_py1, 0, 255, 0, "rooty");
  1017. while (!viewer.wasStopped()) {
  1018. viewer.spinOnce(100);
  1019. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  1020. }
  1021. }
  1022. void CRootStockGrabPoint::viewer_cloud_cluster(
  1023. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
  1024. std::vector<pcl::PointXYZ>cluster_center,
  1025. std::string&winname)
  1026. {
  1027. pcl::visualization::PCLVisualizer viewer(winname);
  1028. viewer.addPointCloud(cloud);
  1029. viewer.addCoordinateSystem();
  1030. int cnt = 0;
  1031. char buf[8];
  1032. for (auto& p : cluster_center) {
  1033. pcl::PointXYZ px0, px1, py1, py0;
  1034. px0.x = p.x-5.0;
  1035. px0.y = p.y;
  1036. px0.z = p.z;
  1037. px1.x = p.x + 5.0;
  1038. px1.y = p.y;
  1039. px1.z = p.z;
  1040. py0.x = p.x;
  1041. py0.y = p.y - 5.0;
  1042. py0.z = p.z;
  1043. py1.x = p.x;
  1044. py1.y = p.y + 5.0;
  1045. py1.z = p.z;
  1046. viewer.addLine(px0, px1, 255, 0, 0, "x" + string(_itoa(cnt, buf,10)));
  1047. viewer.addLine(py0, py1, 0, 255, 0, "y" + string(_itoa(cnt, buf, 10)));
  1048. cnt += 1;
  1049. }
  1050. while (!viewer.wasStopped()) {
  1051. viewer.spinOnce(100);
  1052. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  1053. }
  1054. }
  1055. void CRootStockGrabPoint::viewer_cloud_cluster_box(
  1056. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
  1057. std::vector<pcl::PointXYZ>&cluster_center,
  1058. std::vector<pcl::PointXYZ>&cluster_box,
  1059. std::vector<std::vector<int> >& clt_line_idx,
  1060. std::string&winname)
  1061. {
  1062. pcl::visualization::PCLVisualizer viewer(winname);
  1063. viewer.addCoordinateSystem();
  1064. viewer.addPointCloud<pcl::PointXYZ>(cloud, "all_cloud");
  1065. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 1, 1, "all_cloud");
  1066. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "all_cloud");
  1067. int cnt = 0;
  1068. char buf[8];
  1069. for (size_t i = 0; i < cluster_center.size();++i) {
  1070. pcl::PointXYZ &p = cluster_center.at(i);
  1071. pcl::PointXYZ px0, px1, py1, py0;
  1072. px0.x = p.x - 5.0;
  1073. px0.y = p.y;
  1074. px0.z = p.z;
  1075. px1.x = p.x + 5.0;
  1076. px1.y = p.y;
  1077. px1.z = p.z;
  1078. py0.x = p.x;
  1079. py0.y = p.y - 5.0;
  1080. py0.z = p.z;
  1081. py1.x = p.x;
  1082. py1.y = p.y + 5.0;
  1083. py1.z = p.z;
  1084. viewer.addLine(px0, px1, 255, 0, 0, "x" + string(_itoa(cnt, buf, 10)));
  1085. viewer.addLine(py0, py1, 0, 255, 0, "y" + string(_itoa(cnt, buf, 10)));
  1086. //box
  1087. pcl::PointXYZ & min_pt = cluster_box.at(2 * i);
  1088. pcl::PointXYZ & max_pt = cluster_box.at(2 * i + 1);
  1089. viewer.addCube(min_pt.x, max_pt.x, min_pt.y, max_pt.y, min_pt.z, max_pt.z, 0.5,0.5,0.0,"AABB_"+string(_itoa(cnt, buf, 10)));
  1090. viewer.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_REPRESENTATION,
  1091. pcl::visualization::PCL_VISUALIZER_REPRESENTATION_WIREFRAME, "AABB_" + string(_itoa(cnt, buf, 10)));
  1092. pcl::PointCloud<pcl::PointXYZ>::Ptr line_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  1093. pcl::copyPointCloud(*cloud, clt_line_idx.at(i), *line_cloud);
  1094. viewer.addPointCloud(line_cloud, "fit_line" + string(_itoa(cnt, buf, 10)));
  1095. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 0, 1, 0, "fit_line" + string(_itoa(cnt, buf, 10)));
  1096. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "fit_line" + string(_itoa(cnt, buf, 10)));
  1097. cnt += 1;
  1098. }
  1099. while (!viewer.wasStopped()) {
  1100. viewer.spinOnce(100);
  1101. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  1102. }
  1103. }
  1104. };