grab_point_rs.cpp 99 KB

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