grab_point_rs.cpp 101 KB

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