ground_region.cpp 22 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657
  1. //
  2. // Created by zx on 2021/5/20.
  3. //
  4. #include "ground_region.h"
  5. #include <pcl/common/transforms.h>
  6. #include <pcl/filters/statistical_outlier_removal.h>
  7. #include <pcl/filters/voxel_grid.h>
  8. #include <pcl/segmentation/extract_clusters.h>
  9. #include <fcntl.h>
  10. #include "publisher.h"
  11. #include "point_tool.h"
  12. //欧式聚类*******************************************************
  13. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> Ground_region::segmentation(pcl::PointCloud<pcl::PointXYZ>::Ptr sor_cloud)
  14. {
  15. std::vector<pcl::PointIndices> ece_inlier;
  16. pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>);
  17. pcl::EuclideanClusterExtraction<pcl::PointXYZ> ece;
  18. ece.setInputCloud(sor_cloud);
  19. ece.setClusterTolerance(0.07);
  20. ece.setMinClusterSize(20);
  21. ece.setMaxClusterSize(20000);
  22. ece.setSearchMethod(tree);
  23. ece.extract(ece_inlier);
  24. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation_clouds;
  25. for (int i = 0; i < ece_inlier.size(); i++)
  26. {
  27. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_copy(new pcl::PointCloud<pcl::PointXYZ>);
  28. std::vector<int> ece_inlier_ext = ece_inlier[i].indices;
  29. copyPointCloud(*sor_cloud, ece_inlier_ext, *cloud_copy);//按照索引提取点云数据
  30. segmentation_clouds.push_back(cloud_copy);
  31. }
  32. return segmentation_clouds;
  33. }
  34. double Ground_region::distance(cv::Point2f p1, cv::Point2f p2)
  35. {
  36. return sqrt(pow(p1.x - p2.x, 2.0) + pow(p1.y - p2.y, 2.0));
  37. }
  38. bool Ground_region::isRect(std::vector<cv::Point2f>& points)
  39. {
  40. if (points.size() == 4)
  41. {
  42. double L[3] = {0.0};
  43. L[0] = distance(points[0], points[1]);
  44. L[1] = distance(points[1], points[2]);
  45. L[2] = distance(points[0], points[2]);
  46. double max_l = L[0];
  47. double l1 = L[1];
  48. double l2 = L[2];
  49. cv::Point2f ps = points[0], pt = points[1];
  50. cv::Point2f pc = points[2];
  51. for (int i = 1; i < 3; ++i) {
  52. if (L[i] > max_l)
  53. {
  54. max_l = L[i];
  55. l1 = L[abs(i + 1) % 3];
  56. l2 = L[abs(i + 2) % 3];
  57. ps = points[i % 3];
  58. pt = points[(i + 1) % 3];
  59. pc = points[(i + 2) % 3];
  60. }
  61. }
  62. //直角边与坐标轴的夹角 <20°
  63. float thresh=20.0*M_PI/180.0;
  64. cv::Point2f vct(pt.x-pc.x,pt.y-pc.y);
  65. float angle=atan2(vct.y,vct.x);
  66. if(!(fabs(angle)<thresh || (M_PI_2-fabs(angle)<thresh)))
  67. {
  68. //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
  69. return false;
  70. }
  71. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  72. if (fabs(cosa) >= 0.15) {
  73. /*char description[255]={0};
  74. sprintf(description,"angle cos value(%.2f) >0.13 ",cosa);
  75. std::cout<<description<<std::endl;*/
  76. return false;
  77. }
  78. float width=std::min(l1,l2);
  79. float length=std::max(l1,l2);
  80. if(width<1.400 || width >1.900 || length >3.300 ||length < 2.200)
  81. {
  82. /*char description[255]={0};
  83. sprintf(description,"width<1400 || width >1900 || length >3300 ||length < 2200 l:%.1f,w:%.1f",length,width);
  84. std::cout<<description<<std::endl;*/
  85. return false;
  86. }
  87. double d = distance(pc, points[3]);
  88. cv::Point2f center1 = (ps + pt) * 0.5;
  89. cv::Point2f center2 = (pc + points[3]) * 0.5;
  90. if (fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150) {
  91. /*std::cout << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2<<std::endl;
  92. char description[255]={0};
  93. sprintf(description,"Verify failed-4 fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150 ");
  94. std::cout<<description<<std::endl;*/
  95. return false;
  96. }
  97. //std::cout << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2<<std::endl;
  98. return true;
  99. }
  100. else if(points.size()==3)
  101. {
  102. double L[3] = {0.0};
  103. L[0] = distance(points[0], points[1]);
  104. L[1] = distance(points[1], points[2]);
  105. L[2] = distance(points[0], points[2]);
  106. double max_l = L[0];
  107. double l1 = L[1];
  108. double l2 = L[2];
  109. int max_index = 0;
  110. cv::Point2f ps = points[0], pt = points[1];
  111. cv::Point2f pc = points[2];
  112. for (int i = 1; i < 3; ++i) {
  113. if (L[i] > max_l) {
  114. max_index = i;
  115. max_l = L[i];
  116. l1 = L[abs(i + 1) % 3];
  117. l2 = L[abs(i + 2) % 3];
  118. ps = points[i % 3];
  119. pt = points[(i + 1) % 3];
  120. pc = points[(i + 2) % 3];
  121. }
  122. }
  123. //直角边与坐标轴的夹角 <20°
  124. float thresh=20.0*M_PI/180.0;
  125. cv::Point2f vct(pt.x-pc.x,pt.y-pc.y);
  126. float angle=atan2(vct.y,vct.x);
  127. if(!(fabs(angle)<thresh || (M_PI_2-fabs(angle)<thresh)))
  128. {
  129. //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
  130. return false;
  131. }
  132. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  133. if (fabs(cosa) >= 0.15) {
  134. /*char description[255]={0};
  135. sprintf(description,"3 wheels angle cos value(%.2f) >0.13 ",cosa);
  136. std::cout<<description<<std::endl;*/
  137. return false;
  138. }
  139. double l=std::max(l1,l2);
  140. double w=std::min(l1,l2);
  141. if(l>2.100 && l<3.300 && w>1.400 && w<2.100)
  142. {
  143. //生成第四个点
  144. cv::Point2f vec1=ps-pc;
  145. cv::Point2f vec2=pt-pc;
  146. cv::Point2f point4=(vec1+vec2)+pc;
  147. points.push_back(point4);
  148. /*char description[255]={0};
  149. sprintf(description,"3 wheels rectangle cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  150. std::cout<<description<<std::endl;*/
  151. return true;
  152. }
  153. else
  154. {
  155. /*char description[255]={0};
  156. sprintf(description,"3 wheels rectangle verify Failed cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  157. std::cout<<description<<std::endl;*/
  158. return false;
  159. }
  160. }
  161. //std::cout<<" default false"<<std::endl;
  162. return false;
  163. }
  164. bool Ground_region::classify_ceres_detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,double thresh_z,
  165. detect_wheel_ceres3d::Detect_result& result)
  166. {
  167. if(m_detector== nullptr)
  168. return false;
  169. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  170. for(int i=0;i<cloud->size();++i)
  171. {
  172. pcl::PointXYZ pt=cloud->points[i];
  173. if(pt.z< thresh_z)
  174. {
  175. cloud_filtered->push_back(pt);
  176. }
  177. }
  178. //下采样
  179. pcl::VoxelGrid<pcl::PointXYZ> vox; //创建滤波对象
  180. vox.setInputCloud(cloud_filtered); //设置需要过滤的点云给滤波对象
  181. vox.setLeafSize(0.02f, 0.02f, 0.2f); //设置滤波时创建的体素体积为1cm的立方体
  182. vox.filter(*cloud_filtered); //执行滤波处理,存储输出
  183. if(cloud_filtered->size()==0)
  184. {
  185. return false;
  186. }
  187. if(cloud_filtered->size()==0)
  188. return false;
  189. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor; //创建滤波器对象
  190. sor.setInputCloud (cloud_filtered); //设置待滤波的点云
  191. sor.setMeanK (5); //设置在进行统计时考虑的临近点个数
  192. sor.setStddevMulThresh (3.0); //设置判断是否为离群点的阀值,用来倍乘标准差,也就是上面的std_mul
  193. sor.filter (*cloud_filtered); //滤波结果存储到cloud_filtered
  194. if(cloud_filtered->size()==0)
  195. {
  196. return false;
  197. }
  198. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> seg_clouds;
  199. seg_clouds=segmentation(cloud_filtered);
  200. if(!(seg_clouds.size()==4 || seg_clouds.size()==3))
  201. {
  202. return false;
  203. }
  204. std::vector<cv::Point2f> centers;
  205. for(int i=0;i<seg_clouds.size();++i)
  206. {
  207. Eigen::Vector4f centroid;
  208. pcl::compute3DCentroid(*seg_clouds[i], centroid);
  209. centers.push_back(cv::Point2f(centroid[0],centroid[1]));
  210. }
  211. bool ret= isRect(centers);
  212. if(ret)
  213. {
  214. std::string error_str;
  215. if(m_detector->detect(seg_clouds,result,error_str))
  216. {
  217. return true;
  218. }
  219. else
  220. {
  221. return false;
  222. }
  223. }
  224. return ret;
  225. }
  226. Ground_region::~Ground_region()
  227. {
  228. m_exit_condition.set_pass_ever(true);
  229. // Close Capturte Thread
  230. if( m_running_thread && m_running_thread->joinable() ){
  231. m_running_thread->join();
  232. m_running_thread->~thread();
  233. delete m_running_thread;
  234. m_running_thread = nullptr;
  235. }
  236. for(int i=0;i<m_lidars.size();++i)
  237. {
  238. if(m_lidars[i]!= nullptr)
  239. {
  240. m_lidars[i]->close();
  241. delete m_lidars[i];
  242. }
  243. }
  244. m_lidars.clear();
  245. if(m_detector)
  246. {
  247. delete m_detector;
  248. m_detector= nullptr;
  249. }
  250. }
  251. Ground_region::Ground_region()
  252. {
  253. m_detector= nullptr ;
  254. m_running_thread=nullptr;
  255. }
  256. Error_manager Ground_region::init(std::string configure_file)
  257. {
  258. if(read_proto_param(configure_file,m_configure)==false)
  259. {
  260. return Error_manager(FAILED,NORMAL,"read proto failed");
  261. }
  262. pcl::PointCloud<pcl::PointXYZ>::Ptr left_model=ReadTxtCloud("/media/youchen/block_ntfs/yct/catkin_ws/src/feature_extra/left_model.txt");
  263. // std::cout << "left model:" << left_model->size() << std::endl;
  264. pcl::PointCloud<pcl::PointXYZ>::Ptr right_model = ReadTxtCloud("/media/youchen/block_ntfs/yct/catkin_ws/src/feature_extra/right_model.txt");
  265. // std::cout << "right model:" << right_model->size() << std::endl;
  266. m_detector=new detect_wheel_ceres3d(left_model,right_model);
  267. // std::cout << "????" << std::endl;
  268. return init(m_configure);
  269. }
  270. Error_manager Ground_region::init(ground_region::Configure configure)
  271. {
  272. //绑定通讯ip
  273. /*char connect_str[255]={0};
  274. sprintf(connect_str,"tcp://%s:%d",configure.communication_cfg().ip().c_str(),
  275. configure.communication_cfg().port());
  276. Publisher::get_instance_pointer()->communication_bind(connect_str);
  277. Publisher::get_instance_pointer()->communication_run();
  278. //创建雷达
  279. m_lidars.resize(configure.lidar_size());
  280. for(int i=0;i<configure.lidar_size();++i)
  281. {
  282. const boost::asio::ip::address address = boost::asio::ip::address::from_string( configure.lidar(i).ip() );
  283. const unsigned short port = configure.lidar(i).port();
  284. m_lidars[i]=new velodyne::VLP16Capture(address,port);
  285. if( !m_lidars[i]->isOpen() ){
  286. char description[255]={0};
  287. sprintf(description,"lidar [%d] open failed ip:%s ,port:%d",i,configure.lidar(i).ip().c_str(),port);
  288. return Error_manager(FAILED,NORMAL,description);
  289. }
  290. }
  291. */
  292. m_configure=configure;
  293. m_running_thread=new std::thread(std::bind(thread_measure_func,this));
  294. return SUCCESS;
  295. }
  296. bool Ground_region::read_proto_param(std::string file, ::google::protobuf::Message& parameter)
  297. {
  298. int fd = open(file.c_str(), O_RDONLY);
  299. if (fd == -1) return false;
  300. FileInputStream* input = new FileInputStream(fd);
  301. bool success = google::protobuf::TextFormat::Parse(input, &parameter);
  302. delete input;
  303. close(fd);
  304. return success;
  305. }
  306. pcl::PointCloud<pcl::PointXYZ>::Ptr Ground_region::scans2cloud(const velodyne::Frame& frame,
  307. const ground_region::Calib_parameter& calib)
  308. {
  309. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
  310. for(int i=0;i<frame.scans.size();++i)
  311. {
  312. pcl::PointXYZ pt;
  313. }
  314. // 变换
  315. Eigen::Matrix3d rotation_matrix3 ;
  316. rotation_matrix3= Eigen::AngleAxisd(calib.r(), Eigen::Vector3d::UnitZ()) *
  317. Eigen::AngleAxisd(calib.p(), Eigen::Vector3d::UnitY()) *
  318. Eigen::AngleAxisd(calib.y(), Eigen::Vector3d::UnitX());
  319. Eigen::Affine3d transform_2 = Eigen::Affine3d::Identity();
  320. transform_2.translation() << calib.cx(),calib.cy(),calib.cz();
  321. transform_2.rotate (rotation_matrix3);
  322. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_transpose(new pcl::PointCloud<pcl::PointXYZ>);
  323. pcl::transformPointCloud (*cloud, *cloud_transpose, transform_2);
  324. return cloud_transpose;
  325. }
  326. Error_manager Ground_region::sync_capture(std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr>& clouds,double timeout_second)
  327. {
  328. Tick timer;
  329. bool sync=false;
  330. clouds.clear();
  331. std::vector<velodyne::Frame> sync_frames;
  332. while((false==m_exit_condition.wait_for_ex(std::chrono::microseconds(1))) && sync==false)
  333. {
  334. bool sync_once=true;
  335. for(int i=0;i<m_lidars.size();++i)
  336. {
  337. velodyne::Frame frame;
  338. m_lidars[i]->get_frame(frame);
  339. if(frame.tic.tic()>0.2)
  340. {
  341. sync_frames.clear();
  342. sync_once=false;
  343. break;
  344. }
  345. else
  346. {
  347. sync_frames.push_back(frame);
  348. }
  349. }
  350. if(timer.tic()>timeout_second)
  351. {
  352. return Error_manager(FAILED,NORMAL,"sync capture time out");
  353. }
  354. sync=sync_once;
  355. usleep(1);
  356. }
  357. if(sync)
  358. {
  359. for(int i=0;i<sync_frames.size();++i)
  360. {
  361. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud=(scans2cloud(sync_frames[i],m_configure.lidar(i).calib()));
  362. clouds.push_back(cloud);
  363. }
  364. return SUCCESS;
  365. }
  366. return FAILED;
  367. }
  368. Error_manager Ground_region::prehandle_cloud(std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr>& clouds,
  369. message::Ground_measure_statu_msg& msg)
  370. {
  371. if(msg.laser_statu_vector_size()!=m_lidars.size())
  372. return ERROR;
  373. //直通滤波
  374. ground_region::Box box = m_configure.box();
  375. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> filtered_cloud_vector;
  376. for (int i = 0; i < clouds.size(); ++i)
  377. {
  378. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  379. for (int j = 0; j < clouds[i]->size(); ++j)
  380. {
  381. pcl::PointXYZ pt = clouds[i]->points[j];
  382. if (pt.x > box.minx() && pt.x < box.maxx()
  383. && pt.y > box.miny() && pt.y < box.maxy()
  384. && pt.z > box.minz() && pt.z < box.maxz())
  385. {
  386. cloud_filtered->push_back(pt);
  387. }
  388. }
  389. filtered_cloud_vector.push_back(cloud_filtered);
  390. }
  391. //根据点云判断雷达状态,若所有雷达滤波后都有点, 则正常,lidar_statu_bit 各个位代表雷达是否有点, 有点为0,无点为1
  392. int lidar_statu_bit = 0;
  393. for (int i = 0; i < filtered_cloud_vector.size(); ++i)
  394. {
  395. if (filtered_cloud_vector[i]->size() == 0)
  396. lidar_statu_bit |= (0x01 << i);
  397. else
  398. msg.set_laser_statu_vector(i, message::LASER_READY);//雷达正常
  399. }
  400. if (lidar_statu_bit == 0)
  401. {
  402. clouds = filtered_cloud_vector;
  403. return SUCCESS;
  404. }
  405. //判断是否有雷达故障
  406. for (int i = 0; i < filtered_cloud_vector.size(); ++i)
  407. {
  408. if (filtered_cloud_vector[i]->size() == 0)
  409. {
  410. //滤波之前也没有点,雷达故障
  411. if (clouds[i]->size() == 0)
  412. {
  413. clouds = filtered_cloud_vector;
  414. msg.set_laser_statu_vector(i, message::LASER_DISCONNECT);
  415. return Error_manager(DISCONNECT, NORMAL, "雷达故障");
  416. }
  417. }
  418. }
  419. //判断是不是所有雷达在该区域都没有点,表示该区域没有东西
  420. int temp = 0;
  421. if (~(((~temp) << (filtered_cloud_vector.size())) | lidar_statu_bit) == 0)
  422. {
  423. clouds = filtered_cloud_vector;
  424. return Error_manager(POINT_EMPTY, NORMAL, "区域无点");
  425. }
  426. else
  427. {
  428. clouds = filtered_cloud_vector;
  429. return Error_manager(CLOUD_INCOMPLETED, NORMAL, "点云不完整(雷达正常)");
  430. }
  431. }
  432. bool computer_var(std::vector<double> data,double& var)
  433. {
  434. if(data.size()==0)
  435. return false;
  436. Eigen::VectorXd dis_vec(data.size());
  437. for(int i=0;i<data.size();++i)
  438. {
  439. dis_vec[i]=data[i];
  440. }
  441. double mean=dis_vec.mean();
  442. Eigen::VectorXd mean_vec(data.size());
  443. Eigen::VectorXd mat=dis_vec-(mean_vec.setOnes()*mean);
  444. Eigen::MatrixXd result=(mat.transpose())*mat;
  445. var=sqrt(result(0)/double(data.size()));
  446. return true;
  447. }
  448. Error_manager Ground_region::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
  449. const ground_region::Box& box,detect_wheel_ceres3d::Detect_result& last_result)
  450. {
  451. if(cloud->size()==0)
  452. return Error_manager(POINT_EMPTY,NORMAL,"no point");
  453. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  454. for(int i=0;i<cloud->size();++i)
  455. {
  456. pcl::PointXYZ pt=cloud->points[i];
  457. if(pt.x>box.minx()&&pt.x<box.maxx()
  458. &&pt.y>box.miny()&&pt.y<box.maxy()
  459. &&pt.z>box.minz()&&pt.z<box.maxz())
  460. {
  461. cloud_filtered->push_back(pt);
  462. }
  463. }
  464. if(cloud_filtered->size()==0)
  465. return Error_manager(POINT_EMPTY,NORMAL,"filtered no point");
  466. float start_z=box.minz();
  467. float max_z=0.2;
  468. float center_z=(start_z+max_z)/2.0;
  469. float last_center_z=start_z;
  470. float last_succ_z=-1.0;
  471. int count=0;
  472. //二分法 找识别成功的 最高的z
  473. std::vector<detect_wheel_ceres3d::Detect_result> results;
  474. do
  475. {
  476. detect_wheel_ceres3d::Detect_result result;
  477. bool ret = classify_ceres_detect(cloud_filtered, center_z,result);
  478. // std::cout << "z: " << center_z <<", "<<start_z<<"," << max_z << std::endl;
  479. if(ret)
  480. {
  481. results.push_back(result);
  482. last_succ_z=center_z;
  483. start_z=center_z;
  484. last_center_z=center_z;
  485. }
  486. else
  487. {
  488. max_z=center_z;
  489. last_center_z=center_z;
  490. }
  491. center_z=(start_z+max_z)/2.0;
  492. count++;
  493. } while (fabs(center_z - last_center_z) > 0.01);
  494. //
  495. if(results.size()==0)
  496. {
  497. return Error_manager(FAILED,NORMAL,"nor car");
  498. }
  499. /// to be
  500. float min_mean_loss=1.0;
  501. for(int i=0;i<results.size();++i)
  502. {
  503. detect_wheel_ceres3d::Detect_result result=results[i];
  504. std::vector<double> loss;
  505. loss.push_back(result.loss.lf_loss);
  506. loss.push_back(result.loss.rf_loss);
  507. loss.push_back(result.loss.lb_loss);
  508. loss.push_back(result.loss.rb_loss);
  509. double mean=(result.loss.lf_loss+result.loss.rf_loss+result.loss.lb_loss+result.loss.rb_loss)/4.0;
  510. double var=-1.;
  511. computer_var(loss,var);
  512. if(mean<min_mean_loss)
  513. {
  514. last_result=result;
  515. min_mean_loss=mean;
  516. }
  517. }
  518. printf("z : %.3f angle : %.3f front : %.3f wheel_base:%.3f,width:%.3f, mean:%.5f\n",
  519. center_z,last_result.theta,last_result.front_theta,last_result.wheel_base,last_result.width,
  520. min_mean_loss);
  521. //m_detector->save_debug_data("/home/zx/zzw/catkin_ws/src/feature_extra/debug");
  522. return SUCCESS;
  523. }
  524. #include "message/message_base.pb.h"
  525. void Ground_region::thread_measure_func(Ground_region* p)
  526. {
  527. return ;
  528. message::Ground_measure_statu_msg msg;
  529. message::Base_info base_info;
  530. base_info.set_msg_type(message::eGround_measure_statu_msg);
  531. base_info.set_sender(message::eEmpty);
  532. base_info.set_receiver(message::eEmpty);
  533. msg.mutable_base_info()->CopyFrom(base_info);
  534. msg.set_ground_statu(message::Nothing);
  535. const float fps=10.;
  536. //保持 10 fps
  537. while(false==p->m_exit_condition.wait_for_millisecond(int(1000./fps)))
  538. {
  539. for(int i=0;i<p->m_lidars.size();++i)
  540. {
  541. msg.add_laser_statu_vector(
  542. p->m_lidars[i]->isRun()?message::LASER_READY:message::LASER_DISCONNECT);
  543. }
  544. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> clouds;
  545. Error_manager code=p->sync_capture(clouds,0.5);
  546. if(code!=SUCCESS)
  547. {
  548. LOG(WARNING)<<code.get_error_description();
  549. continue;
  550. }
  551. Tick tick;
  552. code=p->prehandle_cloud(clouds,msg);
  553. if(code!=SUCCESS)
  554. {
  555. LOG(WARNING)<<code.get_error_description();
  556. continue;
  557. }
  558. detect_wheel_ceres3d::Detect_result result;
  559. pcl::PointCloud<pcl::PointXYZ>::Ptr correct_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  560. for(int i=0;i<clouds.size();++i)
  561. {
  562. *correct_cloud+=(*clouds[i]);
  563. }
  564. code=p->detect(correct_cloud,p->m_configure.box(),result);
  565. if(tick.tic()>1./fps)
  566. {
  567. LOG(WARNING)<<" detect fps < capture fps";
  568. }
  569. if(code!=SUCCESS)
  570. {
  571. LOG_EVERY_N(INFO,20)<<code.get_error_description();
  572. continue;
  573. }
  574. // to be 发布结果
  575. msg.set_ground_statu(message::Car_correct);
  576. message::Locate_information locate_information;
  577. locate_information.set_locate_x(result.cx);
  578. locate_information.set_locate_y(result.cy);
  579. locate_information.set_locate_angle(result.theta);
  580. locate_information.set_locate_wheel_base(result.wheel_base);
  581. locate_information.set_locate_length(result.wheel_base);
  582. locate_information.set_locate_wheel_width(result.width);
  583. locate_information.set_locate_width(result.body_width);
  584. locate_information.set_locate_front_theta(result.front_theta);
  585. locate_information.set_locate_correct(true);
  586. Communication_message c_msg;
  587. c_msg.reset(msg.base_info(),msg.SerializeAsString());
  588. Publisher::get_instance_pointer()->publish_msg(&c_msg);
  589. }
  590. }