ground_region.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423
  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. //欧式聚类*******************************************************
  11. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> Ground_region::segmentation(pcl::PointCloud<pcl::PointXYZ>::Ptr sor_cloud)
  12. {
  13. std::vector<pcl::PointIndices> ece_inlier;
  14. pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>);
  15. pcl::EuclideanClusterExtraction<pcl::PointXYZ> ece;
  16. ece.setInputCloud(sor_cloud);
  17. ece.setClusterTolerance(0.07);
  18. ece.setMinClusterSize(20);
  19. ece.setMaxClusterSize(20000);
  20. ece.setSearchMethod(tree);
  21. ece.extract(ece_inlier);
  22. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation_clouds;
  23. for (int i = 0; i < ece_inlier.size(); i++)
  24. {
  25. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_copy(new pcl::PointCloud<pcl::PointXYZ>);
  26. std::vector<int> ece_inlier_ext = ece_inlier[i].indices;
  27. copyPointCloud(*sor_cloud, ece_inlier_ext, *cloud_copy); //按照索引提取点云数据
  28. segmentation_clouds.push_back(cloud_copy);
  29. }
  30. return segmentation_clouds;
  31. }
  32. /**
  33. * @description: distance between two points
  34. * @param {Point2f} p1
  35. * @param {Point2f} p2
  36. * @return the distance
  37. */
  38. double Ground_region::distance(cv::Point2f p1, cv::Point2f p2)
  39. {
  40. return sqrt(pow(p1.x - p2.x, 2.0) + pow(p1.y - p2.y, 2.0));
  41. }
  42. /**
  43. * @description: point rectangle detect
  44. * @param points detect if points obey the rectangle rule
  45. * @return wether forms a rectangle
  46. */
  47. bool Ground_region::isRect(std::vector<cv::Point2f> &points)
  48. {
  49. if (points.size() == 4)
  50. {
  51. double L[3] = {0.0};
  52. L[0] = distance(points[0], points[1]);
  53. L[1] = distance(points[1], points[2]);
  54. L[2] = distance(points[0], points[2]);
  55. double max_l = L[0];
  56. double l1 = L[1];
  57. double l2 = L[2];
  58. cv::Point2f ps = points[0], pt = points[1];
  59. cv::Point2f pc = points[2];
  60. for (int i = 1; i < 3; ++i)
  61. {
  62. if (L[i] > max_l)
  63. {
  64. max_l = L[i];
  65. l1 = L[abs(i + 1) % 3];
  66. l2 = L[abs(i + 2) % 3];
  67. ps = points[i % 3];
  68. pt = points[(i + 1) % 3];
  69. pc = points[(i + 2) % 3];
  70. }
  71. }
  72. //直角边与坐标轴的夹角 <20°
  73. float thresh = 20.0 * M_PI / 180.0;
  74. cv::Point2f vct(pt.x - pc.x, pt.y - pc.y);
  75. float angle = atan2(vct.y, vct.x);
  76. if (!(fabs(angle) < thresh || (M_PI_2 - fabs(angle) < thresh)))
  77. {
  78. //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
  79. return false;
  80. }
  81. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  82. if (fabs(cosa) >= 0.15)
  83. {
  84. /*char description[255]={0};
  85. sprintf(description,"angle cos value(%.2f) >0.13 ",cosa);
  86. std::cout<<description<<std::endl;*/
  87. return false;
  88. }
  89. float width = std::min(l1, l2);
  90. float length = std::max(l1, l2);
  91. if (width < 1.400 || width > 1.900 || length > 3.300 || length < 2.200)
  92. {
  93. /*char description[255]={0};
  94. sprintf(description,"width<1400 || width >1900 || length >3300 ||length < 2200 l:%.1f,w:%.1f",length,width);
  95. std::cout<<description<<std::endl;*/
  96. return false;
  97. }
  98. double d = distance(pc, points[3]);
  99. cv::Point2f center1 = (ps + pt) * 0.5;
  100. cv::Point2f center2 = (pc + points[3]) * 0.5;
  101. if (fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150)
  102. {
  103. /*std::cout << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2<<std::endl;
  104. char description[255]={0};
  105. sprintf(description,"Verify failed-4 fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150 ");
  106. std::cout<<description<<std::endl;*/
  107. return false;
  108. }
  109. //std::cout << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2<<std::endl;
  110. return true;
  111. }
  112. else if (points.size() == 3)
  113. {
  114. double L[3] = {0.0};
  115. L[0] = distance(points[0], points[1]);
  116. L[1] = distance(points[1], points[2]);
  117. L[2] = distance(points[0], points[2]);
  118. double max_l = L[0];
  119. double l1 = L[1];
  120. double l2 = L[2];
  121. int max_index = 0;
  122. cv::Point2f ps = points[0], pt = points[1];
  123. cv::Point2f pc = points[2];
  124. for (int i = 1; i < 3; ++i)
  125. {
  126. if (L[i] > max_l)
  127. {
  128. max_index = i;
  129. max_l = L[i];
  130. l1 = L[abs(i + 1) % 3];
  131. l2 = L[abs(i + 2) % 3];
  132. ps = points[i % 3];
  133. pt = points[(i + 1) % 3];
  134. pc = points[(i + 2) % 3];
  135. }
  136. }
  137. //直角边与坐标轴的夹角 <20°
  138. float thresh = 20.0 * M_PI / 180.0;
  139. cv::Point2f vct(pt.x - pc.x, pt.y - pc.y);
  140. float angle = atan2(vct.y, vct.x);
  141. if (!(fabs(angle) < thresh || (M_PI_2 - fabs(angle) < thresh)))
  142. {
  143. //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
  144. return false;
  145. }
  146. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  147. if (fabs(cosa) >= 0.15)
  148. {
  149. /*char description[255]={0};
  150. sprintf(description,"3 wheels angle cos value(%.2f) >0.13 ",cosa);
  151. std::cout<<description<<std::endl;*/
  152. return false;
  153. }
  154. double l = std::max(l1, l2);
  155. double w = std::min(l1, l2);
  156. if (l > 2.100 && l < 3.300 && w > 1.400 && w < 2.100)
  157. {
  158. //生成第四个点
  159. cv::Point2f vec1 = ps - pc;
  160. cv::Point2f vec2 = pt - pc;
  161. cv::Point2f point4 = (vec1 + vec2) + pc;
  162. points.push_back(point4);
  163. /*char description[255]={0};
  164. sprintf(description,"3 wheels rectangle cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  165. std::cout<<description<<std::endl;*/
  166. return true;
  167. }
  168. else
  169. {
  170. /*char description[255]={0};
  171. sprintf(description,"3 wheels rectangle verify Failed cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  172. std::cout<<description<<std::endl;*/
  173. return false;
  174. }
  175. }
  176. //std::cout<<" default false"<<std::endl;
  177. return false;
  178. }
  179. /**
  180. * @description: 3d wheel detect core func
  181. * @param cloud input cloud for measure
  182. * @param thresh_z z value to cut wheel
  183. * @param result detect result
  184. * @return wether successfully detected
  185. */
  186. bool Ground_region::classify_ceres_detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double thresh_z,
  187. detect_wheel_ceres3d::Detect_result &result)
  188. {
  189. if (m_detector == nullptr)
  190. return false;
  191. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  192. for (int i = 0; i < cloud->size(); ++i)
  193. {
  194. pcl::PointXYZ pt = cloud->points[i];
  195. if (pt.z < thresh_z)
  196. {
  197. cloud_filtered->push_back(pt);
  198. }
  199. }
  200. //下采样
  201. pcl::VoxelGrid<pcl::PointXYZ> vox; //创建滤波对象
  202. vox.setInputCloud(cloud_filtered); //设置需要过滤的点云给滤波对象
  203. vox.setLeafSize(0.02f, 0.02f, 0.2f); //设置滤波时创建的体素体积为1cm的立方体
  204. vox.filter(*cloud_filtered); //执行滤波处理,存储输出
  205. if (cloud_filtered->size() == 0)
  206. {
  207. return false;
  208. }
  209. if (cloud_filtered->size() == 0)
  210. return false;
  211. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor; //创建滤波器对象
  212. sor.setInputCloud(cloud_filtered); //设置待滤波的点云
  213. sor.setMeanK(5); //设置在进行统计时考虑的临近点个数
  214. sor.setStddevMulThresh(3.0); //设置判断是否为离群点的阀值,用来倍乘标准差,也就是上面的std_mul
  215. sor.filter(*cloud_filtered); //滤波结果存储到cloud_filtered
  216. if (cloud_filtered->size() == 0)
  217. {
  218. return false;
  219. }
  220. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> seg_clouds;
  221. seg_clouds = segmentation(cloud_filtered);
  222. if (!(seg_clouds.size() == 4 || seg_clouds.size() == 3))
  223. {
  224. return false;
  225. }
  226. std::vector<cv::Point2f> centers;
  227. for (int i = 0; i < seg_clouds.size(); ++i)
  228. {
  229. Eigen::Vector4f centroid;
  230. pcl::compute3DCentroid(*seg_clouds[i], centroid);
  231. centers.push_back(cv::Point2f(centroid[0], centroid[1]));
  232. }
  233. bool ret = isRect(centers);
  234. if (ret)
  235. {
  236. std::string error_str;
  237. if (m_detector->detect(seg_clouds, result, error_str))
  238. {
  239. return true;
  240. }
  241. else
  242. {
  243. return false;
  244. }
  245. }
  246. return ret;
  247. }
  248. // constructor
  249. Ground_region::Ground_region()
  250. {
  251. m_detector = nullptr;
  252. m_measure_thread = nullptr;
  253. }
  254. // deconstructor
  255. Ground_region::~Ground_region()
  256. {
  257. if(m_measure_thread){
  258. m_measure_condition.kill_all();
  259. // Close Capturte Thread
  260. if (m_measure_thread->joinable())
  261. {
  262. m_measure_thread->join();
  263. delete m_measure_thread;
  264. m_measure_thread = nullptr;
  265. }
  266. }
  267. }
  268. Error_manager Ground_region::init(velodyne::Region region)
  269. {
  270. m_region = region;
  271. m_measure_thread = new std::thread(&Ground_region::thread_measure_func, this);
  272. return SUCCESS;
  273. }
  274. // 计算均方误差
  275. bool computer_var(std::vector<double> data, double &var)
  276. {
  277. if (data.size() == 0)
  278. return false;
  279. Eigen::VectorXd dis_vec(data.size());
  280. for (int i = 0; i < data.size(); ++i)
  281. {
  282. dis_vec[i] = data[i];
  283. }
  284. double mean = dis_vec.mean();
  285. Eigen::VectorXd mean_vec(data.size());
  286. Eigen::VectorXd mat = dis_vec - (mean_vec.setOnes() * mean);
  287. Eigen::MatrixXd result = (mat.transpose()) * mat;
  288. var = sqrt(result(0) / double(data.size()));
  289. return true;
  290. }
  291. Error_manager Ground_region::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, detect_wheel_ceres3d::Detect_result &last_result)
  292. {
  293. if (cloud->size() == 0)
  294. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NORMAL, "no point");
  295. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  296. for (int i = 0; i < cloud->size(); ++i)
  297. {
  298. pcl::PointXYZ pt = cloud->points[i];
  299. if (pt.x > m_region.minx() && pt.x < m_region.maxx() && pt.y > m_region.miny() && pt.y < m_region.maxy() && pt.z > m_region.minz() && pt.z < m_region.maxz())
  300. {
  301. cloud_filtered->push_back(pt);
  302. }
  303. }
  304. if (cloud_filtered->size() == 0)
  305. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NORMAL, "filtered no point");
  306. float start_z = m_region.minz();
  307. float max_z = 0.2;
  308. float center_z = (start_z + max_z) / 2.0;
  309. float last_center_z = start_z;
  310. float last_succ_z = -1.0;
  311. int count = 0;
  312. //二分法 找识别成功的 最高的z
  313. std::vector<detect_wheel_ceres3d::Detect_result> results;
  314. do
  315. {
  316. detect_wheel_ceres3d::Detect_result result;
  317. bool ret = classify_ceres_detect(cloud_filtered, center_z, result);
  318. // std::cout << "z: " << center_z <<", "<<start_z<<"," << max_z << std::endl;
  319. if (ret)
  320. {
  321. results.push_back(result);
  322. last_succ_z = center_z;
  323. start_z = center_z;
  324. last_center_z = center_z;
  325. }
  326. else
  327. {
  328. max_z = center_z;
  329. last_center_z = center_z;
  330. }
  331. center_z = (start_z + max_z) / 2.0;
  332. count++;
  333. } while (fabs(center_z - last_center_z) > 0.01);
  334. //
  335. if (results.size() == 0)
  336. {
  337. return Error_manager(FAILED, NORMAL, "no car detected");
  338. }
  339. /// to be
  340. float min_mean_loss = 1.0;
  341. for (int i = 0; i < results.size(); ++i)
  342. {
  343. detect_wheel_ceres3d::Detect_result result = results[i];
  344. std::vector<double> loss;
  345. loss.push_back(result.loss.lf_loss);
  346. loss.push_back(result.loss.rf_loss);
  347. loss.push_back(result.loss.lb_loss);
  348. loss.push_back(result.loss.rb_loss);
  349. double mean = (result.loss.lf_loss + result.loss.rf_loss + result.loss.lb_loss + result.loss.rb_loss) / 4.0;
  350. double var = -1.;
  351. computer_var(loss, var);
  352. if (mean < min_mean_loss)
  353. {
  354. last_result = result;
  355. min_mean_loss = mean;
  356. }
  357. }
  358. printf("z : %.3f angle : %.3f front : %.3f wheel_base:%.3f,width:%.3f, mean:%.5f\n",
  359. center_z, last_result.theta, last_result.front_theta, last_result.wheel_base, last_result.width,
  360. min_mean_loss);
  361. //m_detector->save_debug_data("/home/zx/zzw/catkin_ws/src/feature_extra/debug");
  362. return SUCCESS;
  363. }
  364. #include "message/message_base.pb.h"
  365. void Ground_region::thread_measure_func()
  366. {
  367. //保持 10 fps
  368. while (m_measure_condition.is_alive())
  369. {
  370. m_measure_condition.wait();
  371. if (m_measure_condition.is_alive())
  372. {
  373. // to be 发布结果
  374. msg.set_ground_statu(message::Car_correct);
  375. message::Locate_information locate_information;
  376. locate_information.set_locate_x(result.cx);
  377. locate_information.set_locate_y(result.cy);
  378. locate_information.set_locate_angle(result.theta);
  379. locate_information.set_locate_wheel_base(result.wheel_base);
  380. locate_information.set_locate_length(result.wheel_base);
  381. locate_information.set_locate_wheel_width(result.width);
  382. locate_information.set_locate_width(result.body_width);
  383. locate_information.set_locate_front_theta(result.front_theta);
  384. locate_information.set_locate_correct(true);
  385. Communication_message c_msg;
  386. c_msg.reset(msg.base_info(), msg.SerializeAsString());
  387. Publisher::get_instance_pointer()->publish_msg(&c_msg);
  388. }
  389. }
  390. }