grab_point_rs.cpp 83 KB

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