grab_point_rs.cpp 109 KB

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