grab_point_rs.cpp 92 KB

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