grab_point_rs.cpp 87 KB

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