grab_point_rs.cpp 59 KB

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