grab_point_rs.cpp 59 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728172917301731173217331734173517361737173817391740174117421743174417451746174717481749175017511752175317541755175617571758175917601761176217631764176517661767176817691770177117721773177417751776177717781779178017811782178317841785178617871788178917901791
  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 <math.h>
  20. #include "grab_point_rs.h"
  21. #include "utils.h"
  22. #define PI std::acos(-1)
  23. namespace graft_cv {
  24. CRootStockGrabPoint::CRootStockGrabPoint(ConfigParam&cp, CGcvLogger*pLog/*=0*/)
  25. :m_cparam(cp),
  26. m_pLogger(pLog),
  27. m_dtype(0),
  28. m_pcdId(""),
  29. m_ppImgSaver(0),
  30. m_1st_row_zmean_rs(-1.0),
  31. m_1st_row_zmean_sc(-1.0)
  32. {
  33. }
  34. CRootStockGrabPoint::~CRootStockGrabPoint() {}
  35. float* CRootStockGrabPoint::get_raw_point_cloud(int &data_size)
  36. {
  37. data_size = m_raw_cloud->width * m_raw_cloud->height;
  38. if (data_size == 0) {
  39. return 0;
  40. }
  41. else {
  42. pcl::PointXYZ* pp = m_raw_cloud->points.data();
  43. return (float*)pp->data;
  44. }
  45. }
  46. int CRootStockGrabPoint::load_data(
  47. float*pPoint,
  48. int pixel_size,
  49. int pt_size,
  50. const char* fn/* = 0*/)
  51. {
  52. int rst = 0;
  53. //1 get point cloud data
  54. if (pPoint != 0 && pt_size>0) {
  55. //read point
  56. m_raw_cloud.reset(new pcl::PointCloud<pcl::PointXYZ>);
  57. int step = pixel_size;
  58. for (int i = 0; i < pt_size; ++i) {
  59. pcl::PointXYZ pt = { pPoint[i*step], pPoint[i*step + 1] , pPoint[i*step + 2] };
  60. m_raw_cloud->push_back(pt);
  61. }
  62. rst = m_raw_cloud->width * m_raw_cloud->height;
  63. if (m_pLogger) {
  64. stringstream buff;
  65. buff << "load raw point cloud " << rst << " data points";
  66. m_pLogger->INFO(buff.str());
  67. }
  68. }
  69. else if (fn != 0) {
  70. //read file
  71. rst = this->read_ply_file(fn);
  72. }
  73. else {//error
  74. if (m_pLogger) {
  75. m_pLogger->ERRORINFO("no valid input");
  76. return (-1);
  77. }
  78. }
  79. if (m_dtype == 0) {
  80. m_pcdId = getImgId(img_type::sola_sc_pcd);
  81. }
  82. else {
  83. m_pcdId = getImgId(img_type::sola_rs_pcd);
  84. }
  85. if (m_ppImgSaver && *m_ppImgSaver) {
  86. (*m_ppImgSaver)->saveBinPly(m_raw_cloud, m_pcdId);
  87. }
  88. if (m_cparam.image_show) {
  89. viewer_cloud(m_raw_cloud, std::string("raw point cloud"));
  90. }
  91. return rst;
  92. }
  93. int CRootStockGrabPoint::grab_point_detect(
  94. int dtype,
  95. PositionInfo& posinfo
  96. )
  97. {
  98. // dtype == 0, scion
  99. // dtype != 0, rootstock
  100. // 输入,穗苗--0, 砧木--1
  101. if (m_raw_cloud->width * m_raw_cloud->height < 1) {
  102. if (m_pLogger) {
  103. stringstream buff;
  104. buff << "m_raw_cloud point cloud " << m_raw_cloud->width * m_raw_cloud->height << " data points";
  105. m_pLogger->ERRORINFO(buff.str());
  106. }
  107. return 1;
  108. }
  109. ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  110. //1 crop filter
  111. if (m_pLogger) {
  112. m_pLogger->INFO("begin crop");
  113. }
  114. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  115. pcl::CropBox<pcl::PointXYZ> box_filter;
  116. m_dtype = dtype;
  117. if (dtype != 0) {//rootstock
  118. box_filter.setMin(Eigen::Vector4f(m_cparam.rs_grab_xmin, m_cparam.rs_grab_ymin, m_cparam.rs_grab_zmin, 1));
  119. box_filter.setMax(Eigen::Vector4f(m_cparam.rs_grab_xmax, m_cparam.rs_grab_ymax, m_cparam.rs_grab_zmax, 1));
  120. }
  121. else {//scion
  122. box_filter.setMin(Eigen::Vector4f(m_cparam.sc_grab_xmin, m_cparam.sc_grab_ymin, m_cparam.sc_grab_zmin, 1));
  123. box_filter.setMax(Eigen::Vector4f(m_cparam.sc_grab_xmax, m_cparam.sc_grab_ymax, m_cparam.sc_grab_zmax, 1));
  124. }
  125. box_filter.setNegative(false);
  126. box_filter.setInputCloud(m_raw_cloud);
  127. box_filter.filter(*cloud_inbox);
  128. if (m_pLogger) {
  129. stringstream buff;
  130. buff << "CropBox croped point cloud " << cloud_inbox->width * cloud_inbox->height << " data points";
  131. m_pLogger->INFO(buff.str());
  132. }
  133. if (cloud_inbox->width * cloud_inbox->height < 1) {
  134. return 1;
  135. }
  136. if (m_cparam.image_show) {
  137. viewer_cloud(cloud_inbox, std::string("cloud_inbox"));
  138. }
  139. if (m_pLogger) {
  140. m_pLogger->INFO("end crop");
  141. }
  142. ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  143. //2 filtler with radius remove
  144. if (m_pLogger) {
  145. m_pLogger->INFO("begin ror");
  146. }
  147. int nb_points = 20;
  148. double stem_radius = m_cparam.rs_grab_stem_diameter / 2.0;
  149. if(dtype == 0){
  150. stem_radius = m_cparam.sc_grab_stem_diameter / 2.0;
  151. }
  152. double remove_radius = stem_radius * 2.0;
  153. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ror(new pcl::PointCloud<pcl::PointXYZ>);
  154. pcl::RadiusOutlierRemoval<pcl::PointXYZ> ror(false);
  155. ror.setInputCloud(cloud_inbox);
  156. ror.setRadiusSearch(remove_radius);
  157. ror.setMinNeighborsInRadius(nb_points);
  158. ror.filter(*cloud_ror);
  159. if (m_pLogger) {
  160. stringstream buff;
  161. buff << "RadiusOutlierRemoval filtered point cloud " << cloud_ror->width * cloud_ror->height << " data points. param stem_radius="<<
  162. stem_radius<<", nb_points="<< nb_points;
  163. m_pLogger->INFO(buff.str());
  164. }
  165. if (cloud_ror->width * cloud_ror->height < 1) {
  166. return 1;
  167. }
  168. /*if (m_cparam.image_show) {
  169. viewer_cloud(cloud_ror, std::string("cloud_ror"));
  170. }*/
  171. if (m_pLogger) {
  172. m_pLogger->INFO("end ror");
  173. }
  174. ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  175. //3 voxel grid down sampling
  176. if (m_pLogger) {
  177. m_pLogger->INFO("begin down");
  178. }
  179. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_dowm_sampled(new pcl::PointCloud<pcl::PointXYZ>);
  180. pcl::VoxelGrid<pcl::PointXYZ> outrem;
  181. outrem.setInputCloud(cloud_ror);
  182. outrem.setLeafSize(stem_radius, stem_radius, stem_radius);
  183. outrem.filter(*cloud_dowm_sampled);
  184. if (m_pLogger) {
  185. stringstream buff;
  186. buff << "VoxelGrid dowm_sampled point cloud " << cloud_dowm_sampled->width * cloud_dowm_sampled->height << " data points (if < 50, return)";
  187. m_pLogger->INFO(buff.str());
  188. }
  189. if (cloud_dowm_sampled->width * cloud_dowm_sampled->height < 50) {
  190. return 1;
  191. }
  192. /*if (m_cparam.image_show) {
  193. viewer_cloud(cloud_dowm_sampled, std::string("cloud_dowm_sampled"));
  194. }*/
  195. if (m_pLogger) {
  196. m_pLogger->INFO("end down");
  197. }
  198. ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  199. //4 seedling position,找到第一个位置上的植株
  200. std::vector<int> first_seedling_cloud_idx; //存储找到的第一个位置上植株茎上直线点的index
  201. pcl::PointXYZ xz_center; //存储找到的第一个位置上植株根部坐标
  202. if (m_pLogger) {
  203. m_pLogger->INFO("begin find seedling position");
  204. }
  205. find_seedling_position_key(cloud_dowm_sampled, first_seedling_cloud_idx, xz_center);
  206. if (m_pLogger) {
  207. stringstream buff;
  208. buff << "after find_seedling_position(), foud first seedling seeds points size " << first_seedling_cloud_idx.size();
  209. m_pLogger->INFO(buff.str());
  210. }
  211. if (m_pLogger) {
  212. m_pLogger->INFO("end find seedling position");
  213. }
  214. ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  215. //5 nearest seedling grab point selection,找到最接近指定高度的最优抓取点坐标
  216. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_seedling_seed(new pcl::PointCloud<pcl::PointXYZ>);
  217. pcl::copyPointCloud(*cloud_dowm_sampled, first_seedling_cloud_idx, *cloud_seedling_seed);
  218. //改进思路:将茎直线上cloud_seedling_seed的点,提取周围邻域xz的宽度,在相同邻域cloud_dowm_sampled点云内提取xz的宽度
  219. //对比两个宽度,变化很大的,说明周边有异物(叶柄或叶子),不适合作为抓取位置;否则就是抓取位置
  220. //在众多抓取位置上,选择离指定高度最近的点作为抓取位置
  221. //
  222. pcl::PointXYZ selected_pt;
  223. int selected_pt_idx;
  224. std::vector<int> optimal_seeds_idx;
  225. get_optimal_seed_compare(cloud_dowm_sampled, cloud_seedling_seed, selected_pt, selected_pt_idx, optimal_seeds_idx);
  226. if (selected_pt_idx < 0) {
  227. if (m_pLogger) {
  228. m_pLogger->ERRORINFO("Not found valid grab point");
  229. }
  230. return 1;
  231. }
  232. if (m_pLogger) {
  233. m_pLogger->INFO("end get_optimal_seed");
  234. }
  235. posinfo.rs_grab_x = selected_pt.x;
  236. posinfo.rs_grab_y = selected_pt.y;
  237. posinfo.rs_grab_z = selected_pt.z;
  238. ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
  239. //6 debug 显示结果
  240. if (m_cparam.image_show) {
  241. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_cand_demo(new pcl::PointCloud<pcl::PointXYZRGB>);
  242. pcl::copyPointCloud(*cloud_dowm_sampled, *cloud_cand_demo);
  243. for (auto& pt : *cloud_cand_demo) {
  244. pt.r = 255;
  245. pt.g = 255;
  246. pt.b = 255;
  247. }
  248. int cnt = 0;
  249. for (auto& idx : optimal_seeds_idx) {
  250. int p_idx = first_seedling_cloud_idx.at(idx);
  251. /*if (p_idx == optimal_seeds_idx[selected_pt_idx]) {
  252. cloud_cand_demo->points[p_idx].r = 0;
  253. cloud_cand_demo->points[p_idx].g = 255;
  254. cloud_cand_demo->points[p_idx].b = 0;
  255. }
  256. else {*/
  257. cloud_cand_demo->points.at(p_idx).r = 255;
  258. cloud_cand_demo->points.at(p_idx).g = 0;
  259. cloud_cand_demo->points.at(p_idx).b = 0;
  260. /*} */
  261. if (cnt > optimal_seeds_idx.size()) { break; }
  262. cnt++;
  263. }
  264. pcl::PointXYZRGB pt_grab = {0,255,0};
  265. pt_grab.x = selected_pt.x;
  266. pt_grab.y = selected_pt.y;
  267. pt_grab.z = selected_pt.z;
  268. pcl::PointXYZRGB pt_grab_ = { 0,255,120 };
  269. pt_grab_.x = selected_pt.x;
  270. pt_grab_.y = selected_pt.y+0.2;
  271. pt_grab_.z = selected_pt.z;
  272. cloud_cand_demo->push_back(pt_grab);
  273. //viewer_cloud(cloud_cand_demo, std::string("cloud_cand_demo"));
  274. viewer_cloud_debug(cloud_cand_demo, selected_pt, xz_center, std::string("cloud_cand_demo"));
  275. }
  276. return 0;
  277. }
  278. int CRootStockGrabPoint::read_ply_file(const char* fn)
  279. {
  280. m_raw_cloud.reset( new pcl::PointCloud<pcl::PointXYZ>);
  281. if (pcl::io::loadPLYFile<pcl::PointXYZ>(fn, *m_raw_cloud) == -1) {
  282. if (m_pLogger) {
  283. m_pLogger->ERRORINFO("could not load file: "+std::string(fn));
  284. }
  285. return (-1);
  286. }
  287. if (m_pLogger) {
  288. stringstream buff;
  289. buff << "load raw point cloud " << m_raw_cloud->width * m_raw_cloud->height << " data points";
  290. m_pLogger->INFO(buff.str());
  291. }
  292. return m_raw_cloud->width * m_raw_cloud->height;
  293. }
  294. double CRootStockGrabPoint::compute_nearest_neighbor_distance(pcl::PointCloud<pcl::PointXYZ>::Ptr pcd)
  295. {
  296. pcl::KdTreeFLANN<pcl::PointXYZ> tree;
  297. tree.setInputCloud(pcd);
  298. int k = 2;
  299. double res = 0.0;
  300. int n_points = 0;
  301. for (size_t i = 0; i < pcd->size(); ++i) {
  302. std::vector<int> idx(k);
  303. std::vector<float> sqr_distances(k);
  304. if (tree.nearestKSearch(i, k, idx, sqr_distances) == k) {
  305. for (int id = 1; id < k; ++id) {
  306. res += sqrt(sqr_distances.at(id));
  307. ++n_points;
  308. }
  309. }
  310. }
  311. if (n_points > 0) {
  312. res /= (double)n_points;
  313. }
  314. return res;
  315. }
  316. //void CRootStockGrabPoint::find_tray_top_edge(
  317. //pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  318. //float & tray_top_edge_y
  319. //)
  320. //{
  321. // tray_top_edge_y = -1000.0;
  322. // //以毫米为单位构建vector
  323. // pcl::PointXYZ min_point_aabb;
  324. // pcl::PointXYZ max_point_aabb;
  325. // pcl::MomentOfInertiaEstimation<pcl::PointXYZ> feature_extractor;
  326. // feature_extractor.setInputCloud(in_cloud);
  327. // feature_extractor.compute();
  328. // feature_extractor.getAABB(min_point_aabb, max_point_aabb);
  329. // float miny = min_point_aabb.y;
  330. // float maxy = max_point_aabb.y;
  331. // if(maxy - miny <5.0){
  332. // tray_top_edge_y = maxy;
  333. // return;
  334. // }
  335. // std::vector<int> y_cnt_hist(int(maxy - miny), 0);
  336. // for(auto& pt : in_cloud->points){
  337. // int idx = (int)(pt.y - miny);
  338. // if(idx<0){continue;}
  339. // if (idx >= y_cnt_hist.size()) { continue; }
  340. // y_cnt_hist.at(idx) += 1;
  341. // }
  342. // //从上半部分找到最大值,作为平面上沿
  343. // int idx_part = (int)(y_cnt_hist.size() / 2);
  344. // int idx_edge = std::max_element(y_cnt_hist.begin(), y_cnt_hist.begin() + idx_part) - y_cnt_hist.begin();
  345. // tray_top_edge_y = miny + (float)(idx_edge + 2.0);
  346. //}
  347. //void CRootStockGrabPoint::find_seedling_position_line_based(
  348. // pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  349. // std::vector<int> &first_seedling_cloud_idx,
  350. // pcl::PointXYZ&xz_center
  351. //)
  352. //{
  353. // //找到穴盘上沿z,最优抓取的z,再在最优抓取的z基础上加上3作为有效范围
  354. // float tray_y = -1000.0;
  355. // float top_y = 0.0;
  356. // find_tray_top_edge(in_cloud, tray_y);
  357. // if (tray_y < -500.0) {
  358. // if (m_dtype == 0) {
  359. // //scion
  360. // tray_y = m_cparam.sc_grab_y_opt-2.0;
  361. // }
  362. // else {
  363. // tray_y = m_cparam.rs_grab_y_opt-2.0;
  364. // }
  365. // }
  366. // //up limit
  367. // if (m_dtype == 0) {
  368. // top_y = m_cparam.sc_grab_zmax;
  369. // if (top_y > m_cparam.sc_grab_y_opt + 3.0) {
  370. // top_y = m_cparam.sc_grab_y_opt + 3.0;
  371. // }
  372. // }
  373. // else {
  374. // top_y = m_cparam.rs_grab_zmax;
  375. // if (top_y > m_cparam.rs_grab_y_opt + 3.0) {
  376. // top_y = m_cparam.rs_grab_y_opt + 3.0;
  377. // }
  378. // }
  379. // //sub cloud
  380. // pcl::PointCloud<pcl::PointXYZ>::Ptr sub_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  381. // pcl::CropBox<pcl::PointXYZ> box_filter;
  382. // if (m_dtype != 0) {//rootstock
  383. // box_filter.setMin(Eigen::Vector4f(m_cparam.rs_grab_xmin, tray_y, m_cparam.rs_grab_zmin, 1));
  384. // box_filter.setMax(Eigen::Vector4f(m_cparam.rs_grab_xmax, top_y, m_cparam.rs_grab_zmax, 1));
  385. // }
  386. // else {//scion
  387. // box_filter.setMin(Eigen::Vector4f(m_cparam.sc_grab_xmin, tray_y, m_cparam.sc_grab_zmin, 1));
  388. // box_filter.setMax(Eigen::Vector4f(m_cparam.sc_grab_xmax, top_y, m_cparam.sc_grab_zmax, 1));
  389. // }
  390. // box_filter.setNegative(false);
  391. // box_filter.setInputCloud(in_cloud);
  392. // box_filter.filter(*sub_cloud);
  393. // if (m_cparam.image_show) {
  394. // viewer_cloud(sub_cloud, std::string("sub inbox"));
  395. // }
  396. // //在sub_cloud中进行直线检测
  397. // segement_line(sub_cloud);
  398. //}
  399. //void CRootStockGrabPoint::segement_line(
  400. // pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud
  401. //)
  402. //{
  403. // pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
  404. // pcl::PointIndices::Ptr inliers(new pcl::PointIndices);
  405. // pcl::SACSegmentation<pcl::PointXYZ> seg;
  406. // seg.setOptimizeCoefficients(true);
  407. // seg.setModelType(pcl::SACMODEL_LINE);
  408. // seg.setMethodType(pcl::SAC_RANSAC);
  409. // seg.setDistanceThreshold(0.5);
  410. // seg.setInputCloud(in_cloud);
  411. // seg.segment(*inliers, *coefficients);
  412. // if (m_cparam.image_show) {
  413. // pcl::PointCloud<pcl::PointXYZ>::Ptr line_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  414. // pcl::copyPointCloud(*in_cloud, *inliers, *line_cloud);
  415. // viewer_cloud(line_cloud, std::string("cloud_line"));
  416. // }
  417. //}
  418. ////////////////////////////////////////////////////////////
  419. void CRootStockGrabPoint::gen_all_seedling_positions(
  420. pcl::PointXYZ&key_center, //输入,已知的苗的坐标
  421. std::vector<pcl::PointXYZ>&candidate_center //输出,有倾斜苗的坐标
  422. )
  423. {
  424. //生成所有的植株位置,并排序
  425. candidate_center.clear();
  426. //找到z最小的那一株,并找出和它一排的那些
  427. float step_harf = m_cparam.rs_grab_seedling_dist / 2.0;
  428. float xmin = m_cparam.rs_grab_xmin;
  429. float xmax = m_cparam.rs_grab_xmax;
  430. float zmin = m_cparam.rs_grab_zmin;
  431. float zmax = m_cparam.rs_grab_zmax;
  432. int col_from = -8;
  433. int col_to = 8;
  434. int col_step = 1;
  435. if (m_dtype == 0) {
  436. step_harf = m_cparam.sc_grab_seedling_dist / 2.0;
  437. xmin = m_cparam.sc_grab_xmin;
  438. xmax = m_cparam.sc_grab_xmax;
  439. zmin = m_cparam.sc_grab_zmin;
  440. zmax = m_cparam.sc_grab_zmax;
  441. }
  442. // 生成所有可能的植株位置中心点
  443. for (int row = -8; row <= 4; row += 1) {
  444. float cz = key_center.z + row * step_harf/2.0;
  445. if (cz < zmin || cz > zmax) { continue; }
  446. for (int col = 4*col_from; col <= 4*col_to; col += col_step) {
  447. float cx = key_center.x + col * step_harf/2;
  448. if (cx < xmin || cx > xmax) { continue; }
  449. //保存
  450. pcl::PointXYZ pc(cx, 0.0, cz);
  451. candidate_center.push_back(pc);
  452. }
  453. }
  454. }
  455. void CRootStockGrabPoint::nms_box(
  456. std::vector<pcl::PointXYZ>&clt_root_v,
  457. std::vector<float>&valid_box_cc_dist,
  458. float hole_step_radius,
  459. std::vector<pcl::PointXYZ>& target_toot)
  460. {
  461. target_toot.clear();
  462. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
  463. for (auto&p : clt_root_v) { cloud->points.push_back(p); }
  464. pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
  465. kdtree.setInputCloud(cloud);
  466. std::vector<int>idx;
  467. std::vector<float>dist_sqr;
  468. std::vector<int> tar_idx;
  469. for (size_t i = 0; i < cloud->points.size(); ++i) {
  470. int k = kdtree.radiusSearch(cloud->points.at(i), hole_step_radius, idx, dist_sqr);
  471. std::vector<float> cc_tmp;
  472. for (auto& j : idx) { cc_tmp.push_back(valid_box_cc_dist.at(j)); }
  473. int min_id = std::min_element(cc_tmp.begin(), cc_tmp.end()) - cc_tmp.begin();
  474. if (min_id == 0) {
  475. tar_idx.push_back(i);
  476. }
  477. }
  478. for (auto& i : tar_idx) {
  479. target_toot.push_back(clt_root_v.at(i));
  480. }
  481. }
  482. //通过指定位置内,取部分点云分析是否存在真正的茎,真茎位置保存到target_filtered
  483. void CRootStockGrabPoint::line_filter(
  484. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, //输入点云
  485. float radius, //输入,取点半径
  486. float ymin,
  487. float ymax,
  488. std::vector<pcl::PointXYZ>&target_root, //输入,位置
  489. std::vector<pcl::PointXYZ>&target_filtered, //输出,位置
  490. std::vector<pcl::PointXYZ>&target_filtered_root, //输出,茎上根部点坐标
  491. std::vector<std::vector<int>>&target_filtered_element //输出,茎上点index
  492. )
  493. {
  494. target_filtered.clear();
  495. target_filtered_element.clear();
  496. target_filtered_root.clear();
  497. if (target_root.size() == 0) { return; }
  498. for (auto&p : target_root) {
  499. // 构建box,获取植株点云
  500. pcl::PointCloud<pcl::PointXYZ>::Ptr seedling_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  501. pcl::CropBox<pcl::PointXYZ> box_filter;
  502. std::vector<int>inbox_idx;
  503. pcl::PointXYZ min_point_aabb_ex;
  504. pcl::PointXYZ max_point_aabb_ex;
  505. min_point_aabb_ex.x = p.x - radius;
  506. min_point_aabb_ex.y = ymin;
  507. min_point_aabb_ex.z = p.z - radius;
  508. max_point_aabb_ex.x = p.x + radius;
  509. max_point_aabb_ex.y = ymax;
  510. max_point_aabb_ex.z = p.z + radius;
  511. box_filter.setMin(Eigen::Vector4f(min_point_aabb_ex.x, min_point_aabb_ex.y, min_point_aabb_ex.z, 1));
  512. box_filter.setMax(Eigen::Vector4f(max_point_aabb_ex.x, max_point_aabb_ex.y, max_point_aabb_ex.z, 1));
  513. box_filter.setNegative(false);
  514. box_filter.setInputCloud(in_cloud);
  515. box_filter.filter(inbox_idx);
  516. pcl::copyPointCloud(*in_cloud, inbox_idx, *seedling_inbox);
  517. //植株点云直线查找
  518. //找到inbox点云中的直线
  519. float stem_radius = m_cparam.rs_grab_stem_diameter / 2.0;
  520. if (m_dtype == 0) {
  521. stem_radius = m_cparam.sc_grab_stem_diameter / 2.0;
  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.setDistanceThreshold(stem_radius);
  529. seg.setInputCloud(seedling_inbox);
  530. seg.segment(*inliers, *coefficients);
  531. pcl::PointCloud<pcl::PointXYZ>::Ptr stem_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  532. pcl::copyPointCloud(*seedling_inbox, *inliers, *stem_cloud);
  533. //点数过滤
  534. int min_stem_pts = m_cparam.rs_grab_stem_min_pts;
  535. if (m_dtype == 0) { min_stem_pts = m_cparam.sc_grab_stem_min_pts; }
  536. if (inliers->indices.size() < int(min_stem_pts / 2)) { continue; }
  537. //y方向分布范围滤波
  538. pcl::PointXYZ min_v;
  539. pcl::PointXYZ max_v;
  540. pcl::getMinMax3D(*stem_cloud, min_v, max_v);
  541. float dy = max_v.y - min_v.y;
  542. if (dy / (ymax - ymin) < 0.5) { continue; }
  543. //y方向分布中心滤波
  544. float dy_c = 0.5*(max_v.y + min_v.y);
  545. if ((dy_c - ymin) / (ymax - ymin) > 0.75) { continue; }
  546. //倾斜角度过滤
  547. float xz = std::sqrt(coefficients->values.at(3) * coefficients->values.at(3) +
  548. coefficients->values.at(5) * coefficients->values.at(5));
  549. float a = std::atan2f(coefficients->values.at(4), xz);
  550. a = std::fabs(a) * 180.0 / 3.14159;
  551. if (a < 45.0) { continue; }
  552. target_filtered.push_back(p);
  553. float min_y = 10000.0;
  554. int min_y_idx = -1;
  555. for (size_t j = 0; j < stem_cloud->points.size();++j) {
  556. pcl::PointXYZ &spt = stem_cloud->at(j);
  557. if (spt.y < min_y) {
  558. min_y = spt.y;
  559. min_y_idx = j;
  560. }
  561. }
  562. 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);
  563. target_filtered_root.push_back(tr_pt);
  564. int idx_raw = 0;
  565. std::vector<int> out_idx;
  566. for (auto& idx : inliers->indices) {
  567. idx_raw = inbox_idx.at(idx);
  568. out_idx.push_back(idx_raw);
  569. }
  570. target_filtered_element.push_back(out_idx);
  571. // debug show
  572. /*if (m_cparam.image_show) {
  573. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_line(new pcl::PointCloud<pcl::PointXYZ>);
  574. pcl::copyPointCloud(*seedling_inbox, *inliers, *cloud_line);
  575. pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("line in cluster"));
  576. viewer->addPointCloud<pcl::PointXYZ>(seedling_inbox, "cluster");
  577. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 1, 1, "cluster");
  578. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "cluster");
  579. viewer->addPointCloud(cloud_line, "fit_line");
  580. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 0, 1, 0, "fit_line");
  581. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "fit_line");
  582. while (!viewer->wasStopped()) {
  583. viewer->spinOnce(100);
  584. }
  585. }*/
  586. }
  587. }
  588. void CRootStockGrabPoint::find_seedling_position_key(
  589. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  590. std::vector<int> &first_seedling_cloud_idx,
  591. pcl::PointXYZ&xz_center
  592. )
  593. {
  594. // 确定植株inbox范围
  595. float hole_step = m_cparam.rs_grab_seedling_dist - 5.0; //穴盘中穴间距
  596. if (m_dtype == 0) {
  597. hole_step = m_cparam.sc_grab_seedling_dist - 5.0;
  598. }
  599. float hole_step_radius = hole_step / 2.0;
  600. // 点云降维到xz平面,y=0
  601. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2d(new pcl::PointCloud < pcl::PointXYZ>);
  602. pcl::copyPointCloud(*in_cloud, *cloud2d);
  603. for (auto&pt : *cloud2d) {
  604. pt.y = 0.0;
  605. }
  606. // 在xz平面内统计点的密度
  607. double radius = m_cparam.rs_grab_stem_diameter;
  608. if (m_dtype == 0) {
  609. radius = m_cparam.sc_grab_stem_diameter;
  610. }
  611. std::vector<int> counter;
  612. pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
  613. kdtree.setInputCloud(cloud2d);
  614. std::vector<int>idx;
  615. std::vector<float>dist_sqr;
  616. for (size_t i = 0; i < cloud2d->points.size(); ++i) {
  617. int k = kdtree.radiusSearch(cloud2d->points.at(i), radius, idx, dist_sqr);
  618. counter.push_back(k);
  619. }
  620. int max_density_idx = std::max_element(counter.begin(), counter.end()) - counter.begin();
  621. int max_density = counter.at(max_density_idx);
  622. if (m_cparam.image_show) {
  623. //显示密度最大的点的位置
  624. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_tmp(new pcl::PointCloud<pcl::PointXYZRGB>);
  625. pcl::copyPointCloud(*in_cloud, *cloud_tmp);
  626. for (auto& pt : *cloud_tmp) {
  627. pt.r = 255;
  628. pt.g = 255;
  629. pt.b = 255;
  630. }
  631. std::vector<pcl::PointXYZ>cc;
  632. cc.push_back(in_cloud->points.at(max_density_idx));
  633. viewer_cloud_cluster(cloud_tmp, cc, string("key"));
  634. }
  635. // 生成植株的中心及box
  636. std::vector<pcl::PointXYZ>clt_root;
  637. std::vector<pcl::PointXYZ> clt_box;
  638. float ymin = m_cparam.rs_grab_ymin;
  639. float ymax = m_cparam.rs_grab_ymax;
  640. if (m_dtype == 0) {
  641. ymin = m_cparam.sc_grab_ymin;
  642. ymax = m_cparam.sc_grab_ymax;
  643. }
  644. gen_all_seedling_positions(in_cloud->points.at(max_density_idx), clt_root);
  645. // 每个位置点云情况,过滤
  646. std::vector<int> valid_index; //初步有效的矩形index
  647. std::vector<int> valid_box_pts; //立方体内点云数量
  648. std::vector<float>valid_box_cc_dist;//重心和矩形中心距离
  649. for (size_t i = 0; i < clt_root.size();++i) {
  650. pcl::PointXYZ &p = clt_root.at(i);
  651. pcl::PointCloud<pcl::PointXYZ>::Ptr seedling_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  652. pcl::CropBox<pcl::PointXYZ> box_filter;
  653. std::vector<int>inbox_idx;
  654. pcl::PointXYZ min_point_aabb_ex;
  655. pcl::PointXYZ max_point_aabb_ex;
  656. min_point_aabb_ex.x = p.x - hole_step_radius;
  657. min_point_aabb_ex.y = ymin;
  658. min_point_aabb_ex.z = p.z - hole_step_radius;
  659. max_point_aabb_ex.x = p.x + hole_step_radius;
  660. max_point_aabb_ex.y = ymax;
  661. max_point_aabb_ex.z = p.z + hole_step_radius;
  662. box_filter.setMin(Eigen::Vector4f(min_point_aabb_ex.x, min_point_aabb_ex.y, min_point_aabb_ex.z, 1));
  663. box_filter.setMax(Eigen::Vector4f(max_point_aabb_ex.x, max_point_aabb_ex.y, max_point_aabb_ex.z, 1));
  664. box_filter.setNegative(false);
  665. box_filter.setInputCloud(in_cloud);
  666. box_filter.filter(inbox_idx);
  667. pcl::copyPointCloud(*in_cloud, inbox_idx, *seedling_inbox);
  668. //点数过滤
  669. if (inbox_idx.size() < int(max_density/2)) { continue; }
  670. //y方向分布范围滤波
  671. pcl::PointXYZ min_v;
  672. pcl::PointXYZ max_v;
  673. pcl::getMinMax3D(*seedling_inbox, min_v, max_v);
  674. float dy = max_v.y - min_v.y;
  675. if (dy / (ymax - ymin) < 0.5) { continue; }
  676. //y方向分布中心滤波
  677. float dy_c = 0.5*(max_v.y + min_v.y);
  678. if ((dy_c-ymin) / (ymax - ymin) > 0.75) { continue; }
  679. //计算中心
  680. Eigen::Vector4f mean;
  681. pcl::compute3DCentroid(*seedling_inbox, mean);
  682. double cc_dist = std::sqrt((mean[0] - p.x)*(mean[0] - p.x) + (mean[2] - p.z)*(mean[2] - p.z));
  683. valid_index.push_back(i);
  684. valid_box_pts.push_back(inbox_idx.size());
  685. valid_box_cc_dist.push_back((float)cc_dist);
  686. }
  687. // 找到局部最大值,找出真正的位置
  688. std::vector<pcl::PointXYZ> clt_root_v;
  689. std::vector<pcl::PointXYZ> clt_box_v;
  690. for (auto&i : valid_index) {
  691. pcl::PointXYZ&p = clt_root.at(i);
  692. pcl::PointXYZ p_show(p.x, ymin, p.z);
  693. clt_root_v.push_back(p_show);
  694. pcl::PointXYZ min_point_aabb_ex;
  695. pcl::PointXYZ max_point_aabb_ex;
  696. min_point_aabb_ex.x = p.x - hole_step_radius;
  697. min_point_aabb_ex.y = ymin;
  698. min_point_aabb_ex.z = p.z - hole_step_radius;
  699. max_point_aabb_ex.x = p.x + hole_step_radius;
  700. max_point_aabb_ex.y = ymax;
  701. max_point_aabb_ex.z = p.z + hole_step_radius;
  702. clt_box_v.push_back(min_point_aabb_ex);
  703. clt_box_v.push_back(max_point_aabb_ex);
  704. }
  705. // 显示
  706. if (m_cparam.image_show) {
  707. std::vector<std::vector<int> > clt_line_idx;
  708. viewer_cloud_cluster_box(in_cloud, clt_root_v, clt_box_v, clt_line_idx, std::string("valid_box"));
  709. }
  710. std::vector<pcl::PointXYZ> target_root;
  711. nms_box(clt_root_v, valid_box_cc_dist, hole_step_radius, target_root);
  712. // 显示
  713. if (m_cparam.image_show) {
  714. std::vector<std::vector<int> > clt_line_idx;
  715. std::vector<pcl::PointXYZ>clt_box_tmp;
  716. for (auto&p : target_root) {
  717. pcl::PointXYZ p_show(p.x, ymin, p.z);
  718. clt_root_v.push_back(p_show);
  719. pcl::PointXYZ min_point_aabb_ex;
  720. pcl::PointXYZ max_point_aabb_ex;
  721. min_point_aabb_ex.x = p.x - hole_step_radius;
  722. min_point_aabb_ex.y = ymin;
  723. min_point_aabb_ex.z = p.z - hole_step_radius;
  724. max_point_aabb_ex.x = p.x + hole_step_radius;
  725. max_point_aabb_ex.y = ymax;
  726. max_point_aabb_ex.z = p.z + hole_step_radius;
  727. clt_box_tmp.push_back(min_point_aabb_ex);
  728. clt_box_tmp.push_back(max_point_aabb_ex);
  729. }
  730. viewer_cloud_cluster_box(in_cloud, target_root, clt_box_tmp, clt_line_idx, std::string("nms_box"));
  731. }
  732. // 根据得到的位置,直线检测,并过滤
  733. std::vector<pcl::PointXYZ>target_filtered;
  734. std::vector<std::vector<int>> target_member;
  735. std::vector<pcl::PointXYZ>target_filtered_root;
  736. line_filter(in_cloud, hole_step_radius,ymin,ymax, target_root, target_filtered, target_filtered_root, target_member);
  737. if (m_cparam.image_show) {
  738. std::vector<pcl::PointXYZ> final_box;
  739. for (auto&pt : target_filtered_root) {
  740. //扩展矩形范围
  741. pcl::PointXYZ min_point_aabb_ex;
  742. pcl::PointXYZ max_point_aabb_ex;
  743. min_point_aabb_ex.x = pt.x - hole_step_radius;
  744. min_point_aabb_ex.y = ymin;
  745. min_point_aabb_ex.z = pt.z - hole_step_radius;
  746. max_point_aabb_ex.x = pt.x + hole_step_radius;
  747. max_point_aabb_ex.y = ymax;
  748. max_point_aabb_ex.z = pt.z + hole_step_radius;
  749. final_box.push_back(min_point_aabb_ex);
  750. final_box.push_back(max_point_aabb_ex);
  751. }
  752. std::vector<std::vector<int> > clt_line_idx_;
  753. viewer_cloud_cluster_box(in_cloud, target_filtered_root, final_box, clt_line_idx_, std::string("line_filter"));
  754. }
  755. //sort cluster center, get the frontest leftest one
  756. //找最小z,然后计算平均z
  757. float min_root_z = 10000.0;
  758. for(auto&pt : target_filtered_root) {
  759. if (pt.z < min_root_z) { min_root_z = pt.z; }
  760. }
  761. //通过最小z,保守的找到和他一排的植株
  762. std::vector<int> first_row_index;
  763. float mean_z = 0.0;
  764. for (int idx_r = 0; idx_r < target_filtered_root.size();++idx_r) {
  765. pcl::PointXYZ&pt = target_filtered_root.at(idx_r);
  766. if (std::fabs(pt.z - min_root_z) < hole_step) {
  767. first_row_index.push_back(idx_r);
  768. mean_z += pt.z;
  769. }
  770. }
  771. //如果第一排的植株大于3,计算平均值
  772. float first_row_num = (float)first_row_index.size();
  773. mean_z /= first_row_num;
  774. if (first_row_num >= 4) {
  775. if (m_dtype == 0) {
  776. m_1st_row_zmean_sc = mean_z;
  777. }
  778. else{ m_1st_row_zmean_rs = mean_z; }
  779. }
  780. else {
  781. if( m_dtype == 0) {
  782. if (m_1st_row_zmean_sc > 0) { mean_z = m_1st_row_zmean_sc; }
  783. }
  784. else {
  785. if (m_1st_row_zmean_rs > 0) { mean_z = m_1st_row_zmean_rs; }
  786. }
  787. }
  788. //通过mean_z再次寻找第一排的植株
  789. first_row_index.clear();
  790. for (int idx_r = 0; idx_r < target_filtered_root.size(); ++idx_r) {
  791. pcl::PointXYZ&pt = target_filtered_root.at(idx_r);
  792. if (std::fabs(pt.z - mean_z) < hole_step) {
  793. first_row_index.push_back(idx_r);
  794. }
  795. }
  796. std::vector<float> cluster_index;
  797. for (int i=0; i<first_row_index.size();++i){
  798. int raw_idx = first_row_index.at(i);
  799. pcl::PointXYZ&pt = target_filtered_root.at(raw_idx);
  800. cluster_index.push_back(pt.x);
  801. }
  802. int first_idx = std::min_element(cluster_index.begin(), cluster_index.end()) - cluster_index.begin();
  803. if (m_dtype == 0) {
  804. first_idx = std::max_element(cluster_index.begin(), cluster_index.end()) - cluster_index.begin();
  805. }
  806. first_idx = first_row_index.at(first_idx);
  807. first_seedling_cloud_idx.clear();
  808. for (auto&v : target_member.at(first_idx)) {
  809. first_seedling_cloud_idx.push_back(v);
  810. }
  811. xz_center.x = target_filtered_root.at(first_idx).x;
  812. xz_center.y = target_filtered_root.at(first_idx).y;
  813. xz_center.z = target_filtered_root.at(first_idx).z;
  814. if (m_pLogger) {
  815. stringstream buff;
  816. buff << "euclidean_clustering_ttsas, find cluster center(" << xz_center.x
  817. <<", "<< xz_center.y<<", "<< xz_center.z<<")";
  818. m_pLogger->INFO(buff.str());
  819. }
  820. }
  821. void CRootStockGrabPoint::tilted_seedling_discover(
  822. std::vector<pcl::PointXYZ>&cluster_center, //输入,已知的苗的坐标
  823. std::vector<pcl::PointXYZ>&tilted_center //输出,有倾斜苗的坐标
  824. )
  825. {
  826. tilted_center.clear();
  827. if (cluster_center.size() == 0) { return; }
  828. //找到z最小的那一株,并找出和它一排的那些
  829. float step_harf = m_cparam.rs_grab_seedling_dist / 2.0;
  830. float xmin = m_cparam.rs_grab_xmin;
  831. float xmax = m_cparam.rs_grab_xmax;
  832. float zmin = m_cparam.rs_grab_zmin;
  833. float zmax = m_cparam.rs_grab_zmax;
  834. if (m_dtype == 0) {
  835. step_harf = m_cparam.sc_grab_seedling_dist / 2.0;
  836. xmin = m_cparam.sc_grab_xmin;
  837. xmax = m_cparam.sc_grab_xmax;
  838. zmin = m_cparam.sc_grab_zmin;
  839. zmax = m_cparam.sc_grab_zmax;
  840. }
  841. auto minz_it = std::min_element(cluster_center.begin(), cluster_center.end(),
  842. [](const pcl::PointXYZ& p1, const pcl::PointXYZ& p2)-> bool {return p1.z < p2.z; });
  843. float minz = minz_it->z;
  844. float meanz = 0.0;
  845. float cnt = 0.0;
  846. for (auto&p : cluster_center) {
  847. if (fabs(p.z - minz) < step_harf) { meanz += p.z; cnt += 1.0; }
  848. }
  849. if(cnt>0.0){meanz /= cnt;}
  850. else { meanz = minz; }
  851. // 生成所有可能的植株位置中心点
  852. std::vector<pcl::PointXYZ>candidate_centers;
  853. for (int row = -1; row <= 1; row += 1) {
  854. for (int col = -6; col <= 6; col += 1) {
  855. float cx = minz_it->x + col * 2.0 * step_harf;
  856. float cz = meanz + row * 2.0 * step_harf;
  857. if (cx < xmin || cx > xmax) { continue; }
  858. if (cz < zmin || cz > zmax) { continue; }
  859. // 邻域内已经存在植株的跳过
  860. bool with_seedling = false;
  861. for (auto&p : cluster_center) {
  862. float d = std::sqrt((p.x - cx) * (p.x - cx) + (p.z - cz) * (p.z - cz));
  863. if (d < 2.0*step_harf) {
  864. with_seedling=true;
  865. break;
  866. }
  867. }
  868. if (!with_seedling) {//保存
  869. pcl::PointXYZ pc(cx,0.0,cz);
  870. candidate_centers.push_back(pc);
  871. }
  872. }
  873. }
  874. //针对每一个candidat_centers的邻域进行检查,检测是否有茎目标
  875. for (auto&pc : candidate_centers) {
  876. }
  877. }
  878. void CRootStockGrabPoint::find_seedling_position(
  879. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  880. std::vector<int> &first_seedling_cloud_idx,
  881. pcl::PointXYZ&xz_center
  882. )
  883. {
  884. // 确定植株inbox范围
  885. float hole_step = m_cparam.rs_grab_seedling_dist - 10.0; //穴盘中穴间距
  886. if (m_dtype == 0) {
  887. hole_step = m_cparam.sc_grab_seedling_dist - 10.0;
  888. }
  889. float hole_step_radius = hole_step / 2.0;
  890. // 点云降维到xz平面,y=0
  891. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2d(new pcl::PointCloud < pcl::PointXYZ>);
  892. pcl::copyPointCloud(*in_cloud, *cloud2d);
  893. for (auto&pt : *cloud2d) {
  894. pt.y = 0.0;
  895. }
  896. /*if(m_cparam.image_show){
  897. viewer_cloud(cloud2d, std::string("cloud2d"));
  898. } */
  899. // 在xz平面内统计点的密度
  900. double radius = m_cparam.rs_grab_stem_diameter;
  901. if (m_dtype == 0) {
  902. radius = m_cparam.sc_grab_stem_diameter;
  903. }
  904. std::vector<int> counter;
  905. pcl::KdTreeFLANN<pcl::PointXYZ> kdtree;
  906. kdtree.setInputCloud(cloud2d);
  907. std::vector<int>idx;
  908. std::vector<float>dist_sqr;
  909. for (size_t i = 0; i < cloud2d->points.size(); ++i) {
  910. int k = kdtree.radiusSearch(cloud2d->points.at(i), radius, idx, dist_sqr);
  911. counter.push_back(k);
  912. }
  913. // 计算根据密度分割的自动阈值
  914. int th = (int)(otsu(counter));
  915. // 得到茎目标的点云序号,和对应的点云cloud2d_pos
  916. std::vector<int> index;
  917. for (size_t i = 0; i < counter.size(); ++i) {
  918. if (counter.at(i) >= th) {
  919. index.push_back(i);
  920. }
  921. }
  922. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2d_pos(new pcl::PointCloud < pcl::PointXYZ>);
  923. pcl::copyPointCloud(*cloud2d, index, *cloud2d_pos);
  924. if (m_pLogger) {
  925. stringstream buff;
  926. buff << "get 2d seedling seed point cloud " << index.size() << " data points with thrreshold " << th;
  927. m_pLogger->INFO(buff.str());
  928. }
  929. if (m_cparam.image_show) {
  930. viewer_cloud(cloud2d_pos, std::string("cloud2d_pos"));
  931. }
  932. //对茎的点云进行clustering,得到不同的茎的分组
  933. double d1 = m_cparam.rs_grab_stem_diameter;
  934. double d2 = m_cparam.rs_grab_stem_diameter * 3.0;
  935. if (m_dtype == 0) {
  936. d1 = m_cparam.sc_grab_stem_diameter;
  937. d2 = m_cparam.sc_grab_stem_diameter * 3.0;
  938. }
  939. std::vector<pcl::PointXYZ>cluster_center;
  940. std::vector<std::vector<int>> cluster_member;
  941. euclidean_clustering_ttsas(cloud2d_pos, d1, d2, cluster_center, cluster_member);
  942. if (m_pLogger) {
  943. stringstream buff;
  944. buff << "euclidean_clustering_ttsas: " << cluster_center.size() << " t1=" << d1
  945. << " t2=" << d2;
  946. m_pLogger->INFO(buff.str());
  947. }
  948. if (m_cparam.image_show) {
  949. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_cluster(new pcl::PointCloud<pcl::PointXYZRGB>);
  950. pcl::copyPointCloud(*cloud2d_pos, *cloud_cluster);
  951. for (auto& pt : *cloud_cluster) {
  952. pt.r = 255;
  953. pt.g = 255;
  954. pt.b = 255;
  955. }
  956. viewer_cloud_cluster(cloud_cluster, cluster_center, std::string("cloud2d_cluster_pos"));
  957. }
  958. // 扩展检测第一排的可能位置,找到倾斜的苗
  959. std::vector<pcl::PointXYZ> tilted_center;
  960. tilted_seedling_discover(cluster_center, tilted_center);
  961. //对每个类别进行检测,剔除不是茎的类别
  962. std::vector<pcl::PointXYZ> clt_root;
  963. std::vector<pcl::PointXYZ> clt_box;
  964. std::vector<std::vector<int> > clt_line_idx;
  965. for (size_t i = 0; i < cluster_center.size(); ++i) {
  966. pcl::PointIndices cluster_idxs;
  967. for (auto idx_clt : cluster_member.at(i)) {
  968. int idx_raw = index.at(idx_clt);
  969. cluster_idxs.indices.push_back(idx_raw);
  970. }
  971. pcl::PointCloud<pcl::PointXYZ>::Ptr clt_cloud(new pcl::PointCloud < pcl::PointXYZ>);
  972. pcl::copyPointCloud(*in_cloud, cluster_idxs, *clt_cloud);
  973. //计算每一个茎的外接矩形
  974. pcl::PointXYZ min_point_aabb;
  975. pcl::PointXYZ max_point_aabb;
  976. pcl::MomentOfInertiaEstimation<pcl::PointXYZ> feature_extractor;
  977. feature_extractor.setInputCloud(clt_cloud);
  978. feature_extractor.compute();
  979. feature_extractor.getAABB(min_point_aabb, max_point_aabb);
  980. //扩展矩形范围
  981. pcl::PointXYZ min_point_aabb_ex;
  982. pcl::PointXYZ max_point_aabb_ex;
  983. min_point_aabb_ex.x = 0.5*(min_point_aabb.x + max_point_aabb.x) - hole_step_radius;
  984. min_point_aabb_ex.y = m_cparam.sc_grab_ymin;
  985. if (m_dtype != 0) { min_point_aabb_ex.y = m_cparam.rs_grab_ymin; }
  986. min_point_aabb_ex.z = 0.5*(min_point_aabb.z + max_point_aabb.z) - hole_step_radius;
  987. max_point_aabb_ex.x = 0.5*(min_point_aabb.x + max_point_aabb.x) + hole_step_radius;
  988. max_point_aabb_ex.y = m_cparam.sc_grab_ymax;
  989. if (m_dtype != 0) { max_point_aabb_ex.y = m_cparam.rs_grab_ymax; }
  990. max_point_aabb_ex.z = 0.5*(min_point_aabb.z + max_point_aabb.z) + hole_step_radius;
  991. /////////////////////////////////
  992. //扩展矩形内直线检测
  993. std::vector<int>line_idx;
  994. find_line_in_cube(in_cloud, min_point_aabb_ex, max_point_aabb_ex, line_idx);
  995. clt_line_idx.push_back(line_idx);
  996. //找到line_idx中y最小的那个点的idx
  997. int line_root_idx = -1;
  998. float line_root_y_min = 10000.0;
  999. for (size_t lidx = 0; lidx < line_idx.size(); ++lidx) {
  1000. int raw_idx = line_idx.at(lidx);
  1001. if (in_cloud->at(raw_idx).y < line_root_y_min) {
  1002. line_root_y_min = in_cloud->at(raw_idx).y;
  1003. line_root_idx = raw_idx;
  1004. }
  1005. }
  1006. //找到底部中心点,然后找到根部坐标
  1007. pcl::PointXYZ pt_root;
  1008. pt_root = in_cloud->at(line_root_idx);
  1009. clt_root.push_back(pt_root);
  1010. clt_box.push_back(min_point_aabb_ex);
  1011. clt_box.push_back(max_point_aabb_ex);
  1012. //viewer_cloud(clt_cloud, std::string("cluster"));
  1013. }
  1014. if (m_cparam.image_show) {
  1015. viewer_cloud_cluster_box(in_cloud, clt_root, clt_box, clt_line_idx, std::string("cloud2d_cluster_box"));
  1016. }
  1017. //sort cluster center, get the frontest leftest one
  1018. std::vector<float> cluster_index;
  1019. for (auto&pt : clt_root) {
  1020. float idx = pt.x - pt.z;
  1021. cluster_index.push_back(idx);
  1022. }
  1023. int first_idx = std::min_element(cluster_index.begin(), cluster_index.end()) - cluster_index.begin();
  1024. if (m_dtype == 0) {
  1025. first_idx = std::max_element(cluster_index.begin(), cluster_index.end()) - cluster_index.begin();
  1026. }
  1027. first_seedling_cloud_idx.clear();
  1028. for (auto&v : clt_line_idx.at(first_idx)) {
  1029. first_seedling_cloud_idx.push_back(v);
  1030. }
  1031. xz_center.x = clt_root.at(first_idx).x;
  1032. xz_center.y = clt_root.at(first_idx).y;
  1033. xz_center.z = clt_root.at(first_idx).z;
  1034. if (m_pLogger) {
  1035. stringstream buff;
  1036. buff << "euclidean_clustering_ttsas, find cluster center(" << xz_center.x
  1037. << ", " << xz_center.y << ", " << xz_center.z << ")";
  1038. m_pLogger->INFO(buff.str());
  1039. }
  1040. }
  1041. void CRootStockGrabPoint::find_line_in_cube(
  1042. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, //输入,整体点云
  1043. pcl::PointXYZ& min_pt_ex, //输入,
  1044. pcl::PointXYZ& max_pt_ex, //输入,
  1045. std::vector<int>& out_idx //输出,直线上点的index, 基于输入整体点云
  1046. )
  1047. {
  1048. out_idx.clear();
  1049. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  1050. pcl::CropBox<pcl::PointXYZ> box_filter;
  1051. std::vector<int>inbox_idx;
  1052. box_filter.setMin(Eigen::Vector4f(min_pt_ex.x, min_pt_ex.y, min_pt_ex.z, 1));
  1053. box_filter.setMax(Eigen::Vector4f(max_pt_ex.x, max_pt_ex.y, max_pt_ex.z, 1));
  1054. box_filter.setNegative(false);
  1055. box_filter.setInputCloud(in_cloud);
  1056. box_filter.filter(inbox_idx);
  1057. pcl::copyPointCloud(*in_cloud, inbox_idx, *cloud_inbox);
  1058. //找到inbox点云中的直线
  1059. float stem_radius = m_cparam.rs_grab_stem_diameter / 2.0;
  1060. if (m_dtype == 0) {
  1061. stem_radius = m_cparam.sc_grab_stem_diameter / 2.0;
  1062. }
  1063. pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
  1064. pcl::PointIndices::Ptr inliers(new pcl::PointIndices);
  1065. pcl::SACSegmentation<pcl::PointXYZ> seg;
  1066. seg.setOptimizeCoefficients(true);
  1067. seg.setModelType(pcl::SACMODEL_LINE);
  1068. seg.setDistanceThreshold(stem_radius);
  1069. seg.setInputCloud(cloud_inbox);
  1070. seg.segment(*inliers, *coefficients);
  1071. int idx_raw = 0;
  1072. for (auto& idx : inliers->indices) {
  1073. idx_raw = inbox_idx.at(idx);
  1074. out_idx.push_back(idx_raw);
  1075. }
  1076. if (m_cparam.image_show) {
  1077. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_line(new pcl::PointCloud<pcl::PointXYZ>);
  1078. pcl::copyPointCloud(*cloud_inbox, *inliers, *cloud_line);
  1079. pcl::visualization::PCLVisualizer::Ptr viewer(new pcl::visualization::PCLVisualizer("line in cluster"));
  1080. viewer->addPointCloud<pcl::PointXYZ>(cloud_inbox, "cluster");
  1081. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 1, 1, "cluster");
  1082. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "cluster");
  1083. viewer->addPointCloud(cloud_line, "fit_line");
  1084. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 0, 1, 0, "fit_line");
  1085. viewer->setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "fit_line");
  1086. while (!viewer->wasStopped()) {
  1087. viewer->spinOnce(100);
  1088. }
  1089. }
  1090. }
  1091. void CRootStockGrabPoint::crop_nn_analysis(
  1092. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  1093. pcl::PointCloud<pcl::PointXYZ>::Ptr seed_cloud,
  1094. double dist_mean,
  1095. std::vector<double>&mass_indices,
  1096. std::vector<int>& candidate_idx
  1097. )
  1098. {
  1099. candidate_idx.clear();
  1100. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  1101. pcl::CropBox<pcl::PointXYZ> box_filter;
  1102. box_filter.setNegative(false);
  1103. box_filter.setInputCloud(in_cloud);
  1104. double radius = 5;
  1105. double rx = 0.8;
  1106. double ry = 1.0;
  1107. double rz = 0.8;
  1108. double cx, cy, cz;
  1109. double dz;
  1110. for (size_t i = 0; i < seed_cloud->points.size(); ++i) {
  1111. cx = seed_cloud->points.at(i).x;
  1112. cy = seed_cloud->points.at(i).y;
  1113. cz = seed_cloud->points.at(i).z;
  1114. box_filter.setMin(Eigen::Vector4f(cx - rx*radius, cy - ry*radius, cz - rz*radius, 1));
  1115. box_filter.setMax(Eigen::Vector4f(cx + rx*radius, cy + ry*radius, cz + rz*radius, 1));
  1116. box_filter.filter(*cloud_inbox);
  1117. //dz
  1118. Eigen::Vector4f min_point;
  1119. Eigen::Vector4f max_point;
  1120. pcl::getMinMax3D(*cloud_inbox, min_point, max_point);
  1121. dz = max_point(2) - min_point(2);
  1122. //project to xy-plane
  1123. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox_xy(new pcl::PointCloud<pcl::PointXYZ>);
  1124. pcl::copyPointCloud(*cloud_inbox, *cloud_inbox_xy);
  1125. for (auto&pt : *cloud_inbox_xy) { pt.z = 0.0; }
  1126. //pca
  1127. double dx_obb;
  1128. double dy_obb;
  1129. double angle_obb;
  1130. cal_obb_2d(cloud_inbox_xy, 0, dx_obb, dy_obb, angle_obb);
  1131. try {
  1132. double dx_grid = dx_obb / dist_mean;
  1133. double dy_grid = dy_obb / dist_mean;
  1134. double dz_grid = dz / dist_mean;
  1135. double fill_ratio = cloud_inbox->points.size() / dx_grid / dy_grid / dz_grid;
  1136. double y_ratio = dy_obb / dx_obb/2;
  1137. y_ratio = pow(y_ratio, 2);
  1138. double a_ratio = cos((angle_obb - 90)*PI / 180.0);
  1139. a_ratio = pow(a_ratio, 3);
  1140. double mass_index = fill_ratio*y_ratio*a_ratio;
  1141. mass_indices.push_back(mass_index);
  1142. if (m_pLogger) {
  1143. stringstream buff;
  1144. buff << i << "/" << seed_cloud->points.size() << " dx=" << dx_obb << ", dy=" << dy_obb << ", fill_ratio=" << fill_ratio
  1145. << ", y_ratio=" << y_ratio << ", a_ratio=" << a_ratio << ", mass_index=" << mass_index;
  1146. m_pLogger->INFO(buff.str());
  1147. }
  1148. }
  1149. catch (...) {
  1150. mass_indices.push_back(0);
  1151. }
  1152. }
  1153. // sort by mass_indices
  1154. std::vector<size_t> sort_idx = sort_indexes_e(mass_indices, false);
  1155. for (auto&v : sort_idx) { candidate_idx.push_back((int)v); }
  1156. }
  1157. void CRootStockGrabPoint::euclidean_clustering_ttsas(
  1158. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  1159. double d1, double d2,
  1160. std::vector<pcl::PointXYZ>&cluster_center,
  1161. std::vector<std::vector<int>> &clustr_member
  1162. )
  1163. {
  1164. if (m_pLogger) {
  1165. stringstream buff;
  1166. buff << "euclidean_clustering_ttsas() begin...";
  1167. m_pLogger->INFO(buff.str());
  1168. }
  1169. std::vector<int> cluster_weight;
  1170. std::vector<int> data_stat;
  1171. std::vector<pcl::PointXYZ>cluster_center_raw;
  1172. std::vector<std::vector<int>> clustr_member_raw;
  1173. for (size_t i = 0; i < in_cloud->points.size(); ++i) { data_stat.push_back(0); }
  1174. size_t data_len = in_cloud->points.size();
  1175. int exists_change = 0;
  1176. int prev_change = 0;
  1177. int cur_change = 0;
  1178. int m = 0;
  1179. while (std::find(data_stat.begin(), data_stat.end(), 0) != data_stat.end()) {
  1180. bool new_while_first = true;
  1181. for (size_t i = 0; i < data_len; ++i) {
  1182. if (data_stat.at(i) == 0 && new_while_first && exists_change == 0) {
  1183. new_while_first = false;
  1184. std::vector<int> idx;
  1185. idx.push_back(i);
  1186. clustr_member_raw.push_back(idx);
  1187. pcl::PointXYZ center;
  1188. center.x = in_cloud->points.at(i).x;
  1189. center.y = in_cloud->points.at(i).y;
  1190. center.z = in_cloud->points.at(i).z;
  1191. cluster_center_raw.push_back(center);
  1192. data_stat.at(i) = 1;
  1193. cur_change += 1;
  1194. cluster_weight.push_back(1);
  1195. m += 1;
  1196. }
  1197. else if (data_stat[i] == 0) {
  1198. std::vector<float> distances;
  1199. for (size_t j = 0; j < clustr_member_raw.size(); ++j) {
  1200. std::vector<float> distances_sub;
  1201. for (size_t jj = 0; jj < clustr_member_raw.at(j).size(); ++jj) {
  1202. size_t ele_idx = clustr_member_raw.at(j).at(jj);
  1203. double d = sqrt(
  1204. (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) +
  1205. (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) +
  1206. (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));
  1207. distances_sub.push_back(d);
  1208. }
  1209. double min_dist = *std::min_element(distances_sub.begin(), distances_sub.end());
  1210. distances.push_back(min_dist);
  1211. }
  1212. int min_idx = std::min_element(distances.begin(), distances.end()) - distances.begin();
  1213. if (distances.at(min_idx) < d1) {
  1214. data_stat.at(i) = 1;
  1215. double w = cluster_weight.at(min_idx);
  1216. cluster_weight.at(min_idx) += 1;
  1217. clustr_member_raw.at(min_idx).push_back(i);
  1218. cluster_center_raw.at(min_idx).x = (cluster_center_raw.at(min_idx).x * w + in_cloud->points.at(i).x) / (w + 1);
  1219. cluster_center_raw.at(min_idx).y = (cluster_center_raw.at(min_idx).y * w + in_cloud->points.at(i).y) / (w + 1);
  1220. cluster_center_raw.at(min_idx).z = (cluster_center_raw.at(min_idx).z * w + in_cloud->points.at(i).z) / (w + 1);
  1221. cur_change += 1;
  1222. }
  1223. else if (distances.at(min_idx) > d2) {
  1224. std::vector<int> idx;
  1225. idx.push_back(i);
  1226. clustr_member_raw.push_back(idx);
  1227. pcl::PointXYZ center;
  1228. center.x = in_cloud->points.at(i).x;
  1229. center.y = in_cloud->points.at(i).y;
  1230. center.z = in_cloud->points.at(i).z;
  1231. cluster_center_raw.push_back(center);
  1232. data_stat.at(i) = 1;
  1233. cur_change += 1;
  1234. cluster_weight.push_back(1);
  1235. m += 1;
  1236. }
  1237. }
  1238. else if (data_stat.at(i)== 1) {
  1239. cur_change += 1;
  1240. }
  1241. }
  1242. exists_change = fabs(cur_change - prev_change);
  1243. prev_change = cur_change;
  1244. cur_change = 0;
  1245. }
  1246. // copy result
  1247. for (size_t i = 0; i < clustr_member_raw.size(); ++i) {
  1248. if (clustr_member_raw.at(i).size() < 20) { continue; }
  1249. cluster_center.push_back(cluster_center_raw.at(i));
  1250. clustr_member.push_back(clustr_member_raw.at(i));
  1251. }
  1252. if (m_pLogger) {
  1253. stringstream buff;
  1254. buff << "euclidean_clustering_ttsas() end";
  1255. m_pLogger->INFO(buff.str());
  1256. }
  1257. }
  1258. void CRootStockGrabPoint::cal_obb_2d(
  1259. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  1260. int axis, //0--xy, 1--zy
  1261. double &dx_obb,
  1262. double &dy_obb,
  1263. double &angle_obb
  1264. )
  1265. {
  1266. // asign value
  1267. Eigen::MatrixXd pts(in_cloud->points.size(), 2);
  1268. for (size_t i = 0; i < in_cloud->points.size(); ++i) {
  1269. if (axis == 0) {
  1270. pts(i, 0) = in_cloud->points.at(i).x;
  1271. }
  1272. else {
  1273. pts(i, 0) = in_cloud->points.at(i).z;
  1274. }
  1275. pts(i, 1) = in_cloud->points.at(i).y;
  1276. }
  1277. // centerlize
  1278. Eigen::MatrixXd mu = pts.colwise().mean();
  1279. Eigen::RowVectorXd mu_row = mu;
  1280. pts.rowwise() -= mu_row;
  1281. //calculate covariance
  1282. Eigen::MatrixXd C = pts.adjoint()*pts;
  1283. C = C.array() / (pts.cols() - 1);
  1284. //compute eig
  1285. Eigen::SelfAdjointEigenSolver<Eigen::MatrixXd> eig(C);
  1286. Eigen::MatrixXd d = eig.eigenvalues();
  1287. Eigen::MatrixXd v = eig.eigenvectors();
  1288. //projection
  1289. Eigen::MatrixXd p = pts * v;
  1290. Eigen::VectorXd minv = p.colwise().minCoeff();
  1291. Eigen::VectorXd maxv = p.colwise().maxCoeff();
  1292. Eigen::VectorXd range = maxv - minv;
  1293. dy_obb = range(1);
  1294. dx_obb = range(0);
  1295. angle_obb = std::atan2(v(1, 1), v(0, 1));
  1296. if (angle_obb < 0) { angle_obb = PI + angle_obb; }
  1297. angle_obb = angle_obb * 180 / PI;
  1298. }
  1299. //void CRootStockGrabPoint::get_optimal_seed(
  1300. // pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  1301. // pcl::PointXYZ&pt,
  1302. // int &pt_idx)
  1303. //{
  1304. // double d1 = m_cparam.rs_grab_stem_diameter;
  1305. // double d2 = m_cparam.rs_grab_stem_diameter * 4.0;
  1306. // if (m_dtype != 0) {
  1307. // d1 = m_cparam.sc_grab_stem_diameter;
  1308. // d2 = m_cparam.sc_grab_stem_diameter * 4.0;
  1309. // }
  1310. // std::vector<pcl::PointXYZ>cluster_center;
  1311. // std::vector<std::vector<int>> cluster_member;
  1312. // euclidean_clustering_ttsas(in_cloud, d1, d2, cluster_center, cluster_member);
  1313. // float min_y_dist = 1.0e6;
  1314. // int opt_idx = -1;
  1315. // int member_size = 5;
  1316. // float y_opt = m_cparam.rs_grab_y_opt;
  1317. // if (m_dtype != 0) {
  1318. // y_opt = m_cparam.sc_grab_y_opt;
  1319. // }
  1320. // for (int i = 0; i < cluster_member.size(); ++i) {
  1321. // if (cluster_member.at(i).size() < member_size) {
  1322. // continue;
  1323. // }
  1324. // if (fabs(cluster_center.at(i).y -y_opt) < min_y_dist) {
  1325. // min_y_dist = fabs(cluster_center.at(i).y - y_opt);
  1326. // opt_idx = i;
  1327. // }
  1328. // }
  1329. // if (opt_idx < 0) {
  1330. // if (m_pLogger) {
  1331. // stringstream buff;
  1332. // buff << "get_optimal_seed failed, get invalid optimal cluster id";
  1333. // m_pLogger->ERRORINFO(buff.str());
  1334. // }
  1335. // return;
  1336. // }
  1337. // //find nearest pt
  1338. // float nearest_dist = 1.0e6;
  1339. // int nearest_idx = -1;
  1340. // for (int i = 0; i < cluster_member.at(opt_idx).size(); ++i) {
  1341. // int idx = cluster_member.at(opt_idx).at(i);
  1342. // float dist = fabs(in_cloud->points.at(idx).x - cluster_center.at(opt_idx).x) +
  1343. // fabs(in_cloud->points.at(idx).y - cluster_center.at(opt_idx).y) +
  1344. // fabs(in_cloud->points.at(idx).z - cluster_center.at(opt_idx).z);
  1345. // if (dist < nearest_dist) {
  1346. // nearest_dist = dist;
  1347. // nearest_idx = idx;
  1348. // }
  1349. // }
  1350. // pt.x = in_cloud->points.at(nearest_idx).x;
  1351. // pt.y = in_cloud->points.at(nearest_idx).y;
  1352. // pt.z = in_cloud->points.at(nearest_idx).z;
  1353. // pt_idx = nearest_idx;
  1354. //}
  1355. void CRootStockGrabPoint::get_optimal_seed(
  1356. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud,
  1357. pcl::PointXYZ&pt,
  1358. int &pt_idx)
  1359. {
  1360. /*double d1 = m_cparam.rs_grab_stem_diameter;
  1361. double d2 = m_cparam.rs_grab_stem_diameter * 4.0;
  1362. if (m_dtype != 0) {
  1363. d1 = m_cparam.sc_grab_stem_diameter;
  1364. d2 = m_cparam.sc_grab_stem_diameter * 4.0;
  1365. }
  1366. std::vector<pcl::PointXYZ>cluster_center;
  1367. std::vector<std::vector<int>> cluster_member;
  1368. euclidean_clustering_ttsas(in_cloud, d1, d2, cluster_center, cluster_member);*/
  1369. float min_y_dist = 1.0e6;
  1370. int opt_idx = -1;
  1371. int member_size = 5;
  1372. float y_opt = m_cparam.rs_grab_y_opt;
  1373. if (m_dtype == 0) {
  1374. y_opt = m_cparam.sc_grab_y_opt;
  1375. }
  1376. for (int i = 0; i < in_cloud->points.size(); ++i) {
  1377. /*if (cluster_member.at(i).size() < member_size) {
  1378. continue;
  1379. }*/
  1380. if (fabs(in_cloud->points.at(i).y - y_opt) < min_y_dist) {
  1381. min_y_dist = fabs(in_cloud->points.at(i).y - y_opt);
  1382. opt_idx = i;
  1383. }
  1384. }
  1385. if (opt_idx < 0) {
  1386. if (m_pLogger) {
  1387. stringstream buff;
  1388. buff << "get_optimal_seed failed, get invalid optimal cluster id";
  1389. m_pLogger->ERRORINFO(buff.str());
  1390. }
  1391. return;
  1392. }
  1393. //find nearest pt
  1394. /*float nearest_dist = 1.0e6;
  1395. int nearest_idx = -1;
  1396. for (int i = 0; i < cluster_member.at(opt_idx).size(); ++i) {
  1397. int idx = cluster_member.at(opt_idx).at(i);
  1398. float dist = fabs(in_cloud->points.at(idx).x - cluster_center.at(opt_idx).x) +
  1399. fabs(in_cloud->points.at(idx).y - cluster_center.at(opt_idx).y) +
  1400. fabs(in_cloud->points.at(idx).z - cluster_center.at(opt_idx).z);
  1401. if (dist < nearest_dist) {
  1402. nearest_dist = dist;
  1403. nearest_idx = idx;
  1404. }
  1405. }*/
  1406. pt.x = in_cloud->points.at(opt_idx).x;
  1407. pt.y = in_cloud->points.at(opt_idx).y;
  1408. pt.z = in_cloud->points.at(opt_idx).z;
  1409. pt_idx = opt_idx;
  1410. }
  1411. //通过比较直线点云和原始点云相同位置邻域内xz的范围,确定此点是否是无干扰点的茎
  1412. void CRootStockGrabPoint::get_optimal_seed_compare(
  1413. pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud, // 全部有效点云
  1414. pcl::PointCloud<pcl::PointXYZ>::Ptr in_line_cloud, // 茎上直线点云
  1415. pcl::PointXYZ&pt, // 返回抓取的点坐标
  1416. int &pt_idx, // 返回点index
  1417. std::vector<int>& valid_line_index // 返回有效直线点index
  1418. )
  1419. {
  1420. valid_line_index.clear();
  1421. float th = 0.75; //原始点云和直线点云邻域尺寸增加原来的20%,不能当做抓取点
  1422. pt_idx = -1;
  1423. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox(new pcl::PointCloud<pcl::PointXYZ>);
  1424. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_inbox_line(new pcl::PointCloud<pcl::PointXYZ>);
  1425. pcl::CropBox<pcl::PointXYZ> box_filter;
  1426. box_filter.setNegative(false);
  1427. box_filter.setInputCloud(in_cloud);
  1428. pcl::CropBox<pcl::PointXYZ> box_filter_line;
  1429. box_filter_line.setNegative(false);
  1430. box_filter_line.setInputCloud(in_line_cloud);
  1431. float radius = m_cparam.rs_grab_stem_diameter;
  1432. float opt_y = m_cparam.rs_grab_y_opt;
  1433. if (m_dtype == 0) {
  1434. radius = m_cparam.sc_grab_stem_diameter;
  1435. opt_y = m_cparam.sc_grab_y_opt;
  1436. }
  1437. float rx = 1.5;
  1438. float ry = 1.5;
  1439. float rz = 1.5;
  1440. float cx, cy, cz;
  1441. float dz,dx, dz_line, dx_line;
  1442. float dist_min = 10000.0;
  1443. for (size_t i = 0; i < in_line_cloud->points.size(); ++i) {
  1444. cx = in_line_cloud->points.at(i).x;
  1445. cy = in_line_cloud->points.at(i).y;
  1446. cz = in_line_cloud->points.at(i).z;
  1447. //////////////////////////////////////////////////////////////////
  1448. //原始点云,获取指定区域的dx,dz
  1449. box_filter.setMin(Eigen::Vector4f(cx - rx*radius, cy - ry*radius, cz - rz*radius, 1));
  1450. box_filter.setMax(Eigen::Vector4f(cx + rx*radius, cy + ry*radius, cz + rz*radius, 1));
  1451. box_filter.filter(*cloud_inbox);
  1452. Eigen::Vector4f min_point;
  1453. Eigen::Vector4f max_point;
  1454. pcl::getMinMax3D(*cloud_inbox, min_point, max_point);
  1455. dz = max_point(2) - min_point(2);
  1456. dx = max_point(0) - min_point(0);
  1457. /////////////////////////////////////////////////////////////////////
  1458. //直线点云,获取指定区域的dx_line,dz_line
  1459. box_filter_line.setMin(Eigen::Vector4f(cx - rx*radius, cy - ry*radius, cz - rz*radius, 1));
  1460. box_filter_line.setMax(Eigen::Vector4f(cx + rx*radius, cy + ry*radius, cz + rz*radius, 1));
  1461. box_filter_line.filter(*cloud_inbox_line);
  1462. pcl::getMinMax3D(*cloud_inbox_line, min_point, max_point);
  1463. dz_line = max_point(2) - min_point(2);
  1464. dx_line = max_point(0) - min_point(0);
  1465. float ratio_ex = (dx + dz - dz_line - dx_line) / (dz_line + dx_line);
  1466. if (ratio_ex < th) {
  1467. valid_line_index.push_back(i);
  1468. if (fabs(cy - opt_y) < dist_min) {
  1469. dist_min = fabs(cy - opt_y);
  1470. pt_idx = i;
  1471. }
  1472. }
  1473. }
  1474. if (pt_idx >= 0) {
  1475. pt = in_line_cloud->points.at(pt_idx);
  1476. }
  1477. }
  1478. void CRootStockGrabPoint::viewer_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, std::string&winname)
  1479. {
  1480. pcl::visualization::CloudViewer viewer(winname);
  1481. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  1482. viewer.showCloud(cloud);
  1483. while (!viewer.wasStopped()) {
  1484. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  1485. }
  1486. }
  1487. void CRootStockGrabPoint::viewer_cloud(pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud, std::string&winname)
  1488. {
  1489. pcl::visualization::CloudViewer viewer(winname);
  1490. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  1491. viewer.showCloud(cloud);
  1492. while (!viewer.wasStopped()) {
  1493. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  1494. }
  1495. }
  1496. void CRootStockGrabPoint::viewer_cloud_debug(
  1497. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
  1498. pcl::PointXYZ &p,
  1499. pcl::PointXYZ &root_pt,
  1500. std::string&winname)
  1501. {
  1502. pcl::visualization::PCLVisualizer viewer(winname);
  1503. //viewer.runOnVisualizationThreadOnce(viewerOneOff);
  1504. viewer.addPointCloud(cloud);
  1505. viewer.addCoordinateSystem();
  1506. pcl::PointXYZ p0, x1, y1,p00,x0,y0, root_px0, root_px1, root_py0,root_py1;
  1507. p0.x = p.x;
  1508. p0.y = p.y;
  1509. p0.z = p.z;
  1510. x1.x = p.x + 100.0;
  1511. x1.y = p.y;
  1512. x1.z = p.z;
  1513. y1.x = p.x;
  1514. y1.y = p.y + 20.0;
  1515. y1.z = p.z;
  1516. p00.x = 0.0;
  1517. p00.y = 0.0;
  1518. p00.z = p.z;
  1519. x0.x = 600.0;
  1520. x0.y = 0;
  1521. x0.z = p.z;
  1522. y0.x = 0.0;
  1523. y0.y = 300.0;
  1524. y0.z = p.z;
  1525. root_px0.x = root_pt.x - 5.0;
  1526. root_px0.y = root_pt.y;
  1527. root_px0.z = root_pt.z;
  1528. root_px1.x = root_pt.x + 5.0;
  1529. root_px1.y = root_pt.y;
  1530. root_px1.z = root_pt.z;
  1531. root_py0.x = root_pt.x;
  1532. root_py0.y = root_pt.y - 5.0;
  1533. root_py0.z = root_pt.z;
  1534. root_py1.x = root_pt.x;
  1535. root_py1.y = root_pt.y + 5.0;
  1536. root_py1.z = root_pt.z;
  1537. viewer.addLine(p0, x1, 255, 0, 0, "x");
  1538. viewer.addLine(p0, y1, 0, 255, 0, "y");
  1539. viewer.addLine(p00, x0, 255, 0, 0, "x0");
  1540. viewer.addLine(p00, y0, 0, 255, 0, "y0");
  1541. viewer.addLine(root_px0, root_px1, 255, 0, 0, "rootx");
  1542. viewer.addLine(root_py0, root_py1, 0, 255, 0, "rooty");
  1543. while (!viewer.wasStopped()) {
  1544. viewer.spinOnce(100);
  1545. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  1546. }
  1547. }
  1548. void CRootStockGrabPoint::viewer_cloud_cluster(
  1549. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud,
  1550. std::vector<pcl::PointXYZ>cluster_center,
  1551. std::string&winname)
  1552. {
  1553. pcl::visualization::PCLVisualizer viewer(winname);
  1554. viewer.addPointCloud(cloud);
  1555. viewer.addCoordinateSystem();
  1556. int cnt = 0;
  1557. char buf[8];
  1558. for (auto& p : cluster_center) {
  1559. pcl::PointXYZ px0, px1, py1, py0;
  1560. px0.x = p.x-5.0;
  1561. px0.y = p.y;
  1562. px0.z = p.z;
  1563. px1.x = p.x + 5.0;
  1564. px1.y = p.y;
  1565. px1.z = p.z;
  1566. py0.x = p.x;
  1567. py0.y = p.y - 5.0;
  1568. py0.z = p.z;
  1569. py1.x = p.x;
  1570. py1.y = p.y + 5.0;
  1571. py1.z = p.z;
  1572. viewer.addLine(px0, px1, 255, 0, 0, "x" + string(_itoa(cnt, buf,10)));
  1573. viewer.addLine(py0, py1, 0, 255, 0, "y" + string(_itoa(cnt, buf, 10)));
  1574. cnt += 1;
  1575. }
  1576. while (!viewer.wasStopped()) {
  1577. viewer.spinOnce(100);
  1578. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  1579. }
  1580. }
  1581. void CRootStockGrabPoint::viewer_cloud_cluster_box(
  1582. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
  1583. std::vector<pcl::PointXYZ>&cluster_center,
  1584. std::vector<pcl::PointXYZ>&cluster_box,
  1585. std::vector<std::vector<int> >& clt_line_idx,
  1586. std::string&winname)
  1587. {
  1588. pcl::visualization::PCLVisualizer viewer(winname);
  1589. viewer.addCoordinateSystem();
  1590. viewer.addPointCloud<pcl::PointXYZ>(cloud, "all_cloud");
  1591. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 1, 1, 1, "all_cloud");
  1592. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 1, "all_cloud");
  1593. int cnt = 0;
  1594. char buf[8];
  1595. for (size_t i = 0; i < cluster_center.size();++i) {
  1596. pcl::PointXYZ &p = cluster_center.at(i);
  1597. pcl::PointXYZ px0, px1, py1, py0;
  1598. px0.x = p.x - 5.0;
  1599. px0.y = p.y;
  1600. px0.z = p.z;
  1601. px1.x = p.x + 5.0;
  1602. px1.y = p.y;
  1603. px1.z = p.z;
  1604. py0.x = p.x;
  1605. py0.y = p.y - 5.0;
  1606. py0.z = p.z;
  1607. py1.x = p.x;
  1608. py1.y = p.y + 5.0;
  1609. py1.z = p.z;
  1610. viewer.addLine(px0, px1, 255, 0, 0, "x" + string(_itoa(cnt, buf, 10)));
  1611. viewer.addLine(py0, py1, 0, 255, 0, "y" + string(_itoa(cnt, buf, 10)));
  1612. //box
  1613. pcl::PointXYZ & min_pt = cluster_box.at(2 * i);
  1614. pcl::PointXYZ & max_pt = cluster_box.at(2 * i + 1);
  1615. 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)));
  1616. viewer.setShapeRenderingProperties(pcl::visualization::PCL_VISUALIZER_REPRESENTATION,
  1617. pcl::visualization::PCL_VISUALIZER_REPRESENTATION_WIREFRAME, "AABB_" + string(_itoa(cnt, buf, 10)));
  1618. pcl::PointCloud<pcl::PointXYZ>::Ptr line_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  1619. //pcl::copyPointCloud(*cloud, clt_line_idx.at(i), *line_cloud);
  1620. viewer.addPointCloud(line_cloud, "fit_line" + string(_itoa(cnt, buf, 10)));
  1621. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_COLOR, 0, 1, 0, "fit_line" + string(_itoa(cnt, buf, 10)));
  1622. viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "fit_line" + string(_itoa(cnt, buf, 10)));
  1623. cnt += 1;
  1624. }
  1625. while (!viewer.wasStopped()) {
  1626. viewer.spinOnce(100);
  1627. boost::this_thread::sleep(boost::posix_time::microseconds(100000));
  1628. }
  1629. }
  1630. };