grab_point_rs.cpp 62 KB

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