grab_point_rs.cpp 100 KB

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