grab_point_rs.cpp 71 KB

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