grab_point_rs.cpp 91 KB

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