grab_point_rs.cpp 97 KB

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