grab_point_rs.cpp 82 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453145414551456145714581459146014611462146314641465146614671468146914701471147214731474147514761477147814791480148114821483148414851486148714881489149014911492149314941495149614971498149915001501150215031504150515061507150815091510151115121513151415151516151715181519152015211522152315241525152615271528152915301531153215331534153515361537153815391540154115421543154415451546154715481549155015511552155315541555155615571558155915601561156215631564156515661567156815691570157115721573157415751576157715781579158015811582158315841585158615871588158915901591159215931594159515961597159815991600160116021603160416051606160716081609161016111612161316141615161616171618161916201621162216231624162516261627162816291630163116321633163416351636163716381639164016411642164316441645164616471648164916501651165216531654165516561657165816591660166116621663166416651666166716681669167016711672167316741675167616771678167916801681168216831684168516861687168816891690169116921693169416951696169716981699170017011702170317041705170617071708170917101711171217131714171517161717171817191720172117221723172417251726172717281729173017311732173317341735173617371738173917401741174217431744174517461747174817491750175117521753175417551756175717581759176017611762176317641765176617671768176917701771177217731774177517761777177817791780178117821783178417851786178717881789179017911792179317941795179617971798179918001801180218031804180518061807180818091810181118121813181418151816181718181819182018211822182318241825182618271828182918301831183218331834183518361837183818391840184118421843184418451846184718481849185018511852185318541855185618571858185918601861186218631864186518661867186818691870187118721873187418751876187718781879188018811882188318841885188618871888188918901891189218931894189518961897189818991900190119021903190419051906190719081909191019111912191319141915191619171918191919201921192219231924192519261927192819291930193119321933193419351936193719381939194019411942194319441945194619471948194919501951195219531954195519561957195819591960196119621963196419651966196719681969197019711972197319741975197619771978197919801981198219831984198519861987198819891990199119921993199419951996199719981999200020012002200320042005200620072008200920102011201220132014201520162017201820192020202120222023202420252026202720282029203020312032203320342035203620372038203920402041204220432044204520462047204820492050205120522053205420552056205720582059206020612062206320642065206620672068206920702071207220732074207520762077207820792080208120822083208420852086208720882089209020912092209320942095209620972098209921002101210221032104210521062107210821092110211121122113211421152116211721182119212021212122212321242125212621272128212921302131213221332134213521362137213821392140214121422143214421452146214721482149215021512152215321542155215621572158215921602161216221632164216521662167216821692170217121722173217421752176217721782179218021812182218321842185218621872188218921902191219221932194219521962197219821992200220122022203220422052206220722082209221022112212221322142215221622172218221922202221222222232224222522262227222822292230223122322233223422352236223722382239224022412242224322442245224622472248224922502251225222532254225522562257225822592260226122622263226422652266226722682269227022712272227322742275227622772278227922802281228222832284228522862287228822892290229122922293229422952296229722982299230023012302230323042305230623072308230923102311231223132314231523162317231823192320232123222323232423252326232723282329233023312332233323342335233623372338233923402341234223432344234523462347234823492350235123522353235423552356235723582359236023612362236323642365236623672368236923702371237223732374237523762377237823792380238123822383238423852386238723882389239023912392239323942395239623972398239924002401240224032404240524062407240824092410241124122413241424152416241724182419242024212422242324242425242624272428242924302431243224332434243524362437243824392440244124422443244424452446244724482449245024512452245324542455245624572458245924602461246224632464
  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 <pcl\segmentation\extract_clusters.h>
  20. #include <math.h>
  21. #include "grab_point_rs.h"
  22. #include "utils.h"
  23. #define PI std::acos(-1)
  24. namespace graft_cv {
  25. CRootStockGrabPoint::CRootStockGrabPoint(ConfigParam&cp, CGcvLogger*pLog/*=0*/)
  26. :m_cparam(cp),
  27. m_pLogger(pLog),
  28. m_dtype(0),
  29. m_pcdId(""),
  30. m_ppImgSaver(0),
  31. m_1st_row_zmean_rs(-1.0),
  32. m_1st_row_zmean_sc(-1.0)
  33. {
  34. }
  35. CRootStockGrabPoint::~CRootStockGrabPoint() {}
  36. float* CRootStockGrabPoint::get_raw_point_cloud(int &data_size)
  37. {
  38. data_size = m_raw_cloud->width * m_raw_cloud->height;
  39. if (data_size == 0) {
  40. return 0;
  41. }
  42. else {
  43. pcl::PointXYZ* pp = m_raw_cloud->points.data();
  44. return (float*)pp->data;
  45. }
  46. }
  47. int CRootStockGrabPoint::load_data(
  48. float*pPoint,
  49. int pixel_size,
  50. int pt_size,
  51. int dtype,
  52. const char* fn/* = 0*/)
  53. {
  54. //数据加载功能实现,并生成imageid,保存原始数据到文件
  55. int rst = 0;
  56. m_dtype = dtype;
  57. //generate image id
  58. if (m_dtype == 0) {
  59. m_pcdId = getImgId(img_type::sola_sc_pcd);
  60. }
  61. else {
  62. m_pcdId = getImgId(img_type::sola_rs_pcd);
  63. }
  64. //1 get point cloud data
  65. if (pPoint != 0 && pt_size>0) {
  66. //read point
  67. m_raw_cloud.reset(new pcl::PointCloud<pcl::PointXYZ>);
  68. int step = pixel_size;
  69. for (int i = 0; i < pt_size; ++i) {
  70. pcl::PointXYZ pt = { pPoint[i*step], pPoint[i*step + 1] , pPoint[i*step + 2] };
  71. m_raw_cloud->push_back(pt);
  72. }
  73. rst = m_raw_cloud->width * m_raw_cloud->height;
  74. if (m_pLogger) {
  75. stringstream buff;
  76. buff << m_pcdId <<": load raw point cloud " << rst << " data points";
  77. m_pLogger->INFO(buff.str());
  78. }
  79. }
  80. else if (fn != 0) {
  81. //read file
  82. rst = this->read_ply_file(fn);
  83. }
  84. else {//error
  85. if (m_pLogger) {
  86. m_pLogger->ERRORINFO(m_pcdId + ": no valid input");
  87. return (-1);
  88. }
  89. }
  90. if (m_ppImgSaver && *m_ppImgSaver) {
  91. (*m_ppImgSaver)->saveBinPly(m_raw_cloud, m_pcdId);
  92. }
  93. if (m_cparam.image_show) {
  94. viewer_cloud(m_raw_cloud, m_pcdId + std::string(": raw point cloud"));
  95. }
  96. return rst;
  97. }
  98. int CRootStockGrabPoint::grab_point_detect(
  99. PositionInfo& posinfo
  100. )
  101. {
  102. // 抓取位置识别入口函数,实现整个抓取位置识别功能,返回抓取位置信息
  103. // dtype == 0, scion
  104. // dtype != 0, rootstock
  105. // 输入,穗苗--0, 砧木--1
  106. if (m_raw_cloud->width * m_raw_cloud->height < 1) {
  107. if (m_pLogger) {
  108. stringstream buff;
  109. buff << m_pcdId << ": m_raw_cloud point cloud " << m_raw_cloud->width * m_raw_cloud->height << " data points";
  110. m_pLogger->ERRORINFO(buff.str());
  111. }
  112. return 1;
  113. }
  114. ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  115. //1 crop filter,剪裁需要的部分点云
  116. if (m_pLogger) {
  117. m_pLogger->INFO(m_pcdId + ": begin crop");
  118. }
  119. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  120. pcl::CropBox<pcl::PointXYZ> box_filter;
  121. if (m_dtype != 0) {//rootstock
  122. box_filter.setMin(Eigen::Vector4f(m_cparam.rs_grab_xmin, m_cparam.rs_grab_ymin, m_cparam.rs_grab_zmin, 1));
  123. box_filter.setMax(Eigen::Vector4f(m_cparam.rs_grab_xmax, m_cparam.rs_grab_ymax, m_cparam.rs_grab_zmax, 1));
  124. }
  125. else {//scion
  126. box_filter.setMin(Eigen::Vector4f(m_cparam.sc_grab_xmin, m_cparam.sc_grab_ymin, m_cparam.sc_grab_zmin, 1));
  127. box_filter.setMax(Eigen::Vector4f(m_cparam.sc_grab_xmax, m_cparam.sc_grab_ymax, m_cparam.sc_grab_zmax, 1));
  128. }
  129. box_filter.setNegative(false);
  130. box_filter.setInputCloud(m_raw_cloud);
  131. box_filter.filter(*cloud_inbox);
  132. if (m_pLogger) {
  133. stringstream buff;
  134. buff << m_pcdId << ": CropBox croped point cloud " << cloud_inbox->width * cloud_inbox->height << " data points";
  135. m_pLogger->INFO(buff.str());
  136. }
  137. if (cloud_inbox->width * cloud_inbox->height < 1) {
  138. return 1;
  139. }
  140. if (m_cparam.image_show) {
  141. viewer_cloud(cloud_inbox, std::string("cloud_inbox"));
  142. }
  143. if (m_pLogger) {
  144. m_pLogger->INFO(m_pcdId + ": end crop");
  145. }
  146. ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  147. //2 filtler with radius remove, 去除孤立点
  148. if (m_pLogger) {
  149. m_pLogger->INFO(m_pcdId + ": begin ror");
  150. }
  151. int nb_points = 20;
  152. double stem_radius = m_cparam.rs_grab_stem_diameter / 2.0;
  153. if(m_dtype == 0){
  154. stem_radius = m_cparam.sc_grab_stem_diameter / 2.0;
  155. }
  156. double remove_radius = stem_radius * 2.0;
  157. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ror(new pcl::PointCloud<pcl::PointXYZ>);
  158. pcl::RadiusOutlierRemoval<pcl::PointXYZ> ror(false);
  159. ror.setInputCloud(cloud_inbox);
  160. ror.setRadiusSearch(remove_radius);
  161. ror.setMinNeighborsInRadius(nb_points);
  162. ror.filter(*cloud_ror);
  163. if (m_pLogger) {
  164. stringstream buff;
  165. buff << m_pcdId <<": RadiusOutlierRemoval filtered point cloud "
  166. << cloud_ror->width * cloud_ror->height
  167. << " data points. param stem_radius="<<
  168. stem_radius<<", nb_points="<< nb_points;
  169. m_pLogger->INFO(buff.str());
  170. }
  171. if (cloud_ror->width * cloud_ror->height < 1) {
  172. return 1;
  173. }
  174. /*if (m_cparam.image_show) {
  175. viewer_cloud(cloud_ror, std::string("cloud_ror"));
  176. }*/
  177. if (m_pLogger) {
  178. m_pLogger->INFO(m_pcdId + ": end ror");
  179. }
  180. ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  181. //3 voxel grid down sampling, 降采样
  182. if (m_pLogger) {
  183. m_pLogger->INFO(m_pcdId + ": begin down");
  184. }
  185. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_dowm_sampled_with_leaf(new pcl::PointCloud<pcl::PointXYZ>);
  186. pcl::VoxelGrid<pcl::PointXYZ> outrem;
  187. outrem.setInputCloud(cloud_ror);
  188. //outrem.setLeafSize(stem_radius, stem_radius, stem_radius);
  189. double voxel_size = m_cparam.rs_grab_voxel_size;
  190. if (m_dtype == 0) { voxel_size = m_cparam.sc_grab_voxel_size; }
  191. outrem.setLeafSize(voxel_size, voxel_size, voxel_size);
  192. outrem.filter(*cloud_dowm_sampled_with_leaf);
  193. if (m_pLogger) {
  194. stringstream buff;
  195. buff << m_pcdId <<": VoxelGrid dowm_sampled point cloud "
  196. << cloud_dowm_sampled_with_leaf->width * cloud_dowm_sampled_with_leaf->height
  197. << " data points (if < 50, return)";
  198. m_pLogger->INFO(buff.str());
  199. }
  200. if (cloud_dowm_sampled_with_leaf->width * cloud_dowm_sampled_with_leaf->height < 50) {
  201. return 1;
  202. }
  203. /*if (m_cparam.image_show) {
  204. viewer_cloud(cloud_dowm_sampled, std::string("cloud_dowm_sampled"));
  205. }*/
  206. if (m_pLogger) {
  207. m_pLogger->INFO(m_pcdId + ": end down");
  208. }
  209. ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  210. // 4 对截取的点云进行聚类分析,剔除叶片
  211. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_dowm_sampled(new pcl::PointCloud<pcl::PointXYZ>);
  212. std::vector<int> non_leaf_indices;
  213. //leaf_filter(cloud_dowm_sampled_with_leaf, non_leaf_indices);
  214. //leaf_filter_morph(cloud_dowm_sampled_with_leaf, non_leaf_indices);
  215. leaf_filter_ror(cloud_dowm_sampled_with_leaf, non_leaf_indices);
  216. pcl::copyPointCloud(*cloud_dowm_sampled_with_leaf, non_leaf_indices, *cloud_dowm_sampled);
  217. if (m_pLogger) {
  218. stringstream buff;
  219. buff << m_pcdId << ": after leaf_filter dowm_sampled point cloud "
  220. << cloud_dowm_sampled->width * cloud_dowm_sampled->height << " data points (if < 50, return)";
  221. m_pLogger->INFO(buff.str());
  222. }
  223. if (cloud_dowm_sampled->width * cloud_dowm_sampled->height < 50) {
  224. return 1;
  225. }
  226. ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  227. //5 seedling position,找到第一个位置上的植株
  228. std::vector<int> first_seedling_cloud_idx; //存储找到的第一个位置上植株茎上直线点的index
  229. pcl::PointXYZ xz_center; //存储找到的第一个位置上植株根部坐标
  230. pcl::ModelCoefficients::Ptr line_model; //存储找到的第一个位置上植株茎直线模型
  231. if (m_pLogger) {
  232. m_pLogger->INFO(m_pcdId + ": begin find seedling position");
  233. }
  234. find_seedling_position_key(cloud_dowm_sampled, first_seedling_cloud_idx, xz_center, line_model);
  235. if (m_pLogger) {
  236. stringstream buff;
  237. buff << m_pcdId <<": after find_seedling_position(), foud first seedling seeds points size " << first_seedling_cloud_idx.size();
  238. m_pLogger->INFO(buff.str());
  239. }
  240. if (m_pLogger) {
  241. m_pLogger->INFO(m_pcdId + ": end find seedling position");
  242. }
  243. ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  244. //6 nearest seedling grab point selection,找到最接近指定高度的最优抓取点坐标
  245. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_seedling_seed(new pcl::PointCloud<pcl::PointXYZ>);
  246. pcl::copyPointCloud(*cloud_dowm_sampled, first_seedling_cloud_idx, *cloud_seedling_seed);
  247. //改进思路:将茎直线上cloud_seedling_seed的点,提取周围邻域xz的宽度,在相同邻域cloud_dowm_sampled点云内提取xz的宽度
  248. //对比两个宽度,变化很大的,说明周边有异物(叶柄或叶子),不适合作为抓取位置;否则就是抓取位置
  249. //在众多抓取位置上,选择离指定高度最近的点作为抓取位置
  250. //
  251. //显示位置
  252. if (m_cparam.image_show) {
  253. std::vector<pcl::PointXYZ> tmp;
  254. tmp.push_back(xz_center);
  255. pcl::PointCloud<pcl::PointXYZRGB>::Ptr tttp(new pcl::PointCloud<pcl::PointXYZRGB>);
  256. pcl::copyPointCloud(*cloud_seedling_seed, *tttp);
  257. for (auto& pt : *tttp) {
  258. pt.r = 255;
  259. pt.g = 255;
  260. pt.b = 255;
  261. }
  262. viewer_cloud_cluster(tttp, tmp, string("first"));
  263. }
  264. pcl::PointXYZ selected_pt;
  265. int selected_pt_idx;
  266. std::vector<int> optimal_seeds_idx;
  267. get_optimal_seed_compare(
  268. cloud_dowm_sampled, //input
  269. cloud_seedling_seed, //input
  270. line_model, //input
  271. selected_pt, //output
  272. selected_pt_idx, //output
  273. optimal_seeds_idx); //output
  274. if (selected_pt_idx < 0) {
  275. if (m_pLogger) {
  276. m_pLogger->ERRORINFO(m_pcdId + ": Not found valid fork point");
  277. }
  278. return 1;
  279. }
  280. if (m_pLogger) {
  281. m_pLogger->INFO(m_pcdId + ": end get_optimal_seed");
  282. }
  283. if (m_dtype == 0) {
  284. posinfo.sc_grab_x = selected_pt.x;
  285. posinfo.sc_grab_y = selected_pt.y;
  286. posinfo.sc_grab_z = selected_pt.z;
  287. }
  288. else {
  289. posinfo.rs_grab_x = selected_pt.x;
  290. posinfo.rs_grab_y = selected_pt.y;
  291. posinfo.rs_grab_z = selected_pt.z;
  292. }
  293. ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  294. //7 保存处理结果到图片
  295. cv::Mat rst_img = cv::Mat::zeros(cv::Size(1280,640),CV_8UC1);
  296. gen_result_img(cloud_dowm_sampled, selected_pt, rst_img);
  297. if (m_ppImgSaver && *m_ppImgSaver) {
  298. (*m_ppImgSaver)->saveImage(rst_img, m_pcdId + "_rst_0");
  299. }
  300. ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  301. //7 debug 显示结果
  302. if (m_cparam.image_show) {
  303. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_cand_demo(new pcl::PointCloud<pcl::PointXYZRGB>);
  304. pcl::copyPointCloud(*cloud_dowm_sampled, *cloud_cand_demo);
  305. for (auto& pt : *cloud_cand_demo) {
  306. pt.r = 255;
  307. pt.g = 255;
  308. pt.b = 255;
  309. }
  310. int cnt = 0;
  311. for (auto& idx : optimal_seeds_idx) {
  312. int p_idx = first_seedling_cloud_idx.at(idx);
  313. /*if (p_idx == optimal_seeds_idx[selected_pt_idx]) {
  314. cloud_cand_demo->points[p_idx].r = 0;
  315. cloud_cand_demo->points[p_idx].g = 255;
  316. cloud_cand_demo->points[p_idx].b = 0;
  317. }
  318. else {*/
  319. cloud_cand_demo->points.at(p_idx).r = 255;
  320. cloud_cand_demo->points.at(p_idx).g = 0;
  321. cloud_cand_demo->points.at(p_idx).b = 0;
  322. /*} */
  323. if (cnt > optimal_seeds_idx.size()) { break; }
  324. cnt++;
  325. }
  326. pcl::PointXYZRGB pt_grab = {0,255,0};
  327. pt_grab.x = selected_pt.x;
  328. pt_grab.y = selected_pt.y;
  329. pt_grab.z = selected_pt.z;
  330. pcl::PointXYZRGB pt_grab_ = { 0,255,120 };
  331. pt_grab_.x = selected_pt.x;
  332. pt_grab_.y = selected_pt.y+0.2;
  333. pt_grab_.z = selected_pt.z;
  334. cloud_cand_demo->push_back(pt_grab);
  335. //viewer_cloud(cloud_cand_demo, std::string("cloud_cand_demo"));
  336. viewer_cloud_debug(cloud_cand_demo, selected_pt, xz_center, std::string("cloud_cand_demo"));
  337. imshow_wait("rst_img", rst_img);
  338. }
  339. return 0;
  340. }
  341. //生成结果图片
  342. void CRootStockGrabPoint::gen_result_img(
  343. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, //输入,整体点云cloud_dowm_sampled,
  344. pcl::PointXYZ& selected_pt, //输入,selected_pt,
  345. cv::Mat& rst_img //输出,图片, 640*1280
  346. )
  347. {
  348. if (rst_img.empty()) { return; }
  349. if (rst_img.rows != 640 && rst_img.cols != 1280) { return; }
  350. int cx = 640; //图像中心点0
  351. int cy = 320; //图像中心点0
  352. float res = 0.33333; //分辨率,1个像素0.333mm
  353. //绘制坐标轴
  354. int arrow_len = 20;
  355. cv::line(rst_img, cv::Point(0, cy), cv::Point(cx, cy), cv::Scalar(128));
  356. cv::line(rst_img, cv::Point(0, cy), cv::Point(arrow_len, cy - int(arrow_len/2)), cv::Scalar(128));
  357. cv::line(rst_img, cv::Point(0, cy), cv::Point(arrow_len, cy + int(arrow_len/2)), cv::Scalar(128));
  358. cv::line(rst_img, cv::Point(cx, 0), cv::Point(cx, cy), cv::Scalar(128));
  359. cv::line(rst_img, cv::Point(cx, 0), cv::Point(cx - int(arrow_len/2), arrow_len), cv::Scalar(128));
  360. cv::line(rst_img, cv::Point(cx, 0), cv::Point(cx + int(arrow_len/2), arrow_len), cv::Scalar(128));
  361. cv::putText(rst_img, std::string("x"), cv::Point(20, cy-10), cv::FONT_HERSHEY_SIMPLEX, 1, cv::Scalar(128));
  362. cv::putText(rst_img, std::string("y"), cv::Point(cx+10, 20), cv::FONT_HERSHEY_SIMPLEX, 1, cv::Scalar(128));
  363. //绘制所有点
  364. int x, y;
  365. for (auto&pt : in_cloud->points) {
  366. x = cx - int(pt.x / res + 0.5);
  367. y = cy - int(pt.y / res + 0.5);
  368. if (x < 0 || x >= rst_img.cols) { continue; }
  369. if (y < 0 || y >= rst_img.rows) { continue; }
  370. rst_img.at<unsigned char>(y, x) = 255;
  371. }
  372. //绘制抓取点坐标
  373. int grab_x = cx - int(selected_pt.x / res + 0.5);
  374. int grab_y = cy - int(selected_pt.y / res + 0.5);
  375. int radius = 30;
  376. cv::line(rst_img, cv::Point(grab_x - radius, grab_y - radius), cv::Point(grab_x + radius, grab_y + radius), cv::Scalar(128));
  377. cv::line(rst_img, cv::Point(grab_x - radius, grab_y + radius), cv::Point(grab_x + radius, grab_y - radius), cv::Scalar(128));
  378. }
  379. int CRootStockGrabPoint::read_ply_file(const char* fn)
  380. {
  381. m_raw_cloud.reset( new pcl::PointCloud<pcl::PointXYZ>);
  382. if (pcl::io::loadPLYFile<pcl::PointXYZ>(fn, *m_raw_cloud) == -1) {
  383. if (m_pLogger) {
  384. m_pLogger->ERRORINFO(m_pcdId + ": could not load file: "+std::string(fn));
  385. }
  386. return (-1);
  387. }
  388. if (m_pLogger) {
  389. stringstream buff;
  390. buff << m_pcdId <<": load raw point cloud " << m_raw_cloud->width * m_raw_cloud->height << " data points";
  391. m_pLogger->INFO(buff.str());
  392. }
  393. return m_raw_cloud->width * m_raw_cloud->height;
  394. }
  395. double CRootStockGrabPoint::compute_nearest_neighbor_distance(pcl::PointCloud<pcl::PointXYZ>::Ptr pcd)
  396. {
  397. pcl::KdTreeFLANN<pcl::PointXYZ> tree;
  398. tree.setInputCloud(pcd);
  399. int k = 2;
  400. double res = 0.0;
  401. int n_points = 0;
  402. for (size_t i = 0; i < pcd->size(); ++i) {
  403. std::vector<int> idx(k);
  404. std::vector<float> sqr_distances(k);
  405. if (tree.nearestKSearch(i, k, idx, sqr_distances) == k) {
  406. for (int id = 1; id < k; ++id) {
  407. res += sqrt(sqr_distances.at(id));
  408. ++n_points;
  409. }
  410. }
  411. }
  412. if (n_points > 0) {
  413. res /= (double)n_points;
  414. }
  415. return res;
  416. }
  417. //void CRootStockGrabPoint::find_tray_top_edge(
  418. //pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  419. //float & tray_top_edge_y
  420. //)
  421. //{
  422. // tray_top_edge_y = -1000.0;
  423. // //以毫米为单位构建vector
  424. // pcl::PointXYZ min_point_aabb;
  425. // pcl::PointXYZ max_point_aabb;
  426. // pcl::MomentOfInertiaEstimation<pcl::PointXYZ> feature_extractor;
  427. // feature_extractor.setInputCloud(in_cloud);
  428. // feature_extractor.compute();
  429. // feature_extractor.getAABB(min_point_aabb, max_point_aabb);
  430. // float miny = min_point_aabb.y;
  431. // float maxy = max_point_aabb.y;
  432. // if(maxy - miny <5.0){
  433. // tray_top_edge_y = maxy;
  434. // return;
  435. // }
  436. // std::vector<int> y_cnt_hist(int(maxy - miny), 0);
  437. // for(auto& pt : in_cloud->points){
  438. // int idx = (int)(pt.y - miny);
  439. // if(idx<0){continue;}
  440. // if (idx >= y_cnt_hist.size()) { continue; }
  441. // y_cnt_hist.at(idx) += 1;
  442. // }
  443. // //从上半部分找到最大值,作为平面上沿
  444. // int idx_part = (int)(y_cnt_hist.size() / 2);
  445. // int idx_edge = std::max_element(y_cnt_hist.begin(), y_cnt_hist.begin() + idx_part) - y_cnt_hist.begin();
  446. // tray_top_edge_y = miny + (float)(idx_edge + 2.0);
  447. //}
  448. //void CRootStockGrabPoint::find_seedling_position_line_based(
  449. // pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  450. // std::vector<int> &first_seedling_cloud_idx,
  451. // pcl::PointXYZ&xz_center
  452. //)
  453. //{
  454. // //找到穴盘上沿z,最优抓取的z,再在最优抓取的z基础上加上3作为有效范围
  455. // float tray_y = -1000.0;
  456. // float top_y = 0.0;
  457. // find_tray_top_edge(in_cloud, tray_y);
  458. // if (tray_y < -500.0) {
  459. // if (m_dtype == 0) {
  460. // //scion
  461. // tray_y = m_cparam.sc_grab_y_opt-2.0;
  462. // }
  463. // else {
  464. // tray_y = m_cparam.rs_grab_y_opt-2.0;
  465. // }
  466. // }
  467. // //up limit
  468. // if (m_dtype == 0) {
  469. // top_y = m_cparam.sc_grab_zmax;
  470. // if (top_y > m_cparam.sc_grab_y_opt + 3.0) {
  471. // top_y = m_cparam.sc_grab_y_opt + 3.0;
  472. // }
  473. // }
  474. // else {
  475. // top_y = m_cparam.rs_grab_zmax;
  476. // if (top_y > m_cparam.rs_grab_y_opt + 3.0) {
  477. // top_y = m_cparam.rs_grab_y_opt + 3.0;
  478. // }
  479. // }
  480. // //sub cloud
  481. // pcl::PointCloud<pcl::PointXYZ>::Ptr sub_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  482. // pcl::CropBox<pcl::PointXYZ> box_filter;
  483. // if (m_dtype != 0) {//rootstock
  484. // box_filter.setMin(Eigen::Vector4f(m_cparam.rs_grab_xmin, tray_y, m_cparam.rs_grab_zmin, 1));
  485. // box_filter.setMax(Eigen::Vector4f(m_cparam.rs_grab_xmax, top_y, m_cparam.rs_grab_zmax, 1));
  486. // }
  487. // else {//scion
  488. // box_filter.setMin(Eigen::Vector4f(m_cparam.sc_grab_xmin, tray_y, m_cparam.sc_grab_zmin, 1));
  489. // box_filter.setMax(Eigen::Vector4f(m_cparam.sc_grab_xmax, top_y, m_cparam.sc_grab_zmax, 1));
  490. // }
  491. // box_filter.setNegative(false);
  492. // box_filter.setInputCloud(in_cloud);
  493. // box_filter.filter(*sub_cloud);
  494. // if (m_cparam.image_show) {
  495. // viewer_cloud(sub_cloud, std::string("sub inbox"));
  496. // }
  497. // //在sub_cloud中进行直线检测
  498. // segement_line(sub_cloud);
  499. //}
  500. //void CRootStockGrabPoint::segement_line(
  501. // pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud
  502. //)
  503. //{
  504. // pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
  505. // pcl::PointIndices::Ptr inliers(new pcl::PointIndices);
  506. // pcl::SACSegmentation<pcl::PointXYZ> seg;
  507. // seg.setOptimizeCoefficients(true);
  508. // seg.setModelType(pcl::SACMODEL_LINE);
  509. // seg.setMethodType(pcl::SAC_RANSAC);
  510. // seg.setDistanceThreshold(0.5);
  511. // seg.setInputCloud(in_cloud);
  512. // seg.segment(*inliers, *coefficients);
  513. // if (m_cparam.image_show) {
  514. // pcl::PointCloud<pcl::PointXYZ>::Ptr line_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  515. // pcl::copyPointCloud(*in_cloud, *inliers, *line_cloud);
  516. // viewer_cloud(line_cloud, std::string("cloud_line"));
  517. // }
  518. //}
  519. ////////////////////////////////////////////////////////////
  520. //叶子剔除, 假设叶子和茎是分离的,用欧式聚类分割
  521. void CRootStockGrabPoint::leaf_filter(
  522. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, //输入,降采样的点云
  523. std::vector<int> &stem_cloud_idx //输出,除了叶子的点云序号
  524. )
  525. {
  526. //采用欧式距离聚类,对每一类的点云进行分析,剔除叶子
  527. stem_cloud_idx.clear();
  528. std::vector<pcl::PointIndices> cluster_indices;
  529. pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>);
  530. tree->setInputCloud(in_cloud);
  531. pcl::EuclideanClusterExtraction<pcl::PointXYZ> ec;
  532. ec.setClusterTolerance(2.5);
  533. ec.setMinClusterSize(30);
  534. ec.setMaxClusterSize(20000);
  535. ec.setSearchMethod(tree);
  536. ec.setInputCloud(in_cloud);
  537. ec.extract(cluster_indices);
  538. for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin();
  539. it != cluster_indices.end(); ++it) {
  540. pcl::PointCloud<pcl::PointXYZ>::Ptr cluster_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  541. pcl::copyPointCloud(*in_cloud, *it, *cluster_cloud);
  542. //计算点云的pca
  543. Eigen::Vector4f pcaCenteroid;
  544. pcl::compute3DCentroid(*cluster_cloud, pcaCenteroid);
  545. Eigen::Matrix3f covariance;
  546. pcl::computeCovarianceMatrix(*cluster_cloud, pcaCenteroid, covariance);
  547. Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eigen_solver(covariance, Eigen::ComputeEigenvectors);
  548. Eigen::Vector3f eigenValuesPCA = eigen_solver.eigenvalues();
  549. float e1, e2, e3;
  550. e1 = std::sqrt(eigenValuesPCA(2));
  551. e2 = std::sqrt(eigenValuesPCA(1));
  552. e3 = std::sqrt(eigenValuesPCA(0));
  553. float a1d = (e1 - e2) / e1;
  554. float a2d = (e2 - e3) / e1;
  555. float a3d = e3 / e1;
  556. if (m_pLogger) {
  557. stringstream buff;
  558. buff << m_pcdId << ": ads=(" << a1d << "," << a2d << "," << a3d << "), pca_eigem_values=(" << e1
  559. << "," << e2 << "," << e3 << "), cluster_size=" << it->indices.size();
  560. m_pLogger->INFO(buff.str());
  561. }
  562. if (m_cparam.image_show) {
  563. if (a1d < 0.75) {
  564. viewer_cloud(cluster_cloud, string("cluster_leaf"));
  565. }
  566. else {
  567. viewer_cloud(cluster_cloud, string("cluster_stem"));
  568. }
  569. }
  570. /*
  571. 特征值归一化处理: a1d = (e1 - e2) / e1
  572. a2d = (e2 - e3) / e1
  573. a3d = e3 / e1
  574. ei = sqrt(lamda_i)
  575. 当点云线状分布时,a1d = 1, a2d = 0, a3d = 0
  576. 当点云面状分布时,a1d = 0, a2d = 1, a3d = 0
  577. 当点云球状分布时,a1d = 0, a2d = 0, a3d = 1
  578. */
  579. if (a1d < 0.75) { continue; }
  580. for (int idx : it->indices) {
  581. stem_cloud_idx.push_back(idx);
  582. }
  583. }
  584. }
  585. ////////////////////////////////////////////////////////////////////////////////////
  586. // 基于3d空间形态学方法------------->
  587. //叶子剔除,通过形态学方法,腐蚀,得到叶子区域,将叶子区域内地的点云去掉
  588. void CRootStockGrabPoint::leaf_filter_morph(
  589. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, //input 输入点云数据
  590. std::vector<int> &stem_cloud_idx //output, 过滤后的点云序号
  591. )
  592. {
  593. //获取点云范围
  594. pcl::PointXYZ min_v;
  595. pcl::PointXYZ max_v;
  596. pcl::getMinMax3D(*in_cloud, min_v, max_v);
  597. //定义3维图像和像素间隔
  598. cv::Mat bin_3d_img;
  599. float pix_step = m_cparam.rs_grab_stem_diameter / 4.0;
  600. if (m_dtype == 0) { pix_step = m_cparam.sc_grab_stem_diameter / 4.0; }
  601. //创建点云存储图像对应关系
  602. std::map<int, std::vector<int>> imgidx_to_pcdidx;
  603. gen_3d_image(in_cloud, min_v, max_v, pix_step, bin_3d_img, imgidx_to_pcdidx);
  604. //腐蚀膨胀(开运算)
  605. int iter = 9;
  606. int threshold = 10;
  607. cv::Mat in_img = bin_3d_img.clone();
  608. for (int i = 0; i < iter; ++i) {
  609. cv::Mat e_img = cv::Mat::zeros(3, in_img.size, CV_8UC1);
  610. erosion_3d(in_img, threshold, e_img);
  611. in_img = e_img.clone();
  612. }
  613. for (int i = 0; i < iter; ++i) {
  614. cv::Mat e_img = cv::Mat::zeros(3, in_img.size, CV_8UC1);
  615. dilation_3d(in_img, e_img);
  616. in_img = e_img.clone();
  617. }
  618. //in_img是经过开运算的图像,其中像素位置的点云为叶子区域
  619. std::vector<int> leaf_idx;
  620. get_mass_obj_idx(in_img, imgidx_to_pcdidx, leaf_idx);
  621. std::vector<int>::iterator lit;
  622. for (int i = 0; i < in_cloud->points.size(); ++i) {
  623. lit = std::find(leaf_idx.begin(), leaf_idx.end(), i);
  624. if (lit == leaf_idx.end()) {
  625. stem_cloud_idx.push_back(i);
  626. }
  627. }
  628. //显示开运算的结果
  629. if (m_cparam.image_show) {
  630. pcl::PointCloud<pcl::PointXYZ>::Ptr stem_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  631. pcl::PointCloud<pcl::PointXYZ>::Ptr leaf_cloud(new pcl::PointCloud < pcl::PointXYZ>);
  632. pcl::copyPointCloud(*in_cloud, stem_cloud_idx, *stem_cloud);
  633. pcl::copyPointCloud(*in_cloud, leaf_idx, *leaf_cloud);
  634. pcl::visualization::PCLVisualizer viewer("open cloud");
  635. viewer.addCoordinateSystem();
  636. viewer.addPointCloud<pcl::PointXYZ>(stem_cloud, "stem_cloud");
  637. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 1, 1, "stem_cloud");
  638. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "stem_cloud");
  639. viewer.addPointCloud<pcl::PointXYZ>(leaf_cloud, "leaf_cloud");
  640. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 0, 0, "leaf_cloud");
  641. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "leaf_cloud");
  642. while (!viewer.wasStopped()) {
  643. viewer.spinOnce(100);
  644. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  645. }
  646. }
  647. }
  648. //生成3d图像
  649. void CRootStockGrabPoint::gen_3d_image(
  650. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, //input 输入点云数据
  651. pcl::PointXYZ& min_pt, //input 图像下限
  652. pcl::PointXYZ& max_pt, //input 图像上限
  653. float step, //input 图像像素间隔
  654. cv::Mat& bin_3d_img, //output, 生成的binary图像
  655. std::map<int, std::vector<int>>& id2pcdidx //output, 图像素位置内含pcd点云序号
  656. )
  657. {
  658. int width = static_cast<int>((max_pt.x - min_pt.x) / step);
  659. int height = static_cast<int>((max_pt.y - min_pt.y) / step);
  660. int layer = static_cast<int>((max_pt.z - min_pt.z) / step);
  661. id2pcdidx.clear();
  662. int dims[3];
  663. dims[0] = layer;
  664. dims[1] = height;
  665. dims[2] = width;
  666. std::map<int, std::vector<int>>::iterator it;
  667. bin_3d_img = cv::Mat::zeros(3, dims, CV_8UC1);
  668. for (int i = 0; i < in_cloud->points.size();++i) {
  669. pcl::PointXYZ&pt = in_cloud->points.at(i);
  670. int w = static_cast<int>((pt.x - min_pt.x) / step);
  671. int h = static_cast<int>((pt.y - min_pt.y) / step);
  672. int l = static_cast<int>((pt.z - min_pt.z) / step);
  673. if (w < 0 || w >= width) { continue; }
  674. if (h < 0 || h >= height) { continue; }
  675. if (l < 0 || l >= layer) { continue; }
  676. bin_3d_img.at<unsigned char>(l, h, w) = 1;
  677. int idx = l*height*width + h*width + w;
  678. it = id2pcdidx.find(idx);
  679. if (it == id2pcdidx.end()) {
  680. std::vector<int> tmp;
  681. tmp.push_back(i);
  682. id2pcdidx.insert(std::pair<int, std::vector<int>>(idx,tmp));
  683. }
  684. else {
  685. it->second.push_back(i);
  686. }
  687. }
  688. }
  689. //3*3*3内的膨胀
  690. void CRootStockGrabPoint::dilation_3d(
  691. cv::Mat& in_3d_img, //input, 输入图像
  692. cv::Mat& out_3d_img //output, 生成的图像
  693. )
  694. {
  695. int width = in_3d_img.size[2];
  696. int height = in_3d_img.size[1];
  697. int layer = in_3d_img.size[0];
  698. int x, y, z;
  699. for (int l = 0; l < layer; ++l) {
  700. for (int h = 0; h < height; ++h) {
  701. for (int w = 0; w < width; ++w) {
  702. if (in_3d_img.at<unsigned char>(l, h, w) == 0) { continue; }
  703. for (int dz = -1; dz <= 1; dz++) {
  704. z = l + dz;
  705. if (z < 0 || z >= layer) { continue; }
  706. for (int dy = -1; dy <= 1; dy++) {
  707. y = h + dy;
  708. if (y < 0 || y >= height) { continue; }
  709. for (int dx = -1; dx <= 1; dx++) {
  710. x = w + dx;
  711. if (x < 0 || x >= width) { continue; }
  712. out_3d_img.at<unsigned char>(z, y, x) = 1;
  713. }
  714. }
  715. }
  716. }
  717. }
  718. }
  719. }
  720. //3*3*3内的腐蚀
  721. void CRootStockGrabPoint::erosion_3d(
  722. cv::Mat& in_3d_img,
  723. int th, //阈值
  724. cv::Mat& out_3d_img
  725. )
  726. {
  727. int width = in_3d_img.size[2];
  728. int height = in_3d_img.size[1];
  729. int layer = in_3d_img.size[0];
  730. int x, y, z;
  731. for (int l = 0; l < layer; ++l) {
  732. for (int h = 0; h < height; ++h) {
  733. for (int w = 0; w < width; ++w) {
  734. if (in_3d_img.at<unsigned char>(l, h, w) == 0) { continue; }
  735. int cnt = 0;
  736. for (int dz = -1; dz <= 1; dz++) {
  737. z = l + dz;
  738. if (z < 0 || z >= layer) { continue; }
  739. for (int dy = -1; dy <= 1; dy++) {
  740. y = h + dy;
  741. if (y < 0 || y >= height) { continue; }
  742. for (int dx = -1; dx <= 1; dx++) {
  743. x = w + dx;
  744. if (x < 0 || x >= width) { continue; }
  745. if (in_3d_img.at<unsigned char>(z, y, x) == 0) { continue; }
  746. cnt++;
  747. }
  748. }
  749. }
  750. if (cnt >= th) {
  751. out_3d_img.at<unsigned char>(l, h, w) = 1;
  752. }
  753. }
  754. }
  755. }
  756. }
  757. //得到点云序号
  758. void CRootStockGrabPoint::get_mass_obj_idx(
  759. cv::Mat& open_3d_img, //input, 开运算后的图像
  760. std::map<int, std::vector<int>>& id2pcdidx, //input 保存的像素位置的点云序号
  761. std::vector<int>& mass_idx //output,
  762. )
  763. {
  764. mass_idx.clear();
  765. int width = open_3d_img.size[2];
  766. int height = open_3d_img.size[1];
  767. int layer = open_3d_img.size[0];
  768. std::map<int, std::vector<int>>::iterator it;
  769. for (int l = 0; l < layer; ++l) {
  770. for (int h = 0; h < height; ++h) {
  771. for (int w = 0; w < width; ++w) {
  772. if (open_3d_img.at<unsigned char>(l, h, w) == 0) { continue; }
  773. int idx = l*height*width + h*width + w;
  774. it = id2pcdidx.find(idx);
  775. if (it != id2pcdidx.end()) {
  776. for (int& j : it->second) {
  777. mass_idx.push_back(j);
  778. }
  779. }
  780. }
  781. }
  782. }
  783. }
  784. // <-------------基于3d空间形态学方法
  785. //////////////////////////////////////////////////////////////////////////////////////
  786. // 基于孤立点滤除的方法检测叶子区域
  787. void CRootStockGrabPoint::leaf_filter_ror(
  788. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, //input 输入点云数据
  789. std::vector<int> &stem_cloud_idx //output, 过滤后的点云序号
  790. )
  791. {
  792. //计算点云平均间距
  793. double mean_dist = 0.0;
  794. cloud_mean_dist(in_cloud, mean_dist);
  795. //计算点云过滤半径和点数阈值
  796. double stem_diameter = m_cparam.rs_grab_stem_diameter;
  797. if (m_dtype == 0) { stem_diameter = m_cparam.sc_grab_stem_diameter; }
  798. double remove_radius = stem_diameter;
  799. int nb_points = stem_diameter * stem_diameter * 2.57 / mean_dist / mean_dist; // (2d*d + pi *d*d) /2
  800. //获取叶片的点云
  801. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_leaf(new pcl::PointCloud<pcl::PointXYZ>);
  802. pcl::RadiusOutlierRemoval<pcl::PointXYZ> ror(true);
  803. ror.setInputCloud(in_cloud);
  804. ror.setRadiusSearch(remove_radius);
  805. ror.setMinNeighborsInRadius(nb_points);
  806. ror.filter(*cloud_leaf);
  807. //通过叶片点云寻找附近remove_radius内的近邻点,当做叶子点云序号
  808. std::set<int> leaf_idx_set;
  809. int nres;
  810. std::vector<int> indices;
  811. std::vector<float> sqr_distances;
  812. pcl::search::KdTree<pcl::PointXYZ> tree;
  813. tree.setInputCloud(in_cloud);
  814. for (size_t i = 0; i < cloud_leaf->size(); ++i)
  815. {
  816. nres = tree.radiusSearch(cloud_leaf->points.at(i), remove_radius, indices, sqr_distances);
  817. for (int& idx : indices) {
  818. leaf_idx_set.insert(idx);
  819. }
  820. }
  821. std::vector<int> leaf_idx;
  822. leaf_idx.assign(leaf_idx_set.begin(), leaf_idx_set.end());
  823. //in_img是经过开运算的图像,其中像素位置的点云为叶子区域
  824. std::vector<int>::iterator lit;
  825. for (int i = 0; i < in_cloud->points.size(); ++i) {
  826. lit = std::find(leaf_idx.begin(), leaf_idx.end(), i);
  827. if (lit == leaf_idx.end()) {
  828. stem_cloud_idx.push_back(i);
  829. }
  830. }
  831. //显示开运算的结果
  832. if (m_cparam.image_show) {
  833. pcl::PointCloud<pcl::PointXYZ>::Ptr stem_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  834. pcl::PointCloud<pcl::PointXYZ>::Ptr leaf_cloud(new pcl::PointCloud < pcl::PointXYZ>);
  835. pcl::copyPointCloud(*in_cloud, stem_cloud_idx, *stem_cloud);
  836. pcl::copyPointCloud(*in_cloud, leaf_idx, *leaf_cloud);
  837. pcl::visualization::PCLVisualizer viewer("open cloud");
  838. viewer.addCoordinateSystem();
  839. viewer.addPointCloud<pcl::PointXYZ>(stem_cloud, "stem_cloud");//????????????????
  840. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 1, 1, "stem_cloud");
  841. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "stem_cloud");
  842. viewer.addPointCloud<pcl::PointXYZ>(leaf_cloud, "leaf_cloud");
  843. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 0, 0, "leaf_cloud");
  844. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "leaf_cloud");
  845. while (!viewer.wasStopped()) {
  846. viewer.spinOnce(100);
  847. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  848. }
  849. }
  850. }
  851. void CRootStockGrabPoint::cloud_mean_dist(
  852. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, //input 输入点云数据
  853. double& mean_dist
  854. )
  855. {
  856. mean_dist = 0.0;
  857. int n_points = 0;
  858. int nres;
  859. std::vector<int> indices(2);
  860. std::vector<float> sqr_distances(2);
  861. pcl::search::KdTree<pcl::PointXYZ> tree;
  862. tree.setInputCloud(in_cloud);
  863. for (size_t i = 0; i < in_cloud->size(); ++i)
  864. {
  865. //Considering the second neighbor since the first is the point itself.
  866. nres = tree.nearestKSearch(i, 2, indices, sqr_distances);
  867. if (nres == 2)
  868. {
  869. mean_dist +=std::sqrt(sqr_distances[1]);
  870. ++n_points;
  871. }
  872. }
  873. if (n_points != 0)
  874. {
  875. mean_dist /= n_points;
  876. }
  877. }
  878. //////////////////////////////////////////////////////////////////////////////////////////
  879. void CRootStockGrabPoint::gen_all_seedling_positions(
  880. pcl::PointXYZ&key_center, //输入,已知的苗的坐标
  881. std::vector<pcl::PointXYZ>&candidate_center //输出,有倾斜苗的坐标
  882. )
  883. {
  884. //生成所有的植株位置,并排序
  885. candidate_center.clear();
  886. //找到z最小的那一株,并找出和它一排的那些
  887. float step_harf = m_cparam.rs_grab_seedling_dist / 2.0;
  888. float xmin = m_cparam.rs_grab_xmin;
  889. float xmax = m_cparam.rs_grab_xmax;
  890. float zmin = m_cparam.rs_grab_zmin;
  891. float zmax = m_cparam.rs_grab_zmax;
  892. int col_from = -8;
  893. int col_to = 8;
  894. int col_step = 1;
  895. if (m_dtype == 0) {
  896. step_harf = m_cparam.sc_grab_seedling_dist / 2.0;
  897. xmin = m_cparam.sc_grab_xmin;
  898. xmax = m_cparam.sc_grab_xmax;
  899. zmin = m_cparam.sc_grab_zmin;
  900. zmax = m_cparam.sc_grab_zmax;
  901. }
  902. // 生成所有可能的植株位置中心点
  903. for (int row = -8; row <= 4; row += 1) {
  904. float cz = key_center.z + row * step_harf/2.0;
  905. if (cz < zmin || cz > zmax) { continue; }
  906. for (int col = 4*col_from; col <= 4*col_to; col += col_step) {
  907. float cx = key_center.x + col * step_harf/2;
  908. if (cx < xmin || cx > xmax) { continue; }
  909. //保存
  910. pcl::PointXYZ pc(cx, 0.0, cz);
  911. candidate_center.push_back(pc);
  912. }
  913. }
  914. }
  915. void CRootStockGrabPoint::nms_box(
  916. std::vector<pcl::PointXYZ>&clt_root_v,
  917. std::vector<float>&valid_box_cc_dist,
  918. float hole_step_radius,
  919. std::vector<pcl::PointXYZ>& target_toot)
  920. {
  921. target_toot.clear();
  922. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
  923. for (auto&p : clt_root_v) { cloud->points.push_back(p); }
  924. pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
  925. kdtree.setInputCloud(cloud);
  926. std::vector<int>idx;
  927. std::vector<float>dist_sqr;
  928. std::vector<int> tar_idx;
  929. for (size_t i = 0; i < cloud->points.size(); ++i) {
  930. int k = kdtree.radiusSearch(cloud->points.at(i), hole_step_radius, idx, dist_sqr);
  931. std::vector<float> cc_tmp;
  932. for (auto& j : idx) { cc_tmp.push_back(valid_box_cc_dist.at(j)); }
  933. int min_id = std::min_element(cc_tmp.begin(), cc_tmp.end()) - cc_tmp.begin();
  934. if (min_id == 0) {
  935. tar_idx.push_back(i);
  936. }
  937. }
  938. for (auto& i : tar_idx) {
  939. target_toot.push_back(clt_root_v.at(i));
  940. }
  941. }
  942. //通过指定位置内,取部分点云分析是否存在真正的茎,真茎位置保存到target_filtered
  943. void CRootStockGrabPoint::line_filter(
  944. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, //输入点云
  945. float radius, //输入,取点半径
  946. float ymin,
  947. float ymax,
  948. std::vector<pcl::PointXYZ>&target_root, //输入,位置
  949. std::vector<pcl::PointXYZ>&target_filtered, //输出,位置
  950. std::vector<pcl::PointXYZ>&target_filtered_root, //输出,茎上根部点坐标
  951. std::vector<std::vector<int>>&target_filtered_element, //输出,茎上点index
  952. std::vector<pcl::ModelCoefficients::Ptr>& target_filtered_models//输出,茎直线模型
  953. )
  954. {
  955. target_filtered.clear();
  956. target_filtered_element.clear();
  957. target_filtered_root.clear();
  958. if (target_root.size() == 0) { return; }
  959. for (auto&p : target_root) {
  960. // 构建box,获取植株点云
  961. pcl::PointCloud<pcl::PointXYZ>::Ptr seedling_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  962. pcl::CropBox<pcl::PointXYZ> box_filter;
  963. std::vector<int>inbox_idx;
  964. pcl::PointXYZ min_point_aabb_ex;
  965. pcl::PointXYZ max_point_aabb_ex;
  966. min_point_aabb_ex.x = p.x - radius;
  967. min_point_aabb_ex.y = ymin;
  968. min_point_aabb_ex.z = p.z - radius;
  969. max_point_aabb_ex.x = p.x + radius;
  970. max_point_aabb_ex.y = ymax;
  971. max_point_aabb_ex.z = p.z + radius;
  972. box_filter.setMin(Eigen::Vector4f(min_point_aabb_ex.x, min_point_aabb_ex.y, min_point_aabb_ex.z, 1));
  973. box_filter.setMax(Eigen::Vector4f(max_point_aabb_ex.x, max_point_aabb_ex.y, max_point_aabb_ex.z, 1));
  974. box_filter.setNegative(false);
  975. box_filter.setInputCloud(in_cloud);
  976. box_filter.filter(inbox_idx);
  977. pcl::copyPointCloud(*in_cloud, inbox_idx, *seedling_inbox);
  978. //植株点云直线查找
  979. //找到inbox点云中的直线
  980. float stem_radius = m_cparam.rs_grab_stem_diameter / 2.0;
  981. if (m_dtype == 0) {
  982. stem_radius = m_cparam.sc_grab_stem_diameter / 2.0;
  983. }
  984. pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
  985. pcl::PointIndices::Ptr inliers(new pcl::PointIndices);
  986. pcl::SACSegmentation<pcl::PointXYZ> seg;
  987. seg.setOptimizeCoefficients(true);
  988. seg.setModelType(pcl::SACMODEL_LINE);
  989. seg.setDistanceThreshold(stem_radius);
  990. seg.setInputCloud(seedling_inbox);
  991. seg.segment(*inliers, *coefficients);
  992. pcl::PointCloud<pcl::PointXYZ>::Ptr stem_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  993. pcl::copyPointCloud(*seedling_inbox, *inliers, *stem_cloud);
  994. //点数过滤
  995. int min_stem_pts = m_cparam.rs_grab_stem_min_pts;
  996. if (m_dtype == 0) { min_stem_pts = m_cparam.sc_grab_stem_min_pts; }
  997. if (inliers->indices.size() < int(min_stem_pts / 2)) { continue; }
  998. //y方向分布范围滤波
  999. pcl::PointXYZ min_v;
  1000. pcl::PointXYZ max_v;
  1001. pcl::getMinMax3D(*stem_cloud, min_v, max_v);
  1002. float dy = max_v.y - min_v.y;
  1003. if (dy / (ymax - ymin) < 0.5) { continue; }
  1004. //y方向分布中心滤波
  1005. float dy_c = 0.5*(max_v.y + min_v.y);
  1006. if ((dy_c - ymin) / (ymax - ymin) > 0.75) { continue; }
  1007. //倾斜角度过滤
  1008. float xz = std::sqrt(coefficients->values.at(3) * coefficients->values.at(3) +
  1009. coefficients->values.at(5) * coefficients->values.at(5));
  1010. float a = std::atan2f(coefficients->values.at(4), xz);
  1011. a = std::fabs(a) * 180.0 / 3.14159;
  1012. if (a < 45.0) { continue; }
  1013. target_filtered.push_back(p);
  1014. float min_y = 10000.0;
  1015. int min_y_idx = -1;
  1016. for (size_t j = 0; j < stem_cloud->points.size();++j) {
  1017. pcl::PointXYZ &spt = stem_cloud->at(j);
  1018. if (spt.y < min_y) {
  1019. min_y = spt.y;
  1020. min_y_idx = j;
  1021. }
  1022. }
  1023. pcl::PointXYZ tr_pt(stem_cloud->points.at(min_y_idx).x, stem_cloud->points.at(min_y_idx).y, stem_cloud->points.at(min_y_idx).z);
  1024. target_filtered_root.push_back(tr_pt);
  1025. int idx_raw = 0;
  1026. std::vector<int> out_idx;
  1027. for (auto& idx : inliers->indices) {
  1028. idx_raw = inbox_idx.at(idx);
  1029. out_idx.push_back(idx_raw);
  1030. }
  1031. target_filtered_element.push_back(out_idx);
  1032. target_filtered_models.push_back(coefficients);
  1033. // debug show
  1034. /*if (m_cparam.image_show) {
  1035. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_line(new pcl::PointCloud<pcl::PointXYZ>);
  1036. pcl::copyPointCloud(*seedling_inbox, *inliers, *cloud_line);
  1037. pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("line in cluster"));
  1038. viewer->addPointCloud<pcl::PointXYZ>(seedling_inbox, "cluster");
  1039. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 1, 1, "cluster");
  1040. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "cluster");
  1041. viewer->addPointCloud(cloud_line, "fit_line");
  1042. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 0, 1, 0, "fit_line");
  1043. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "fit_line");
  1044. while (!viewer->wasStopped()) {
  1045. viewer->spinOnce(100);
  1046. }
  1047. }*/
  1048. }
  1049. }
  1050. void CRootStockGrabPoint::find_seedling_position_key(
  1051. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  1052. std::vector<int> &first_seedling_cloud_idx,
  1053. pcl::PointXYZ&xz_center,
  1054. pcl::ModelCoefficients::Ptr& line_model
  1055. )
  1056. {
  1057. // 确定植株inbox范围
  1058. float hole_step = m_cparam.rs_grab_seedling_dist - 5.0; //穴盘中穴间距
  1059. if (m_dtype == 0) {
  1060. hole_step = m_cparam.sc_grab_seedling_dist - 5.0;
  1061. }
  1062. float hole_step_radius = hole_step / 2.0;
  1063. // 点云降维到xz平面,y=0
  1064. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2d(new pcl::PointCloud < pcl::PointXYZ>);
  1065. pcl::copyPointCloud(*in_cloud, *cloud2d);
  1066. for (auto&pt : *cloud2d) {
  1067. pt.y = 0.0;
  1068. }
  1069. // 在xz平面内统计点的密度
  1070. double radius = m_cparam.rs_grab_stem_diameter;
  1071. if (m_dtype == 0) {
  1072. radius = m_cparam.sc_grab_stem_diameter;
  1073. }
  1074. std::vector<int> counter;
  1075. pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
  1076. kdtree.setInputCloud(cloud2d);
  1077. std::vector<int>idx;
  1078. std::vector<float>dist_sqr;
  1079. for (size_t i = 0; i < cloud2d->points.size(); ++i) {
  1080. int k = kdtree.radiusSearch(cloud2d->points.at(i), radius, idx, dist_sqr);
  1081. counter.push_back(k);
  1082. }
  1083. int max_density_idx = std::max_element(counter.begin(), counter.end()) - counter.begin();
  1084. int max_density = counter.at(max_density_idx);
  1085. if (m_cparam.image_show) {
  1086. //显示密度最大的点的位置
  1087. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_tmp(new pcl::PointCloud<pcl::PointXYZRGB>);
  1088. pcl::copyPointCloud(*in_cloud, *cloud_tmp);
  1089. for (auto& pt : *cloud_tmp) {
  1090. pt.r = 255;
  1091. pt.g = 255;
  1092. pt.b = 255;
  1093. }
  1094. std::vector<pcl::PointXYZ>cc;
  1095. cc.push_back(in_cloud->points.at(max_density_idx));
  1096. viewer_cloud_cluster(cloud_tmp, cc, string("key"));
  1097. }
  1098. // 生成植株的中心及box
  1099. std::vector<pcl::PointXYZ>clt_root;
  1100. std::vector<pcl::PointXYZ> clt_box;
  1101. float ymin = m_cparam.rs_grab_ymin;
  1102. float ymax = m_cparam.rs_grab_ymax;
  1103. if (m_dtype == 0) {
  1104. ymin = m_cparam.sc_grab_ymin;
  1105. ymax = m_cparam.sc_grab_ymax;
  1106. }
  1107. gen_all_seedling_positions(in_cloud->points.at(max_density_idx), clt_root);
  1108. // 显示生成的每一个候选框
  1109. /*if (m_cparam.image_show) {
  1110. std::vector<std::vector<int> > clt_line_idx;
  1111. std::vector<pcl::PointXYZ> clt_root_v;
  1112. std::vector<pcl::PointXYZ> clt_box_v;
  1113. for (auto&p : clt_root) {
  1114. pcl::PointXYZ p_show(p.x, ymin, p.z);
  1115. clt_root_v.push_back(p_show);
  1116. pcl::PointXYZ min_point_aabb_ex;
  1117. pcl::PointXYZ max_point_aabb_ex;
  1118. min_point_aabb_ex.x = p.x - hole_step_radius;
  1119. min_point_aabb_ex.y = ymin;
  1120. min_point_aabb_ex.z = p.z - hole_step_radius;
  1121. max_point_aabb_ex.x = p.x + hole_step_radius;
  1122. max_point_aabb_ex.y = ymax;
  1123. max_point_aabb_ex.z = p.z + hole_step_radius;
  1124. clt_box_v.push_back(min_point_aabb_ex);
  1125. clt_box_v.push_back(max_point_aabb_ex);
  1126. }
  1127. viewer_cloud_cluster_box(in_cloud, clt_root_v, clt_box_v, clt_line_idx, std::string("candidate_box"));
  1128. }*/
  1129. // 每个位置点云情况,过滤
  1130. std::vector<int> valid_index; //初步有效的矩形index
  1131. std::vector<int> valid_box_pts; //立方体内点云数量
  1132. std::vector<float>valid_box_cc_dist;//重心和矩形中心距离
  1133. for (size_t i = 0; i < clt_root.size();++i) {
  1134. pcl::PointXYZ &p = clt_root.at(i);
  1135. pcl::PointCloud<pcl::PointXYZ>::Ptr seedling_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  1136. pcl::CropBox<pcl::PointXYZ> box_filter;
  1137. std::vector<int>inbox_idx;
  1138. pcl::PointXYZ min_point_aabb_ex;
  1139. pcl::PointXYZ max_point_aabb_ex;
  1140. min_point_aabb_ex.x = p.x - hole_step_radius;
  1141. min_point_aabb_ex.y = ymin;
  1142. min_point_aabb_ex.z = p.z - hole_step_radius;
  1143. max_point_aabb_ex.x = p.x + hole_step_radius;
  1144. max_point_aabb_ex.y = ymax;
  1145. max_point_aabb_ex.z = p.z + hole_step_radius;
  1146. box_filter.setMin(Eigen::Vector4f(min_point_aabb_ex.x, min_point_aabb_ex.y, min_point_aabb_ex.z, 1));
  1147. box_filter.setMax(Eigen::Vector4f(max_point_aabb_ex.x, max_point_aabb_ex.y, max_point_aabb_ex.z, 1));
  1148. box_filter.setNegative(false);
  1149. box_filter.setInputCloud(in_cloud);
  1150. box_filter.filter(inbox_idx);
  1151. pcl::copyPointCloud(*in_cloud, inbox_idx, *seedling_inbox);
  1152. //点数过滤
  1153. if (inbox_idx.size() < int(max_density/3)) { continue; }
  1154. //y方向分布范围滤波
  1155. pcl::PointXYZ min_v;
  1156. pcl::PointXYZ max_v;
  1157. pcl::getMinMax3D(*seedling_inbox, min_v, max_v);
  1158. float dy = max_v.y - min_v.y;
  1159. if (dy / (ymax - ymin) < 0.35) { continue; }
  1160. //y方向分布中心滤波
  1161. float dy_c = 0.5*(max_v.y + min_v.y);
  1162. if ((dy_c-ymin) / (ymax - ymin) > 0.75) { continue; }
  1163. //计算中心
  1164. Eigen::Vector4f mean;
  1165. pcl::compute3DCentroid(*seedling_inbox, mean);
  1166. double cc_dist = std::sqrt((mean[0] - p.x)*(mean[0] - p.x) + (mean[2] - p.z)*(mean[2] - p.z));
  1167. valid_index.push_back(i);
  1168. valid_box_pts.push_back(inbox_idx.size());
  1169. valid_box_cc_dist.push_back((float)cc_dist);
  1170. }
  1171. // 找到局部最大值,找出真正的位置
  1172. std::vector<pcl::PointXYZ> clt_root_v;
  1173. std::vector<pcl::PointXYZ> clt_box_v;
  1174. for (auto&i : valid_index) {
  1175. pcl::PointXYZ&p = clt_root.at(i);
  1176. pcl::PointXYZ p_show(p.x, ymin, p.z);
  1177. clt_root_v.push_back(p_show);
  1178. pcl::PointXYZ min_point_aabb_ex;
  1179. pcl::PointXYZ max_point_aabb_ex;
  1180. min_point_aabb_ex.x = p.x - hole_step_radius;
  1181. min_point_aabb_ex.y = ymin;
  1182. min_point_aabb_ex.z = p.z - hole_step_radius;
  1183. max_point_aabb_ex.x = p.x + hole_step_radius;
  1184. max_point_aabb_ex.y = ymax;
  1185. max_point_aabb_ex.z = p.z + hole_step_radius;
  1186. clt_box_v.push_back(min_point_aabb_ex);
  1187. clt_box_v.push_back(max_point_aabb_ex);
  1188. }
  1189. // 显示
  1190. if (m_cparam.image_show) {
  1191. std::vector<std::vector<int> > clt_line_idx;
  1192. viewer_cloud_cluster_box(in_cloud, clt_root_v, clt_box_v, clt_line_idx, std::string("valid_box"));
  1193. }
  1194. std::vector<pcl::PointXYZ> target_root;
  1195. nms_box(clt_root_v, valid_box_cc_dist, hole_step_radius, target_root);
  1196. // 显示
  1197. if (m_cparam.image_show) {
  1198. std::vector<std::vector<int> > clt_line_idx;
  1199. std::vector<pcl::PointXYZ>clt_box_tmp;
  1200. for (auto&p : target_root) {
  1201. pcl::PointXYZ p_show(p.x, ymin, p.z);
  1202. clt_root_v.push_back(p_show);
  1203. pcl::PointXYZ min_point_aabb_ex;
  1204. pcl::PointXYZ max_point_aabb_ex;
  1205. min_point_aabb_ex.x = p.x - hole_step_radius;
  1206. min_point_aabb_ex.y = ymin;
  1207. min_point_aabb_ex.z = p.z - hole_step_radius;
  1208. max_point_aabb_ex.x = p.x + hole_step_radius;
  1209. max_point_aabb_ex.y = ymax;
  1210. max_point_aabb_ex.z = p.z + hole_step_radius;
  1211. clt_box_tmp.push_back(min_point_aabb_ex);
  1212. clt_box_tmp.push_back(max_point_aabb_ex);
  1213. }
  1214. viewer_cloud_cluster_box(in_cloud, target_root, clt_box_tmp, clt_line_idx, std::string("nms_box"));
  1215. }
  1216. // 根据得到的位置,直线检测,并过滤
  1217. std::vector<pcl::PointXYZ>target_filtered;
  1218. std::vector<std::vector<int>> target_member;//输出,茎上点index
  1219. std::vector<pcl::PointXYZ>target_filtered_root;
  1220. std::vector<pcl::ModelCoefficients::Ptr> target_filtered_models; //茎直线模型
  1221. line_filter(in_cloud, hole_step_radius,ymin,ymax, target_root, target_filtered,
  1222. target_filtered_root,
  1223. target_member,
  1224. target_filtered_models);
  1225. if (m_cparam.image_show) {
  1226. std::vector<pcl::PointXYZ> final_box;
  1227. for (auto&pt : target_filtered_root) {
  1228. //扩展矩形范围
  1229. pcl::PointXYZ min_point_aabb_ex;
  1230. pcl::PointXYZ max_point_aabb_ex;
  1231. min_point_aabb_ex.x = pt.x - hole_step_radius;
  1232. min_point_aabb_ex.y = ymin;
  1233. min_point_aabb_ex.z = pt.z - hole_step_radius;
  1234. max_point_aabb_ex.x = pt.x + hole_step_radius;
  1235. max_point_aabb_ex.y = ymax;
  1236. max_point_aabb_ex.z = pt.z + hole_step_radius;
  1237. final_box.push_back(min_point_aabb_ex);
  1238. final_box.push_back(max_point_aabb_ex);
  1239. }
  1240. viewer_cloud_cluster_box(in_cloud, target_filtered_root, final_box, target_member, std::string("line_filter"));
  1241. }
  1242. //sort cluster center, get the frontest leftest one
  1243. //找最小z,然后计算平均z
  1244. float min_root_z = 10000.0;
  1245. for(auto&pt : target_filtered_root) {
  1246. if (pt.z < min_root_z) { min_root_z = pt.z; }
  1247. }
  1248. //通过最小z,保守的找到和他一排的植株
  1249. std::vector<int> first_row_index;
  1250. float mean_z = 0.0;
  1251. for (int idx_r = 0; idx_r < target_filtered_root.size();++idx_r) {
  1252. pcl::PointXYZ&pt = target_filtered_root.at(idx_r);
  1253. if (std::fabs(pt.z - min_root_z) < hole_step) {
  1254. first_row_index.push_back(idx_r);
  1255. mean_z += pt.z;
  1256. }
  1257. }
  1258. //如果第一排的植株大于3,计算平均值
  1259. float first_row_num = (float)first_row_index.size();
  1260. mean_z /= first_row_num;
  1261. if (first_row_num >= 4) {
  1262. if (m_dtype == 0) {
  1263. m_1st_row_zmean_sc = mean_z;
  1264. }
  1265. else{ m_1st_row_zmean_rs = mean_z; }
  1266. }
  1267. else {
  1268. if( m_dtype == 0) {
  1269. if (m_1st_row_zmean_sc > 0) { mean_z = m_1st_row_zmean_sc; }
  1270. }
  1271. else {
  1272. if (m_1st_row_zmean_rs > 0) { mean_z = m_1st_row_zmean_rs; }
  1273. }
  1274. }
  1275. //通过mean_z再次寻找第一排的植株
  1276. first_row_index.clear();
  1277. for (int idx_r = 0; idx_r < target_filtered_root.size(); ++idx_r) {
  1278. pcl::PointXYZ&pt = target_filtered_root.at(idx_r);
  1279. if (std::fabs(pt.z - mean_z) < hole_step) {
  1280. first_row_index.push_back(idx_r);
  1281. }
  1282. }
  1283. std::vector<float> cluster_index;
  1284. for (int i=0; i<first_row_index.size();++i){
  1285. int raw_idx = first_row_index.at(i);
  1286. pcl::PointXYZ&pt = target_filtered_root.at(raw_idx);
  1287. cluster_index.push_back(pt.x);
  1288. }
  1289. int first_idx = std::min_element(cluster_index.begin(), cluster_index.end()) - cluster_index.begin();
  1290. if (m_dtype == 0) {
  1291. first_idx = std::max_element(cluster_index.begin(), cluster_index.end()) - cluster_index.begin();
  1292. }
  1293. first_idx = first_row_index.at(first_idx);
  1294. first_seedling_cloud_idx.clear();
  1295. for (auto&v : target_member.at(first_idx)) {
  1296. first_seedling_cloud_idx.push_back(v);
  1297. }
  1298. xz_center.x = target_filtered_root.at(first_idx).x;
  1299. xz_center.y = target_filtered_root.at(first_idx).y;
  1300. xz_center.z = target_filtered_root.at(first_idx).z;
  1301. line_model = target_filtered_models.at(first_idx);
  1302. if (m_pLogger) {
  1303. stringstream buff;
  1304. buff << m_pcdId << ": euclidean_clustering_ttsas, find cluster center(" << xz_center.x
  1305. <<", "<< xz_center.y<<", "<< xz_center.z<<")";
  1306. m_pLogger->INFO(buff.str());
  1307. }
  1308. }
  1309. void CRootStockGrabPoint::tilted_seedling_discover(
  1310. std::vector<pcl::PointXYZ>&cluster_center, //输入,已知的苗的坐标
  1311. std::vector<pcl::PointXYZ>&tilted_center //输出,有倾斜苗的坐标
  1312. )
  1313. {
  1314. tilted_center.clear();
  1315. if (cluster_center.size() == 0) { return; }
  1316. //找到z最小的那一株,并找出和它一排的那些
  1317. float step_harf = m_cparam.rs_grab_seedling_dist / 2.0;
  1318. float xmin = m_cparam.rs_grab_xmin;
  1319. float xmax = m_cparam.rs_grab_xmax;
  1320. float zmin = m_cparam.rs_grab_zmin;
  1321. float zmax = m_cparam.rs_grab_zmax;
  1322. if (m_dtype == 0) {
  1323. step_harf = m_cparam.sc_grab_seedling_dist / 2.0;
  1324. xmin = m_cparam.sc_grab_xmin;
  1325. xmax = m_cparam.sc_grab_xmax;
  1326. zmin = m_cparam.sc_grab_zmin;
  1327. zmax = m_cparam.sc_grab_zmax;
  1328. }
  1329. auto minz_it = std::min_element(cluster_center.begin(), cluster_center.end(),
  1330. [](const pcl::PointXYZ& p1, const pcl::PointXYZ& p2)-> bool {return p1.z < p2.z; });
  1331. float minz = minz_it->z;
  1332. float meanz = 0.0;
  1333. float cnt = 0.0;
  1334. for (auto&p : cluster_center) {
  1335. if (fabs(p.z - minz) < step_harf) { meanz += p.z; cnt += 1.0; }
  1336. }
  1337. if(cnt>0.0){meanz /= cnt;}
  1338. else { meanz = minz; }
  1339. // 生成所有可能的植株位置中心点
  1340. std::vector<pcl::PointXYZ>candidate_centers;
  1341. for (int row = -1; row <= 1; row += 1) {
  1342. for (int col = -6; col <= 6; col += 1) {
  1343. float cx = minz_it->x + col * 2.0 * step_harf;
  1344. float cz = meanz + row * 2.0 * step_harf;
  1345. if (cx < xmin || cx > xmax) { continue; }
  1346. if (cz < zmin || cz > zmax) { continue; }
  1347. // 邻域内已经存在植株的跳过
  1348. bool with_seedling = false;
  1349. for (auto&p : cluster_center) {
  1350. float d = std::sqrt((p.x - cx) * (p.x - cx) + (p.z - cz) * (p.z - cz));
  1351. if (d < 2.0*step_harf) {
  1352. with_seedling=true;
  1353. break;
  1354. }
  1355. }
  1356. if (!with_seedling) {//保存
  1357. pcl::PointXYZ pc(cx,0.0,cz);
  1358. candidate_centers.push_back(pc);
  1359. }
  1360. }
  1361. }
  1362. //针对每一个candidat_centers的邻域进行检查,检测是否有茎目标
  1363. for (auto&pc : candidate_centers) {
  1364. }
  1365. }
  1366. void CRootStockGrabPoint::find_seedling_position(
  1367. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  1368. std::vector<int> &first_seedling_cloud_idx,
  1369. pcl::PointXYZ&xz_center
  1370. )
  1371. {
  1372. // 确定植株inbox范围
  1373. float hole_step = m_cparam.rs_grab_seedling_dist - 10.0; //穴盘中穴间距
  1374. if (m_dtype == 0) {
  1375. hole_step = m_cparam.sc_grab_seedling_dist - 10.0;
  1376. }
  1377. float hole_step_radius = hole_step / 2.0;
  1378. // 点云降维到xz平面,y=0
  1379. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2d(new pcl::PointCloud < pcl::PointXYZ>);
  1380. pcl::copyPointCloud(*in_cloud, *cloud2d);
  1381. for (auto&pt : *cloud2d) {
  1382. pt.y = 0.0;
  1383. }
  1384. /*if(m_cparam.image_show){
  1385. viewer_cloud(cloud2d, std::string("cloud2d"));
  1386. } */
  1387. // 在xz平面内统计点的密度
  1388. double radius = m_cparam.rs_grab_stem_diameter;
  1389. if (m_dtype == 0) {
  1390. radius = m_cparam.sc_grab_stem_diameter;
  1391. }
  1392. std::vector<int> counter;
  1393. pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
  1394. kdtree.setInputCloud(cloud2d);
  1395. std::vector<int>idx;
  1396. std::vector<float>dist_sqr;
  1397. for (size_t i = 0; i < cloud2d->points.size(); ++i) {
  1398. int k = kdtree.radiusSearch(cloud2d->points.at(i), radius, idx, dist_sqr);
  1399. counter.push_back(k);
  1400. }
  1401. // 计算根据密度分割的自动阈值
  1402. int th = (int)(otsu(counter));
  1403. // 得到茎目标的点云序号,和对应的点云cloud2d_pos
  1404. std::vector<int> index;
  1405. for (size_t i = 0; i < counter.size(); ++i) {
  1406. if (counter.at(i) >= th) {
  1407. index.push_back(i);
  1408. }
  1409. }
  1410. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2d_pos(new pcl::PointCloud < pcl::PointXYZ>);
  1411. pcl::copyPointCloud(*cloud2d, index, *cloud2d_pos);
  1412. if (m_pLogger) {
  1413. stringstream buff;
  1414. buff << m_pcdId <<": get 2d seedling seed point cloud " << index.size() << " data points with thrreshold " << th;
  1415. m_pLogger->INFO(buff.str());
  1416. }
  1417. if (m_cparam.image_show) {
  1418. viewer_cloud(cloud2d_pos, std::string("cloud2d_pos"));
  1419. }
  1420. //对茎的点云进行clustering,得到不同的茎的分组
  1421. double d1 = m_cparam.rs_grab_stem_diameter;
  1422. double d2 = m_cparam.rs_grab_stem_diameter * 3.0;
  1423. if (m_dtype == 0) {
  1424. d1 = m_cparam.sc_grab_stem_diameter;
  1425. d2 = m_cparam.sc_grab_stem_diameter * 3.0;
  1426. }
  1427. std::vector<pcl::PointXYZ>cluster_center;
  1428. std::vector<std::vector<int>> cluster_member;
  1429. euclidean_clustering_ttsas(cloud2d_pos, d1, d2, cluster_center, cluster_member);
  1430. if (m_pLogger) {
  1431. stringstream buff;
  1432. buff << m_pcdId <<": euclidean_clustering_ttsas: " << cluster_center.size() << " t1=" << d1
  1433. << " t2=" << d2;
  1434. m_pLogger->INFO(buff.str());
  1435. }
  1436. if (m_cparam.image_show) {
  1437. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_cluster(new pcl::PointCloud<pcl::PointXYZRGB>);
  1438. pcl::copyPointCloud(*cloud2d_pos, *cloud_cluster);
  1439. for (auto& pt : *cloud_cluster) {
  1440. pt.r = 255;
  1441. pt.g = 255;
  1442. pt.b = 255;
  1443. }
  1444. viewer_cloud_cluster(cloud_cluster, cluster_center, std::string("cloud2d_cluster_pos"));
  1445. }
  1446. // 扩展检测第一排的可能位置,找到倾斜的苗
  1447. std::vector<pcl::PointXYZ> tilted_center;
  1448. tilted_seedling_discover(cluster_center, tilted_center);
  1449. //对每个类别进行检测,剔除不是茎的类别
  1450. std::vector<pcl::PointXYZ> clt_root;
  1451. std::vector<pcl::PointXYZ> clt_box;
  1452. std::vector<std::vector<int> > clt_line_idx;
  1453. for (size_t i = 0; i < cluster_center.size(); ++i) {
  1454. pcl::PointIndices cluster_idxs;
  1455. for (auto idx_clt : cluster_member.at(i)) {
  1456. int idx_raw = index.at(idx_clt);
  1457. cluster_idxs.indices.push_back(idx_raw);
  1458. }
  1459. pcl::PointCloud<pcl::PointXYZ>::Ptr clt_cloud(new pcl::PointCloud < pcl::PointXYZ>);
  1460. pcl::copyPointCloud(*in_cloud, cluster_idxs, *clt_cloud);
  1461. //计算每一个茎的外接矩形
  1462. pcl::PointXYZ min_point_aabb;
  1463. pcl::PointXYZ max_point_aabb;
  1464. pcl::MomentOfInertiaEstimation<pcl::PointXYZ> feature_extractor;
  1465. feature_extractor.setInputCloud(clt_cloud);
  1466. feature_extractor.compute();
  1467. feature_extractor.getAABB(min_point_aabb, max_point_aabb);
  1468. //扩展矩形范围
  1469. pcl::PointXYZ min_point_aabb_ex;
  1470. pcl::PointXYZ max_point_aabb_ex;
  1471. min_point_aabb_ex.x = 0.5*(min_point_aabb.x + max_point_aabb.x) - hole_step_radius;
  1472. min_point_aabb_ex.y = m_cparam.sc_grab_ymin;
  1473. if (m_dtype != 0) { min_point_aabb_ex.y = m_cparam.rs_grab_ymin; }
  1474. min_point_aabb_ex.z = 0.5*(min_point_aabb.z + max_point_aabb.z) - hole_step_radius;
  1475. max_point_aabb_ex.x = 0.5*(min_point_aabb.x + max_point_aabb.x) + hole_step_radius;
  1476. max_point_aabb_ex.y = m_cparam.sc_grab_ymax;
  1477. if (m_dtype != 0) { max_point_aabb_ex.y = m_cparam.rs_grab_ymax; }
  1478. max_point_aabb_ex.z = 0.5*(min_point_aabb.z + max_point_aabb.z) + hole_step_radius;
  1479. /////////////////////////////////
  1480. //扩展矩形内直线检测
  1481. std::vector<int>line_idx;
  1482. find_line_in_cube(in_cloud, min_point_aabb_ex, max_point_aabb_ex, line_idx);
  1483. clt_line_idx.push_back(line_idx);
  1484. //找到line_idx中y最小的那个点的idx
  1485. int line_root_idx = -1;
  1486. float line_root_y_min = 10000.0;
  1487. for (size_t lidx = 0; lidx < line_idx.size(); ++lidx) {
  1488. int raw_idx = line_idx.at(lidx);
  1489. if (in_cloud->at(raw_idx).y < line_root_y_min) {
  1490. line_root_y_min = in_cloud->at(raw_idx).y;
  1491. line_root_idx = raw_idx;
  1492. }
  1493. }
  1494. //找到底部中心点,然后找到根部坐标
  1495. pcl::PointXYZ pt_root;
  1496. pt_root = in_cloud->at(line_root_idx);
  1497. clt_root.push_back(pt_root);
  1498. clt_box.push_back(min_point_aabb_ex);
  1499. clt_box.push_back(max_point_aabb_ex);
  1500. //viewer_cloud(clt_cloud, std::string("cluster"));
  1501. }
  1502. if (m_cparam.image_show) {
  1503. viewer_cloud_cluster_box(in_cloud, clt_root, clt_box, clt_line_idx, std::string("cloud2d_cluster_box"));
  1504. }
  1505. //sort cluster center, get the frontest leftest one
  1506. std::vector<float> cluster_index;
  1507. for (auto&pt : clt_root) {
  1508. float idx = pt.x - pt.z;
  1509. cluster_index.push_back(idx);
  1510. }
  1511. int first_idx = std::min_element(cluster_index.begin(), cluster_index.end()) - cluster_index.begin();
  1512. if (m_dtype == 0) {
  1513. first_idx = std::max_element(cluster_index.begin(), cluster_index.end()) - cluster_index.begin();
  1514. }
  1515. first_seedling_cloud_idx.clear();
  1516. for (auto&v : clt_line_idx.at(first_idx)) {
  1517. first_seedling_cloud_idx.push_back(v);
  1518. }
  1519. xz_center.x = clt_root.at(first_idx).x;
  1520. xz_center.y = clt_root.at(first_idx).y;
  1521. xz_center.z = clt_root.at(first_idx).z;
  1522. if (m_pLogger) {
  1523. stringstream buff;
  1524. buff << m_pcdId <<": euclidean_clustering_ttsas, find cluster center(" << xz_center.x
  1525. << ", " << xz_center.y << ", " << xz_center.z << ")";
  1526. m_pLogger->INFO(buff.str());
  1527. }
  1528. }
  1529. void CRootStockGrabPoint::find_line_in_cube(
  1530. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, //输入,整体点云
  1531. pcl::PointXYZ& min_pt_ex, //输入,
  1532. pcl::PointXYZ& max_pt_ex, //输入,
  1533. std::vector<int>& out_idx //输出,直线上点的index, 基于输入整体点云
  1534. )
  1535. {
  1536. out_idx.clear();
  1537. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  1538. pcl::CropBox<pcl::PointXYZ> box_filter;
  1539. std::vector<int>inbox_idx;
  1540. box_filter.setMin(Eigen::Vector4f(min_pt_ex.x, min_pt_ex.y, min_pt_ex.z, 1));
  1541. box_filter.setMax(Eigen::Vector4f(max_pt_ex.x, max_pt_ex.y, max_pt_ex.z, 1));
  1542. box_filter.setNegative(false);
  1543. box_filter.setInputCloud(in_cloud);
  1544. box_filter.filter(inbox_idx);
  1545. pcl::copyPointCloud(*in_cloud, inbox_idx, *cloud_inbox);
  1546. //找到inbox点云中的直线
  1547. float stem_radius = m_cparam.rs_grab_stem_diameter / 2.0;
  1548. if (m_dtype == 0) {
  1549. stem_radius = m_cparam.sc_grab_stem_diameter / 2.0;
  1550. }
  1551. pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
  1552. pcl::PointIndices::Ptr inliers(new pcl::PointIndices);
  1553. pcl::SACSegmentation<pcl::PointXYZ> seg;
  1554. seg.setOptimizeCoefficients(true);
  1555. seg.setModelType(pcl::SACMODEL_LINE);
  1556. seg.setDistanceThreshold(stem_radius);
  1557. seg.setInputCloud(cloud_inbox);
  1558. seg.segment(*inliers, *coefficients);
  1559. int idx_raw = 0;
  1560. for (auto& idx : inliers->indices) {
  1561. idx_raw = inbox_idx.at(idx);
  1562. out_idx.push_back(idx_raw);
  1563. }
  1564. if (m_cparam.image_show) {
  1565. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_line(new pcl::PointCloud<pcl::PointXYZ>);
  1566. pcl::copyPointCloud(*cloud_inbox, *inliers, *cloud_line);
  1567. pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("line in cluster"));
  1568. viewer->addPointCloud<pcl::PointXYZ>(cloud_inbox, "cluster");
  1569. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 1, 1, "cluster");
  1570. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "cluster");
  1571. viewer->addPointCloud(cloud_line, "fit_line");
  1572. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 0, 1, 0, "fit_line");
  1573. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "fit_line");
  1574. while (!viewer->wasStopped()) {
  1575. viewer->spinOnce(100);
  1576. }
  1577. }
  1578. }
  1579. void CRootStockGrabPoint::crop_nn_analysis(
  1580. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  1581. pcl::PointCloud<pcl::PointXYZ>::Ptr seed_cloud,
  1582. double dist_mean,
  1583. std::vector<double>&mass_indices,
  1584. std::vector<int>& candidate_idx
  1585. )
  1586. {
  1587. candidate_idx.clear();
  1588. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  1589. pcl::CropBox<pcl::PointXYZ> box_filter;
  1590. box_filter.setNegative(false);
  1591. box_filter.setInputCloud(in_cloud);
  1592. double radius = 5;
  1593. double rx = 0.8;
  1594. double ry = 1.0;
  1595. double rz = 0.8;
  1596. double cx, cy, cz;
  1597. double dz;
  1598. for (size_t i = 0; i < seed_cloud->points.size(); ++i) {
  1599. cx = seed_cloud->points.at(i).x;
  1600. cy = seed_cloud->points.at(i).y;
  1601. cz = seed_cloud->points.at(i).z;
  1602. box_filter.setMin(Eigen::Vector4f(cx - rx*radius, cy - ry*radius, cz - rz*radius, 1));
  1603. box_filter.setMax(Eigen::Vector4f(cx + rx*radius, cy + ry*radius, cz + rz*radius, 1));
  1604. box_filter.filter(*cloud_inbox);
  1605. //dz
  1606. Eigen::Vector4f min_point;
  1607. Eigen::Vector4f max_point;
  1608. pcl::getMinMax3D(*cloud_inbox, min_point, max_point);
  1609. dz = max_point(2) - min_point(2);
  1610. //project to xy-plane
  1611. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox_xy(new pcl::PointCloud<pcl::PointXYZ>);
  1612. pcl::copyPointCloud(*cloud_inbox, *cloud_inbox_xy);
  1613. for (auto&pt : *cloud_inbox_xy) { pt.z = 0.0; }
  1614. //pca
  1615. double dx_obb;
  1616. double dy_obb;
  1617. double angle_obb;
  1618. cal_obb_2d(cloud_inbox_xy, 0, dx_obb, dy_obb, angle_obb);
  1619. try {
  1620. double dx_grid = dx_obb / dist_mean;
  1621. double dy_grid = dy_obb / dist_mean;
  1622. double dz_grid = dz / dist_mean;
  1623. double fill_ratio = cloud_inbox->points.size() / dx_grid / dy_grid / dz_grid;
  1624. double y_ratio = dy_obb / dx_obb/2;
  1625. y_ratio = pow(y_ratio, 2);
  1626. double a_ratio = cos((angle_obb - 90)*PI / 180.0);
  1627. a_ratio = pow(a_ratio, 3);
  1628. double mass_index = fill_ratio*y_ratio*a_ratio;
  1629. mass_indices.push_back(mass_index);
  1630. if (m_pLogger) {
  1631. stringstream buff;
  1632. buff << i << "/" << seed_cloud->points.size() << " dx=" << dx_obb << ", dy=" << dy_obb << ", fill_ratio=" << fill_ratio
  1633. << ", y_ratio=" << y_ratio << ", a_ratio=" << a_ratio << ", mass_index=" << mass_index;
  1634. m_pLogger->INFO(buff.str());
  1635. }
  1636. }
  1637. catch (...) {
  1638. mass_indices.push_back(0);
  1639. }
  1640. }
  1641. // sort by mass_indices
  1642. std::vector<size_t> sort_idx = sort_indexes_e(mass_indices, false);
  1643. for (auto&v : sort_idx) { candidate_idx.push_back((int)v); }
  1644. }
  1645. void CRootStockGrabPoint::euclidean_clustering_ttsas(
  1646. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  1647. double d1, double d2,
  1648. std::vector<pcl::PointXYZ>&cluster_center,
  1649. std::vector<std::vector<int>> &clustr_member
  1650. )
  1651. {
  1652. if (m_pLogger) {
  1653. stringstream buff;
  1654. buff << m_pcdId <<": euclidean_clustering_ttsas() begin...";
  1655. m_pLogger->INFO(buff.str());
  1656. }
  1657. std::vector<int> cluster_weight;
  1658. std::vector<int> data_stat;
  1659. std::vector<pcl::PointXYZ>cluster_center_raw;
  1660. std::vector<std::vector<int>> clustr_member_raw;
  1661. for (size_t i = 0; i < in_cloud->points.size(); ++i) { data_stat.push_back(0); }
  1662. size_t data_len = in_cloud->points.size();
  1663. int exists_change = 0;
  1664. int prev_change = 0;
  1665. int cur_change = 0;
  1666. int m = 0;
  1667. while (std::find(data_stat.begin(), data_stat.end(), 0) != data_stat.end()) {
  1668. bool new_while_first = true;
  1669. for (size_t i = 0; i < data_len; ++i) {
  1670. if (data_stat.at(i) == 0 && new_while_first && exists_change == 0) {
  1671. new_while_first = false;
  1672. std::vector<int> idx;
  1673. idx.push_back(i);
  1674. clustr_member_raw.push_back(idx);
  1675. pcl::PointXYZ center;
  1676. center.x = in_cloud->points.at(i).x;
  1677. center.y = in_cloud->points.at(i).y;
  1678. center.z = in_cloud->points.at(i).z;
  1679. cluster_center_raw.push_back(center);
  1680. data_stat.at(i) = 1;
  1681. cur_change += 1;
  1682. cluster_weight.push_back(1);
  1683. m += 1;
  1684. }
  1685. else if (data_stat[i] == 0) {
  1686. std::vector<float> distances;
  1687. for (size_t j = 0; j < clustr_member_raw.size(); ++j) {
  1688. std::vector<float> distances_sub;
  1689. for (size_t jj = 0; jj < clustr_member_raw.at(j).size(); ++jj) {
  1690. size_t ele_idx = clustr_member_raw.at(j).at(jj);
  1691. double d = sqrt(
  1692. (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) +
  1693. (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) +
  1694. (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));
  1695. distances_sub.push_back(d);
  1696. }
  1697. double min_dist = *std::min_element(distances_sub.begin(), distances_sub.end());
  1698. distances.push_back(min_dist);
  1699. }
  1700. int min_idx = std::min_element(distances.begin(), distances.end()) - distances.begin();
  1701. if (distances.at(min_idx) < d1) {
  1702. data_stat.at(i) = 1;
  1703. double w = cluster_weight.at(min_idx);
  1704. cluster_weight.at(min_idx) += 1;
  1705. clustr_member_raw.at(min_idx).push_back(i);
  1706. cluster_center_raw.at(min_idx).x = (cluster_center_raw.at(min_idx).x * w + in_cloud->points.at(i).x) / (w + 1);
  1707. cluster_center_raw.at(min_idx).y = (cluster_center_raw.at(min_idx).y * w + in_cloud->points.at(i).y) / (w + 1);
  1708. cluster_center_raw.at(min_idx).z = (cluster_center_raw.at(min_idx).z * w + in_cloud->points.at(i).z) / (w + 1);
  1709. cur_change += 1;
  1710. }
  1711. else if (distances.at(min_idx) > d2) {
  1712. std::vector<int> idx;
  1713. idx.push_back(i);
  1714. clustr_member_raw.push_back(idx);
  1715. pcl::PointXYZ center;
  1716. center.x = in_cloud->points.at(i).x;
  1717. center.y = in_cloud->points.at(i).y;
  1718. center.z = in_cloud->points.at(i).z;
  1719. cluster_center_raw.push_back(center);
  1720. data_stat.at(i) = 1;
  1721. cur_change += 1;
  1722. cluster_weight.push_back(1);
  1723. m += 1;
  1724. }
  1725. }
  1726. else if (data_stat.at(i)== 1) {
  1727. cur_change += 1;
  1728. }
  1729. }
  1730. exists_change = fabs(cur_change - prev_change);
  1731. prev_change = cur_change;
  1732. cur_change = 0;
  1733. }
  1734. // copy result
  1735. for (size_t i = 0; i < clustr_member_raw.size(); ++i) {
  1736. if (clustr_member_raw.at(i).size() < 20) { continue; }
  1737. cluster_center.push_back(cluster_center_raw.at(i));
  1738. clustr_member.push_back(clustr_member_raw.at(i));
  1739. }
  1740. if (m_pLogger) {
  1741. stringstream buff;
  1742. buff << m_pcdId <<": euclidean_clustering_ttsas() end";
  1743. m_pLogger->INFO(buff.str());
  1744. }
  1745. }
  1746. void CRootStockGrabPoint::cal_obb_2d(
  1747. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  1748. int axis, //0--xy, 1--zy
  1749. double &dx_obb,
  1750. double &dy_obb,
  1751. double &angle_obb
  1752. )
  1753. {
  1754. // asign value
  1755. Eigen::MatrixXd pts(in_cloud->points.size(), 2);
  1756. for (size_t i = 0; i < in_cloud->points.size(); ++i) {
  1757. if (axis == 0) {
  1758. pts(i, 0) = in_cloud->points.at(i).x;
  1759. }
  1760. else {
  1761. pts(i, 0) = in_cloud->points.at(i).z;
  1762. }
  1763. pts(i, 1) = in_cloud->points.at(i).y;
  1764. }
  1765. // centerlize
  1766. Eigen::MatrixXd mu = pts.colwise().mean();
  1767. Eigen::RowVectorXd mu_row = mu;
  1768. pts.rowwise() -= mu_row;
  1769. //calculate covariance
  1770. Eigen::MatrixXd C = pts.adjoint()*pts;
  1771. C = C.array() / (pts.cols() - 1);
  1772. //compute eig
  1773. Eigen::SelfAdjointEigenSolver<Eigen::MatrixXd> eig(C);
  1774. Eigen::MatrixXd d = eig.eigenvalues();
  1775. Eigen::MatrixXd v = eig.eigenvectors();
  1776. //projection
  1777. Eigen::MatrixXd p = pts * v;
  1778. Eigen::VectorXd minv = p.colwise().minCoeff();
  1779. Eigen::VectorXd maxv = p.colwise().maxCoeff();
  1780. Eigen::VectorXd range = maxv - minv;
  1781. dy_obb = range(1);
  1782. dx_obb = range(0);
  1783. angle_obb = std::atan2(v(1, 1), v(0, 1));
  1784. if (angle_obb < 0) { angle_obb = PI + angle_obb; }
  1785. angle_obb = angle_obb * 180 / PI;
  1786. }
  1787. //void CRootStockGrabPoint::get_optimal_seed(
  1788. // pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  1789. // pcl::PointXYZ&pt,
  1790. // int &pt_idx)
  1791. //{
  1792. // double d1 = m_cparam.rs_grab_stem_diameter;
  1793. // double d2 = m_cparam.rs_grab_stem_diameter * 4.0;
  1794. // if (m_dtype != 0) {
  1795. // d1 = m_cparam.sc_grab_stem_diameter;
  1796. // d2 = m_cparam.sc_grab_stem_diameter * 4.0;
  1797. // }
  1798. // std::vector<pcl::PointXYZ>cluster_center;
  1799. // std::vector<std::vector<int>> cluster_member;
  1800. // euclidean_clustering_ttsas(in_cloud, d1, d2, cluster_center, cluster_member);
  1801. // float min_y_dist = 1.0e6;
  1802. // int opt_idx = -1;
  1803. // int member_size = 5;
  1804. // float y_opt = m_cparam.rs_grab_y_opt;
  1805. // if (m_dtype != 0) {
  1806. // y_opt = m_cparam.sc_grab_y_opt;
  1807. // }
  1808. // for (int i = 0; i < cluster_member.size(); ++i) {
  1809. // if (cluster_member.at(i).size() < member_size) {
  1810. // continue;
  1811. // }
  1812. // if (fabs(cluster_center.at(i).y -y_opt) < min_y_dist) {
  1813. // min_y_dist = fabs(cluster_center.at(i).y - y_opt);
  1814. // opt_idx = i;
  1815. // }
  1816. // }
  1817. // if (opt_idx < 0) {
  1818. // if (m_pLogger) {
  1819. // stringstream buff;
  1820. // buff << "get_optimal_seed failed, get invalid optimal cluster id";
  1821. // m_pLogger->ERRORINFO(buff.str());
  1822. // }
  1823. // return;
  1824. // }
  1825. // //find nearest pt
  1826. // float nearest_dist = 1.0e6;
  1827. // int nearest_idx = -1;
  1828. // for (int i = 0; i < cluster_member.at(opt_idx).size(); ++i) {
  1829. // int idx = cluster_member.at(opt_idx).at(i);
  1830. // float dist = fabs(in_cloud->points.at(idx).x - cluster_center.at(opt_idx).x) +
  1831. // fabs(in_cloud->points.at(idx).y - cluster_center.at(opt_idx).y) +
  1832. // fabs(in_cloud->points.at(idx).z - cluster_center.at(opt_idx).z);
  1833. // if (dist < nearest_dist) {
  1834. // nearest_dist = dist;
  1835. // nearest_idx = idx;
  1836. // }
  1837. // }
  1838. // pt.x = in_cloud->points.at(nearest_idx).x;
  1839. // pt.y = in_cloud->points.at(nearest_idx).y;
  1840. // pt.z = in_cloud->points.at(nearest_idx).z;
  1841. // pt_idx = nearest_idx;
  1842. //}
  1843. void CRootStockGrabPoint::get_optimal_seed(
  1844. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  1845. pcl::PointXYZ&pt,
  1846. int &pt_idx)
  1847. {
  1848. /*double d1 = m_cparam.rs_grab_stem_diameter;
  1849. double d2 = m_cparam.rs_grab_stem_diameter * 4.0;
  1850. if (m_dtype != 0) {
  1851. d1 = m_cparam.sc_grab_stem_diameter;
  1852. d2 = m_cparam.sc_grab_stem_diameter * 4.0;
  1853. }
  1854. std::vector<pcl::PointXYZ>cluster_center;
  1855. std::vector<std::vector<int>> cluster_member;
  1856. euclidean_clustering_ttsas(in_cloud, d1, d2, cluster_center, cluster_member);*/
  1857. float min_y_dist = 1.0e6;
  1858. int opt_idx = -1;
  1859. int member_size = 5;
  1860. float y_opt = m_cparam.rs_grab_y_opt;
  1861. if (m_dtype == 0) {
  1862. y_opt = m_cparam.sc_grab_y_opt;
  1863. }
  1864. for (int i = 0; i < in_cloud->points.size(); ++i) {
  1865. /*if (cluster_member.at(i).size() < member_size) {
  1866. continue;
  1867. }*/
  1868. if (fabs(in_cloud->points.at(i).y - y_opt) < min_y_dist) {
  1869. min_y_dist = fabs(in_cloud->points.at(i).y - y_opt);
  1870. opt_idx = i;
  1871. }
  1872. }
  1873. if (opt_idx < 0) {
  1874. if (m_pLogger) {
  1875. stringstream buff;
  1876. buff << m_pcdId <<": get_optimal_seed failed, get invalid optimal cluster id";
  1877. m_pLogger->ERRORINFO(buff.str());
  1878. }
  1879. return;
  1880. }
  1881. //find nearest pt
  1882. /*float nearest_dist = 1.0e6;
  1883. int nearest_idx = -1;
  1884. for (int i = 0; i < cluster_member.at(opt_idx).size(); ++i) {
  1885. int idx = cluster_member.at(opt_idx).at(i);
  1886. float dist = fabs(in_cloud->points.at(idx).x - cluster_center.at(opt_idx).x) +
  1887. fabs(in_cloud->points.at(idx).y - cluster_center.at(opt_idx).y) +
  1888. fabs(in_cloud->points.at(idx).z - cluster_center.at(opt_idx).z);
  1889. if (dist < nearest_dist) {
  1890. nearest_dist = dist;
  1891. nearest_idx = idx;
  1892. }
  1893. }*/
  1894. pt.x = in_cloud->points.at(opt_idx).x;
  1895. pt.y = in_cloud->points.at(opt_idx).y;
  1896. pt.z = in_cloud->points.at(opt_idx).z;
  1897. pt_idx = opt_idx;
  1898. }
  1899. //通过比较直线点云和原始点云相同位置邻域内xz的范围,确定此点是否是无干扰点的茎
  1900. //void CRootStockGrabPoint::get_optimal_seed_compare(
  1901. // pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, // 全部有效点云
  1902. // pcl::PointCloud<pcl::PointXYZ>::Ptr in_line_cloud, // 茎上直线点云
  1903. // pcl::PointXYZ&pt, // 返回抓取的点坐标
  1904. // int &pt_idx, // 返回点index
  1905. // std::vector<int>& valid_line_index // 返回有效直线点index
  1906. //)
  1907. //{
  1908. // valid_line_index.clear();
  1909. // float th = 0.75; //原始点云和直线点云邻域尺寸增加原来的20%,不能当做抓取点
  1910. // pt_idx = -1;
  1911. // pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  1912. // pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox_line(new pcl::PointCloud<pcl::PointXYZ>);
  1913. // pcl::CropBox<pcl::PointXYZ> box_filter;
  1914. // box_filter.setNegative(false);
  1915. // box_filter.setInputCloud(in_cloud);
  1916. // pcl::CropBox<pcl::PointXYZ> box_filter_line;
  1917. // box_filter_line.setNegative(false);
  1918. // box_filter_line.setInputCloud(in_line_cloud);
  1919. // float radius = m_cparam.rs_grab_stem_diameter;
  1920. // float opt_y = m_cparam.rs_grab_y_opt;
  1921. // if (m_dtype == 0) {
  1922. // radius = m_cparam.sc_grab_stem_diameter;
  1923. // opt_y = m_cparam.sc_grab_y_opt;
  1924. // }
  1925. // float rx = 1.5;
  1926. // float ry = 1.5;
  1927. // float rz = 1.5;
  1928. // float cx, cy, cz;
  1929. // float dz,dx, dz_line, dx_line;
  1930. // float dist_min = 10000.0;
  1931. // for (size_t i = 0; i < in_line_cloud->points.size(); ++i) {
  1932. // cx = in_line_cloud->points.at(i).x;
  1933. // cy = in_line_cloud->points.at(i).y;
  1934. // cz = in_line_cloud->points.at(i).z;
  1935. // //////////////////////////////////////////////////////////////////
  1936. // //原始点云,获取指定区域的dx,dz
  1937. // box_filter.setMin(Eigen::Vector4f(cx - rx*radius, cy - ry*radius, cz - rz*radius, 1));
  1938. // box_filter.setMax(Eigen::Vector4f(cx + rx*radius, cy + ry*radius, cz + rz*radius, 1));
  1939. // box_filter.filter(*cloud_inbox);
  1940. // Eigen::Vector4f min_point;
  1941. // Eigen::Vector4f max_point;
  1942. // pcl::getMinMax3D(*cloud_inbox, min_point, max_point);
  1943. // dz = max_point(2) - min_point(2);
  1944. // dx = max_point(0) - min_point(0);
  1945. // /////////////////////////////////////////////////////////////////////
  1946. // //直线点云,获取指定区域的dx_line,dz_line
  1947. // box_filter_line.setMin(Eigen::Vector4f(cx - rx*radius, cy - ry*radius, cz - rz*radius, 1));
  1948. // box_filter_line.setMax(Eigen::Vector4f(cx + rx*radius, cy + ry*radius, cz + rz*radius, 1));
  1949. // box_filter_line.filter(*cloud_inbox_line);
  1950. // pcl::getMinMax3D(*cloud_inbox_line, min_point, max_point);
  1951. // dz_line = max_point(2) - min_point(2);
  1952. // dx_line = max_point(0) - min_point(0);
  1953. // float ratio_ex = (dx + dz - dz_line - dx_line) / (dz_line + dx_line);
  1954. // if (ratio_ex > th) {
  1955. // valid_line_index.push_back(i);
  1956. // if (fabs(cy - opt_y) < dist_min) {
  1957. // dist_min = fabs(cy - opt_y);
  1958. // pt_idx = i;
  1959. // }
  1960. // }
  1961. // }
  1962. // if (pt_idx >= 0) {
  1963. // pt = in_line_cloud->points.at(pt_idx);
  1964. // }
  1965. //
  1966. //}
  1967. void CRootStockGrabPoint::get_optimal_seed_compare(
  1968. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, //input 全部有效点云
  1969. pcl::PointCloud<pcl::PointXYZ>::Ptr in_line_cloud, //input 茎上直线点云
  1970. pcl::ModelCoefficients::Ptr line_model, //input
  1971. pcl::PointXYZ&pt, // 返回抓取的点坐标
  1972. int &pt_idx, // 返回点index
  1973. std::vector<int>& valid_line_index // 返回有效直线点index
  1974. )
  1975. {
  1976. valid_line_index.clear();
  1977. float th_ratio = 1.0; //原始点云和直线点云邻域尺寸增加原来的20%,不能当做抓取点
  1978. pt_idx = -1;
  1979. float ymin, ymax;
  1980. ymin = m_cparam.rs_grab_ymin;
  1981. ymax = m_cparam.rs_grab_ymax;
  1982. if (m_dtype == 0) {
  1983. ymin = m_cparam.sc_grab_ymin;
  1984. ymax = m_cparam.sc_grab_ymax;
  1985. }
  1986. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  1987. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox_line(new pcl::PointCloud<pcl::PointXYZ>);
  1988. std::vector<float> stem_width;
  1989. std::vector<pcl::PointXYZ>online_points;
  1990. pcl::CropBox<pcl::PointXYZ> box_filter;
  1991. box_filter.setNegative(false);
  1992. box_filter.setInputCloud(in_cloud);
  1993. pcl::CropBox<pcl::PointXYZ> box_filter_line;
  1994. box_filter_line.setNegative(false);
  1995. box_filter_line.setInputCloud(in_line_cloud);
  1996. float radius = m_cparam.rs_grab_stem_diameter;
  1997. float opt_y = m_cparam.rs_grab_y_opt;
  1998. if (m_dtype == 0) {
  1999. radius = m_cparam.sc_grab_stem_diameter;
  2000. opt_y = m_cparam.sc_grab_y_opt;
  2001. }
  2002. float rx = 1.5;
  2003. float ry = 1.5;
  2004. float rz = 1.5;
  2005. float cx, cy, cz, t;
  2006. float dz, dx;
  2007. cy = ymin;
  2008. while(cy<ymax){
  2009. t = (cy - line_model->values.at(1)) / line_model->values.at(4);
  2010. cx = line_model->values.at(3) * t + line_model->values.at(0);
  2011. cz = line_model->values.at(5) * t + line_model->values.at(2);
  2012. //////////////////////////////////////////////////////////////////
  2013. //原始点云,获取指定区域的dx,dz
  2014. box_filter.setMin(Eigen::Vector4f(cx - rx*radius, cy - 2, cz - rz*radius, 1));
  2015. box_filter.setMax(Eigen::Vector4f(cx + rx*radius, cy + 2, cz + rz*radius, 1));
  2016. box_filter.filter(*cloud_inbox);
  2017. if (cloud_inbox->points.size() > 10) {
  2018. Eigen::Vector4f min_point;
  2019. Eigen::Vector4f max_point;
  2020. pcl::getMinMax3D(*cloud_inbox, min_point, max_point);
  2021. dz = max_point(2) - min_point(2);
  2022. dx = max_point(0) - min_point(0);
  2023. if (dx > dz) {
  2024. stem_width.push_back(dx);
  2025. }
  2026. else {
  2027. stem_width.push_back(dz);
  2028. }
  2029. }
  2030. else {
  2031. stem_width.push_back(0);
  2032. }
  2033. pcl::PointXYZ tmp_pt(cx,cy,cz);
  2034. online_points.push_back(tmp_pt);
  2035. cy += 1.0;
  2036. }
  2037. std::vector<float>valid_stem_width;
  2038. for (auto&w : stem_width) { valid_stem_width.push_back(w); }
  2039. float mu = get_hist_mean(valid_stem_width);
  2040. float stdv = get_hist_std(valid_stem_width, mu);
  2041. int max_pos = std::max_element(stem_width.begin(), stem_width.end()) - stem_width.begin();
  2042. float max_val = stem_width.at(max_pos);
  2043. float th = mu + th_ratio * stdv;
  2044. if (th < max_val) {
  2045. int i = 0;
  2046. for (; i < stem_width.size(); ++i) {
  2047. if (stem_width.at(i) >= th) {
  2048. break;
  2049. }
  2050. }
  2051. max_pos = i;
  2052. }
  2053. /////////////////////////////////////////////////////////////////////
  2054. //直线点云,获取指定区域的dx_line,dz_line
  2055. Eigen::Vector4f min_point;
  2056. Eigen::Vector4f max_point;
  2057. cx = online_points.at(max_pos).x;
  2058. cy = online_points.at(max_pos).y;
  2059. cz = online_points.at(max_pos).z;
  2060. box_filter_line.setMin(Eigen::Vector4f(cx - rx*radius, cy - 2, cz - rz*radius, 1));
  2061. box_filter_line.setMax(Eigen::Vector4f(cx + rx*radius, cy + 2, cz + rz*radius, 1));
  2062. box_filter_line.filter(*cloud_inbox_line);
  2063. pcl::getMinMax3D(*cloud_inbox_line, min_point, max_point);
  2064. float z_mu = 0.5 * (max_point(2) + min_point(2));
  2065. float x_mu = 0.5 * (max_point(0) + min_point(0));
  2066. pt.x = x_mu;
  2067. pt.y = cy;
  2068. pt.z = z_mu;
  2069. pt_idx = max_pos;
  2070. //显示位置
  2071. if (m_cparam.image_show) {
  2072. pcl::visualization::PCLVisualizer viewer("grab line");
  2073. viewer.addCoordinateSystem();
  2074. viewer.addPointCloud<pcl::PointXYZ>(in_line_cloud, "stem_cloud");//????????????????
  2075. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 1, 1, "stem_cloud");
  2076. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "stem_cloud");
  2077. viewer.addLine(online_points.front(), online_points.back(), 1.0, 0.0, 0.0);
  2078. while (!viewer.wasStopped()) {
  2079. viewer.spinOnce(100);
  2080. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  2081. }
  2082. }
  2083. }
  2084. void CRootStockGrabPoint::viewer_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, std::string&winname)
  2085. {
  2086. pcl::visualization::CloudViewer viewer(winname);
  2087. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  2088. viewer.showCloud(cloud);
  2089. while (!viewer.wasStopped()) {
  2090. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  2091. }
  2092. }
  2093. void CRootStockGrabPoint::viewer_cloud(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud, std::string&winname)
  2094. {
  2095. pcl::visualization::CloudViewer viewer(winname);
  2096. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  2097. viewer.showCloud(cloud);
  2098. while (!viewer.wasStopped()) {
  2099. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  2100. }
  2101. }
  2102. void CRootStockGrabPoint::viewer_cloud_debug(
  2103. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
  2104. pcl::PointXYZ &p,
  2105. pcl::PointXYZ &root_pt,
  2106. std::string&winname)
  2107. {
  2108. pcl::visualization::PCLVisualizer viewer(winname);
  2109. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  2110. viewer.addPointCloud(cloud);
  2111. viewer.addCoordinateSystem();
  2112. pcl::PointXYZ p0, x1, y1,p00,x0,y0, root_px0, root_px1, root_py0,root_py1;
  2113. p0.x = p.x;
  2114. p0.y = p.y;
  2115. p0.z = p.z;
  2116. x1.x = p.x + 100.0;
  2117. x1.y = p.y;
  2118. x1.z = p.z;
  2119. y1.x = p.x;
  2120. y1.y = p.y + 20.0;
  2121. y1.z = p.z;
  2122. p00.x = 0.0;
  2123. p00.y = 0.0;
  2124. p00.z = p.z;
  2125. x0.x = 600.0;
  2126. x0.y = 0;
  2127. x0.z = p.z;
  2128. y0.x = 0.0;
  2129. y0.y = 300.0;
  2130. y0.z = p.z;
  2131. root_px0.x = root_pt.x - 5.0;
  2132. root_px0.y = root_pt.y;
  2133. root_px0.z = root_pt.z;
  2134. root_px1.x = root_pt.x + 5.0;
  2135. root_px1.y = root_pt.y;
  2136. root_px1.z = root_pt.z;
  2137. root_py0.x = root_pt.x;
  2138. root_py0.y = root_pt.y - 5.0;
  2139. root_py0.z = root_pt.z;
  2140. root_py1.x = root_pt.x;
  2141. root_py1.y = root_pt.y + 5.0;
  2142. root_py1.z = root_pt.z;
  2143. viewer.addLine(p0, x1, 255, 0, 0, "x");
  2144. viewer.addLine(p0, y1, 0, 255, 0, "y");
  2145. viewer.addLine(p00, x0, 255, 0, 0, "x0");
  2146. viewer.addLine(p00, y0, 0, 255, 0, "y0");
  2147. viewer.addLine(root_px0, root_px1, 255, 0, 0, "rootx");
  2148. viewer.addLine(root_py0, root_py1, 0, 255, 0, "rooty");
  2149. while (!viewer.wasStopped()) {
  2150. viewer.spinOnce(100);
  2151. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  2152. }
  2153. }
  2154. void CRootStockGrabPoint::viewer_cloud_cluster(
  2155. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
  2156. std::vector<pcl::PointXYZ>cluster_center,
  2157. std::string&winname)
  2158. {
  2159. pcl::visualization::PCLVisualizer viewer(winname);
  2160. viewer.addPointCloud(cloud);
  2161. viewer.addCoordinateSystem();
  2162. int cnt = 0;
  2163. char buf[8];
  2164. for (auto& p : cluster_center) {
  2165. pcl::PointXYZ px0, px1, py1, py0;
  2166. px0.x = p.x-5.0;
  2167. px0.y = p.y;
  2168. px0.z = p.z;
  2169. px1.x = p.x + 5.0;
  2170. px1.y = p.y;
  2171. px1.z = p.z;
  2172. py0.x = p.x;
  2173. py0.y = p.y - 5.0;
  2174. py0.z = p.z;
  2175. py1.x = p.x;
  2176. py1.y = p.y + 5.0;
  2177. py1.z = p.z;
  2178. viewer.addLine(px0, px1, 255, 0, 0, "x" + string(_itoa(cnt, buf,10)));
  2179. viewer.addLine(py0, py1, 0, 255, 0, "y" + string(_itoa(cnt, buf, 10)));
  2180. cnt += 1;
  2181. }
  2182. while (!viewer.wasStopped()) {
  2183. viewer.spinOnce(100);
  2184. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  2185. }
  2186. }
  2187. void CRootStockGrabPoint::viewer_cloud_cluster_box(
  2188. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
  2189. std::vector<pcl::PointXYZ>&cluster_center,
  2190. std::vector<pcl::PointXYZ>&cluster_box,
  2191. std::vector<std::vector<int> >& clt_line_idx,
  2192. std::string&winname)
  2193. {
  2194. pcl::visualization::PCLVisualizer viewer(winname);
  2195. viewer.addCoordinateSystem();
  2196. viewer.addPointCloud<pcl::PointXYZ>(cloud, "all_cloud");
  2197. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 1, 1, "all_cloud");
  2198. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "all_cloud");
  2199. int cnt = 0;
  2200. char buf[8];
  2201. for (size_t i = 0; i < cluster_center.size();++i) {
  2202. pcl::PointXYZ &p = cluster_center.at(i);
  2203. pcl::PointXYZ px0, px1, py1, py0;
  2204. px0.x = p.x - 5.0;
  2205. px0.y = p.y;
  2206. px0.z = p.z;
  2207. px1.x = p.x + 5.0;
  2208. px1.y = p.y;
  2209. px1.z = p.z;
  2210. py0.x = p.x;
  2211. py0.y = p.y - 5.0;
  2212. py0.z = p.z;
  2213. py1.x = p.x;
  2214. py1.y = p.y + 5.0;
  2215. py1.z = p.z;
  2216. viewer.addLine(px0, px1, 255, 0, 0, "x" + string(_itoa(cnt, buf, 10)));
  2217. viewer.addLine(py0, py1, 0, 255, 0, "y" + string(_itoa(cnt, buf, 10)));
  2218. //box
  2219. pcl::PointXYZ & min_pt = cluster_box.at(2 * i);
  2220. pcl::PointXYZ & max_pt = cluster_box.at(2 * i + 1);
  2221. 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)));
  2222. viewer.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_REPRESENTATION,
  2223. pcl::visualization::PCL_VISUALIZER_REPRESENTATION_WIREFRAME, "AABB_" + string(_itoa(cnt, buf, 10)));
  2224. if (clt_line_idx.size()>i && clt_line_idx.at(i).size() > 0) {
  2225. pcl::PointCloud<pcl::PointXYZ>::Ptr line_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  2226. pcl::copyPointCloud(*cloud, clt_line_idx.at(i), *line_cloud);
  2227. viewer.addPointCloud(line_cloud, "fit_line" + string(_itoa(cnt, buf, 10)));
  2228. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 0, 1, 0, "fit_line" + string(_itoa(cnt, buf, 10)));
  2229. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "fit_line" + string(_itoa(cnt, buf, 10)));
  2230. }
  2231. cnt += 1;
  2232. }
  2233. while (!viewer.wasStopped()) {
  2234. viewer.spinOnce(100);
  2235. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  2236. }
  2237. }
  2238. };