grab_point_rs.cpp 98 KB

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