grab_point_rs.cpp 88 KB

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