grab_point_rs.cpp 90 KB

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