ground_region.cpp 41 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951
  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 "../tool/point_tool.h"
  11. // 测量结果滤波,不影响现有结构
  12. #include "../tool/measure_filter.h"
  13. // 增加车辆停止状态判断
  14. #include "../tool/region_status_checker.h"
  15. #include "../system/system_communication_mq.h"
  16. //欧式聚类*******************************************************
  17. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> Ground_region::segmentation(pcl::PointCloud<pcl::PointXYZ>::Ptr sor_cloud)
  18. {
  19. std::vector<pcl::PointIndices> ece_inlier;
  20. pcl::search::KdTree<pcl::PointXYZ>::Ptr tree(new pcl::search::KdTree<pcl::PointXYZ>);
  21. pcl::EuclideanClusterExtraction<pcl::PointXYZ> ece;
  22. ece.setInputCloud(sor_cloud);
  23. ece.setClusterTolerance(0.07);
  24. ece.setMinClusterSize(20);
  25. ece.setMaxClusterSize(20000);
  26. ece.setSearchMethod(tree);
  27. ece.extract(ece_inlier);
  28. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> segmentation_clouds;
  29. for (int i = 0; i < ece_inlier.size(); i++)
  30. {
  31. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_copy(new pcl::PointCloud<pcl::PointXYZ>);
  32. std::vector<int> ece_inlier_ext = ece_inlier[i].indices;
  33. copyPointCloud(*sor_cloud, ece_inlier_ext, *cloud_copy); //按照索引提取点云数据
  34. segmentation_clouds.push_back(cloud_copy);
  35. }
  36. return segmentation_clouds;
  37. }
  38. // /**
  39. // * @description: distance between two points
  40. // * @param {Point2f} p1
  41. // * @param {Point2f} p2
  42. // * @return the distance
  43. // */
  44. // double Ground_region::distance(cv::Point2f p1, cv::Point2f p2)
  45. // {
  46. // return sqrt(pow(p1.x - p2.x, 2.0) + pow(p1.y - p2.y, 2.0));
  47. // }
  48. /**
  49. * @description: point rectangle detect
  50. * @param points detect if points obey the rectangle rule
  51. * @return wether forms a rectangle
  52. */
  53. bool Ground_region::isRect(std::vector<cv::Point2f> &points)
  54. {
  55. if (points.size() == 4)
  56. {
  57. double L[3] = {0.0};
  58. L[0] = distance(points[0], points[1]);
  59. L[1] = distance(points[1], points[2]);
  60. L[2] = distance(points[0], points[2]);
  61. double max_l = L[0];
  62. double l1 = L[1];
  63. double l2 = L[2];
  64. cv::Point2f ps = points[0], pt = points[1];
  65. cv::Point2f pc = points[2];
  66. for (int i = 1; i < 3; ++i)
  67. {
  68. if (L[i] > max_l)
  69. {
  70. max_l = L[i];
  71. l1 = L[abs(i + 1) % 3];
  72. l2 = L[abs(i + 2) % 3];
  73. ps = points[i % 3];
  74. pt = points[(i + 1) % 3];
  75. pc = points[(i + 2) % 3];
  76. }
  77. }
  78. //直角边与坐标轴的夹角 <20°
  79. float thresh = 20.0 * M_PI / 180.0;
  80. cv::Point2f vct(pt.x - pc.x, pt.y - pc.y);
  81. float angle = atan2(vct.y, vct.x);
  82. if (!(fabs(angle) < thresh || (M_PI_2 - fabs(angle) < thresh)))
  83. {
  84. //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
  85. return false;
  86. }
  87. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  88. if (fabs(cosa) >= 0.15)
  89. {
  90. /*char description[255]={0};
  91. sprintf(description,"angle cos value(%.2f) >0.13 ",cosa);
  92. std::cout<<description<<std::endl;*/
  93. return false;
  94. }
  95. float width = std::min(l1, l2);
  96. float length = std::max(l1, l2);
  97. if (width < 1.400 || width > 1.900 || length > 3.300 || length < 2.200)
  98. {
  99. /*char description[255]={0};
  100. sprintf(description,"width<1400 || width >1900 || length >3300 ||length < 2200 l:%.1f,w:%.1f",length,width);
  101. std::cout<<description<<std::endl;*/
  102. return false;
  103. }
  104. double d = distance(pc, points[3]);
  105. cv::Point2f center1 = (ps + pt) * 0.5;
  106. cv::Point2f center2 = (pc + points[3]) * 0.5;
  107. if (fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150)
  108. {
  109. /*std::cout << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2<<std::endl;
  110. char description[255]={0};
  111. sprintf(description,"Verify failed-4 fabs(d - max_l) > max_l * 0.1 || distance(center1, center2) > 0.150 ");
  112. std::cout<<description<<std::endl;*/
  113. return false;
  114. }
  115. //std::cout << "d:" << d << " maxl:" << max_l << " center1:" << center1 << " center2:" << center2<<std::endl;
  116. return true;
  117. }
  118. else if (points.size() == 3)
  119. {
  120. double L[3] = {0.0};
  121. L[0] = distance(points[0], points[1]);
  122. L[1] = distance(points[1], points[2]);
  123. L[2] = distance(points[0], points[2]);
  124. double max_l = L[0];
  125. double l1 = L[1];
  126. double l2 = L[2];
  127. int max_index = 0;
  128. cv::Point2f ps = points[0], pt = points[1];
  129. cv::Point2f pc = points[2];
  130. for (int i = 1; i < 3; ++i)
  131. {
  132. if (L[i] > max_l)
  133. {
  134. max_index = i;
  135. max_l = L[i];
  136. l1 = L[abs(i + 1) % 3];
  137. l2 = L[abs(i + 2) % 3];
  138. ps = points[i % 3];
  139. pt = points[(i + 1) % 3];
  140. pc = points[(i + 2) % 3];
  141. }
  142. }
  143. //直角边与坐标轴的夹角 <20°
  144. float thresh = 20.0 * M_PI / 180.0;
  145. cv::Point2f vct(pt.x - pc.x, pt.y - pc.y);
  146. float angle = atan2(vct.y, vct.x);
  147. if (!(fabs(angle) < thresh || (M_PI_2 - fabs(angle) < thresh)))
  148. {
  149. //std::cout<<" 4 wheel axis angle : "<<angle<<std::endl;
  150. return false;
  151. }
  152. double cosa = (l1 * l1 + l2 * l2 - max_l * max_l) / (2.0 * l1 * l2);
  153. if (fabs(cosa) >= 0.15)
  154. {
  155. /*char description[255]={0};
  156. sprintf(description,"3 wheels angle cos value(%.2f) >0.13 ",cosa);
  157. std::cout<<description<<std::endl;*/
  158. return false;
  159. }
  160. double l = std::max(l1, l2);
  161. double w = std::min(l1, l2);
  162. if (l > 2.100 && l < 3.300 && w > 1.400 && w < 2.100)
  163. {
  164. //生成第四个点
  165. cv::Point2f vec1 = ps - pc;
  166. cv::Point2f vec2 = pt - pc;
  167. cv::Point2f point4 = (vec1 + vec2) + pc;
  168. points.push_back(point4);
  169. /*char description[255]={0};
  170. sprintf(description,"3 wheels rectangle cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  171. std::cout<<description<<std::endl;*/
  172. return true;
  173. }
  174. else
  175. {
  176. /*char description[255]={0};
  177. sprintf(description,"3 wheels rectangle verify Failed cos angle=%.2f,L=%.1f, w=%.1f",cosa,l,w);
  178. std::cout<<description<<std::endl;*/
  179. return false;
  180. }
  181. }
  182. //std::cout<<" default false"<<std::endl;
  183. return false;
  184. }
  185. /**
  186. * @description: 3d wheel detect core func
  187. * @param cloud input cloud for measure
  188. * @param thresh_z z value to cut wheel
  189. * @param result detect result
  190. * @return wether successfully detected
  191. */
  192. bool Ground_region::classify_ceres_detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double thresh_z,
  193. detect_wheel_ceres3d::Detect_result &result)
  194. {
  195. if (m_detector == nullptr)
  196. return false;
  197. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  198. for (int i = 0; i < cloud->size(); ++i)
  199. {
  200. pcl::PointXYZ pt = cloud->points[i];
  201. if (pt.z < thresh_z)
  202. {
  203. cloud_filtered->push_back(pt);
  204. }
  205. }
  206. //下采样
  207. pcl::VoxelGrid<pcl::PointXYZ> vox; //创建滤波对象
  208. vox.setInputCloud(cloud_filtered); //设置需要过滤的点云给滤波对象
  209. vox.setLeafSize(0.01f, 0.01f, 0.01f); //设置滤波时创建的体素体积为1cm的立方体
  210. vox.filter(*cloud_filtered); //执行滤波处理,存储输出
  211. if (cloud_filtered->size() == 0)
  212. {
  213. return false;
  214. }
  215. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor; //创建滤波器对象
  216. sor.setInputCloud(cloud_filtered); //设置待滤波的点云
  217. sor.setMeanK(5); //设置在进行统计时考虑的临近点个数
  218. sor.setStddevMulThresh(3.0); //设置判断是否为离群点的阀值,用来倍乘标准差,也就是上面的std_mul
  219. sor.filter(*cloud_filtered); //滤波结果存储到cloud_filtered
  220. if (cloud_filtered->size() == 0)
  221. {
  222. return false;
  223. }
  224. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> seg_clouds;
  225. seg_clouds = segmentation(cloud_filtered);
  226. if (!(seg_clouds.size() == 4 || seg_clouds.size() == 3))
  227. {
  228. return false;
  229. }
  230. std::vector<cv::Point2f> centers;
  231. cv::Point2f temp_centers(0,0);
  232. for (int i = 0; i < seg_clouds.size(); ++i)
  233. {
  234. Eigen::Vector4f centroid;
  235. pcl::compute3DCentroid(*seg_clouds[i], centroid);
  236. centers.push_back(cv::Point2f(centroid[0], centroid[1]));
  237. temp_centers += cv::Point2f(centroid[0], centroid[1]);
  238. }
  239. temp_centers /= 4.0f;
  240. bool ret = isRect(centers);
  241. if (ret)
  242. {
  243. std::string error_str;
  244. // LOG(WARNING) << "region id: "<< m_region.region_id();
  245. if (m_detector->detect(seg_clouds, result, error_str))
  246. {
  247. return true;
  248. }
  249. else
  250. {
  251. // LOG(WARNING) << error_str;
  252. return false;
  253. }
  254. }
  255. return ret;
  256. }
  257. // constructor
  258. Ground_region::Ground_region()
  259. {
  260. m_region_status = E_UNKNOWN;
  261. m_detector = nullptr;
  262. m_measure_thread = nullptr;
  263. }
  264. // deconstructor
  265. Ground_region::~Ground_region()
  266. {
  267. // LOG(WARNING) << "start deconstruct ground region";
  268. if (m_measure_thread)
  269. {
  270. m_measure_condition.kill_all();
  271. // Close Capturte Thread
  272. if (m_measure_thread->joinable())
  273. {
  274. m_measure_thread->join();
  275. delete m_measure_thread;
  276. m_measure_thread = nullptr;
  277. }
  278. }
  279. // LOG(WARNING) << "thread released";
  280. // 将创建的检测器析构
  281. if(m_detector)
  282. {
  283. delete m_detector;
  284. m_detector = nullptr;
  285. }
  286. Region_status_checker::get_instance_references().Region_status_checker_uninit();
  287. // LOG(WARNING) << "detector released";
  288. }
  289. Error_manager Ground_region::init(velodyne::Region region, pcl::PointCloud<pcl::PointXYZ>::Ptr left_model, pcl::PointCloud<pcl::PointXYZ>::Ptr right_model)
  290. {
  291. Region_status_checker::get_instance_references().Region_status_checker_init();
  292. m_region = region;
  293. m_detector = new detect_wheel_ceres3d(left_model,right_model);
  294. mp_cloud_collection = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  295. mp_cloud_filtered = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  296. mp_cloud_detect_z = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  297. m_measure_thread = new std::thread(&Ground_region::thread_measure_func, this);
  298. m_measure_condition.reset();
  299. m_region_status = E_READY;
  300. return SUCCESS;
  301. }
  302. // 计算均方误差
  303. bool computer_var(std::vector<double> data, double &var)
  304. {
  305. if (data.size() == 0)
  306. return false;
  307. Eigen::VectorXd dis_vec(data.size());
  308. for (int i = 0; i < data.size(); ++i)
  309. {
  310. dis_vec[i] = data[i];
  311. }
  312. double mean = dis_vec.mean();
  313. Eigen::VectorXd mean_vec(data.size());
  314. Eigen::VectorXd mat = dis_vec - (mean_vec.setOnes() * mean);
  315. Eigen::MatrixXd result = (mat.transpose()) * mat;
  316. var = sqrt(result(0) / double(data.size()));
  317. return true;
  318. }
  319. Error_manager Ground_region::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, detect_wheel_ceres3d::Detect_result &last_result)
  320. {
  321. // 1.*********点云合法性检验*********
  322. if (cloud->size() == 0){
  323. // 更新过滤点
  324. m_filtered_cloud_mutex.lock();
  325. mp_cloud_filtered->clear();
  326. m_filtered_cloud_mutex.unlock();
  327. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "no input point");
  328. }
  329. // 2.*********点云预处理*********
  330. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  331. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cut(new pcl::PointCloud<pcl::PointXYZ>);
  332. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_clean(new pcl::PointCloud<pcl::PointXYZ>);
  333. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  334. for (int i = 0; i < cloud->size(); ++i)
  335. {
  336. pcl::PointXYZ pt = cloud->points[i];
  337. 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())
  338. {
  339. cloud_cut->push_back(pt);
  340. }
  341. }
  342. if(cloud_cut->size() <= 0)
  343. {
  344. // 更新过滤点
  345. m_filtered_cloud_mutex.lock();
  346. mp_cloud_filtered->clear();
  347. m_filtered_cloud_mutex.unlock();
  348. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "cut no point");
  349. }
  350. //下采样
  351. pcl::VoxelGrid<pcl::PointXYZ> vox; //创建滤波对象
  352. vox.setInputCloud(cloud_cut); //设置需要过滤的点云给滤波对象
  353. vox.setLeafSize(0.02f, 0.02f, 0.02f); //设置滤波时创建的体素体积为1cm的立方体
  354. vox.filter(*cloud_clean); //执行滤波处理,存储输出
  355. // cloud_filtered = cloud_clean;
  356. if (cloud_clean->size() == 0){
  357. // 更新过滤点
  358. m_filtered_cloud_mutex.lock();
  359. mp_cloud_filtered->clear();
  360. m_filtered_cloud_mutex.unlock();
  361. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "ApproximateVoxelGrid no point");
  362. }
  363. //离群点过滤
  364. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
  365. sor.setInputCloud(cloud_clean);
  366. sor.setMeanK(5); //K近邻搜索点个数
  367. sor.setStddevMulThresh(3.0); //标准差倍数
  368. sor.setNegative(false); //保留未滤波点(内点)
  369. sor.filter(*cloud_filtered); //保存滤波结果到cloud_filter
  370. if (cloud_filtered->size() == 0){
  371. // 更新过滤点
  372. m_filtered_cloud_mutex.lock();
  373. mp_cloud_filtered->clear();
  374. m_filtered_cloud_mutex.unlock();
  375. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "StatisticalOutlierRemoval no point");
  376. }
  377. // 更新过滤点
  378. m_filtered_cloud_mutex.lock();
  379. mp_cloud_filtered->clear();
  380. mp_cloud_filtered->operator+=(*cloud_filtered);
  381. m_filtered_cloud_mutex.unlock();
  382. // 3.*********位姿优化,获取中心xy与角度*********
  383. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_detect_z(new pcl::PointCloud<pcl::PointXYZ>);
  384. double car_pose_x, car_pose_y, car_pose_theta, car_pose_width, z_value=0.2;
  385. // if(!Car_pose_detector::get_instance_references().detect_pose(cloud_filtered, cloud_detect_z, car_pose_x, car_pose_y, car_pose_theta, car_pose_width, z_value, false))
  386. if(!Car_pose_detector::get_instance_references().detect_pose_mat(cloud_filtered, cloud_detect_z, car_pose_x, car_pose_y, car_pose_theta, false))
  387. {
  388. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, "find general car pose value failed.");
  389. }
  390. // LOG_IF(INFO, m_region.region_id() == 0) << "car pose :::: cx: " << car_pose_x+m_region.plc_offsetx() << ", cy: " << car_pose_y+m_region.plc_offsety() << ", theta: " << car_pose_theta*180.0/M_PI << std::endl;
  391. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  392. std::chrono::duration<double> time_used_bowl = std::chrono::duration_cast<std::chrono::duration<double>>(t2 - t1);
  393. // 4.*********xoz优化获取底盘高度*********
  394. // 重新取包含地面点的点云,用于底盘优化
  395. double z_solver_x = car_pose_x;
  396. double z_solver_y = car_pose_y;
  397. double z_solver_theta = car_pose_theta;
  398. double z_solver_width = 1.0;
  399. chassis_ceres_solver t_solver;
  400. // !!!重新筛选地面点并滤波,融入第一步位姿使用的滤波后点云,传入第二步获取底盘高度
  401. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_z_solver(new pcl::PointCloud<pcl::PointXYZ>);
  402. for (int i = 0; i < cloud->size(); ++i)
  403. {
  404. pcl::PointXYZ pt = cloud->points[i];
  405. 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())
  406. {
  407. cloud_z_solver->push_back(pt);
  408. }
  409. }
  410. if (cloud_z_solver->size() == 0){
  411. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "cloud z no point for outlier removal");
  412. }
  413. //离群点过滤
  414. sor.setInputCloud(cloud_z_solver);
  415. sor.setMeanK(5); //K近邻搜索点个数
  416. sor.setStddevMulThresh(3.0); //标准差倍数
  417. sor.setNegative(false); //保留未滤波点(内点)
  418. sor.filter(*cloud_z_solver); //保存滤波结果到cloud_filter
  419. // 补上车身与车轮点
  420. cloud_z_solver->operator+=(*mp_cloud_filtered);
  421. // 去中心,角度调正
  422. Car_pose_detector::get_instance_references().inv_trans_cloud(cloud_z_solver, z_solver_x, z_solver_y, z_solver_theta);
  423. if (cloud_z_solver->size() == 0)
  424. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NORMAL, "z solver no point");
  425. // 给予底盘z中心与高度初值
  426. double mid_z = 0.05, height = 0.08;
  427. z_solver_x = 0.0;
  428. // Error_manager ec = t_solver.solve(cloud_z_solver, z_solver_x, mid_z, z_solver_width, height);
  429. Error_manager ec = t_solver.solve_mat(cloud_z_solver, z_solver_x, mid_z, z_solver_width, height, false);
  430. // 切除大于height高度以外点,并显示width直线
  431. // 根据z值切原始点云
  432. pcl::PassThrough<pcl::PointXYZ> pass;
  433. pass.setInputCloud(cloud_z_solver);
  434. pass.setFilterFieldName("z");
  435. pass.setFilterLimits(m_region.minz(), mid_z + height / 2.0);
  436. pass.setFilterLimitsNegative(false);
  437. pass.filter(*cloud_z_solver);
  438. // // 车宽方向画线
  439. // for (double i = -3.0; i < 3.0; i+=0.02)
  440. // {
  441. // cloud_z_solver->push_back(pcl::PointXYZ(-width/2.0, i, 0));
  442. // cloud_z_solver->push_back(pcl::PointXYZ(width/2.0, i, 0));
  443. // }
  444. // std::cout << "\n------------------------------------ chassis z1: " << mid_z + height / 2.0 << ", mid z: "<< mid_z << std::endl;
  445. if(ec != SUCCESS)
  446. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NORMAL, "failed to find chassis z value.");
  447. std::chrono::steady_clock::time_point t3 = std::chrono::steady_clock::now();
  448. std::chrono::duration<double> time_used_block = std::chrono::duration_cast<std::chrono::duration<double>>(t3 - t2);
  449. // 更新z中间点
  450. m_detect_z_cloud_mutex.lock();
  451. mp_cloud_detect_z->clear();
  452. mp_cloud_detect_z->operator+=(*cloud_z_solver);
  453. m_detect_z_cloud_mutex.unlock();
  454. // 二分法存在错误弃用!!!直接使用底盘z值
  455. std::vector<detect_wheel_ceres3d::Detect_result> results;
  456. detect_wheel_ceres3d::Detect_result result;
  457. double chassis_z = mid_z + height / 2.0; // + 0.02;
  458. if(chassis_z > m_region.maxz() || chassis_z < m_region.minz())
  459. {
  460. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, (std::string("optimized chassis z value out of range: ")+std::to_string(chassis_z)).c_str());
  461. }
  462. bool ret = false;
  463. while (chassis_z > (mid_z - height / 2.0))
  464. {
  465. // LOG_IF(WARNING, m_region.region_id() == 0) << "chassis z: " << chassis_z << ", midz: " << mid_z - height / 2.0;
  466. // 初值中x使用第一步优化的值
  467. result.cx = car_pose_x;
  468. // 传入整车角度,用于准确判断轮宽,此处需要的是点云的角度,通常逆时针90度到x轴
  469. result.theta = -(M_PI_2 - car_pose_theta);
  470. ret = classify_ceres_detect(cloud_filtered, chassis_z, result);
  471. // changed by yct, 根据底盘z识别,失败则向下移动直至成功或超过底盘内空中点
  472. if(ret)
  473. {
  474. results.push_back(result);
  475. break;
  476. }else{
  477. chassis_z -= 0.01;
  478. }
  479. }
  480. // } while (fabs(center_z - last_center_z) > 0.01);
  481. std::chrono::steady_clock::time_point t4 = std::chrono::steady_clock::now();
  482. std::chrono::duration<double> time_used_div = std::chrono::duration_cast<std::chrono::duration<double>>(t4 - t3);
  483. // std::cout << "\n------------------------------------------------------------ " << std::to_string(time_used_bowl.count()) << " " << std::to_string(time_used_block.count()) << " " << std::to_string(time_used_div.count())<<" || "<< std::to_string(time_used_bowl.count()+time_used_block.count()+time_used_div.count())<< std::endl;
  484. if (results.size() == 0)
  485. {
  486. // std::cout << "\n-------- no result: " << std::endl;
  487. //LOG_IF(INFO, m_region.region_id() == 4) << "failed with midz, currz: " << mid_z << ", " << chassis_z;
  488. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, "3d wheel detect failed.");
  489. }
  490. else
  491. {
  492. // // 20201010, may lead to problem in chutian, uncomment in debug only
  493. // // changed by yct, save 3d wheel detect result.
  494. // static int save_debug = 0;
  495. // if (m_region.region_id() == 0 && save_debug++ == 5)
  496. // m_detector->save_debug_data("/home/zx/yct/chutian_measure_2021/build");
  497. // LOG_IF(INFO, m_region.region_id() == 4) << "detected with suitable z value: " << chassis_z;
  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. // std::cout << "\n-------- final z: " << chassis_z << std::endl;
  522. // std::cout << "cx: " << last_result.cx << ", cy: " << last_result.cy << ", theta: " << last_result.theta
  523. // << ", front: " << last_result.front_theta << ", wheelbase: " << last_result.wheel_base << ", width: " << last_result.width << std::endl << std::endl;
  524. // last_result.cx -= x;
  525. // last_result.cy -= y;
  526. // last_result.theta -= theta;
  527. // 角度校验,理论上car pose检测使用车身点云,应与车轮点云识别得到的车身 x偏移(0.035)与角度(<1°)一致
  528. double car_pose_theta_deg = 90 - car_pose_theta * 180.0 / M_PI;
  529. if (fabs(car_pose_x - last_result.cx) > 0.035 || fabs(car_pose_theta_deg - last_result.theta) > 1)
  530. {
  531. char valid_info[255];
  532. sprintf(valid_info, "validation failed for x and theta, carpose: (%.3f, %.3f), result: (%.3f, %.3f)", car_pose_x, car_pose_theta_deg, last_result.cx, last_result.theta);
  533. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, valid_info);
  534. }
  535. // 车宽精度优化
  536. {
  537. pcl::PointCloud<pcl::PointXYZ>::Ptr t_width_extract_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  538. t_width_extract_cloud->operator+=(*mp_cloud_filtered);
  539. //离群点过滤
  540. sor.setInputCloud(t_width_extract_cloud);
  541. sor.setMeanK(5); //K近邻搜索点个数
  542. sor.setStddevMulThresh(1.0); //标准差倍数
  543. sor.setNegative(false); //保留未滤波点(内点)
  544. sor.filter(*t_width_extract_cloud); //保存滤波结果到cloud_filter
  545. Eigen::Affine3d t_affine = Eigen::Affine3d::Identity();
  546. t_affine.prerotate(Eigen::AngleAxisd((90 - last_result.theta) * M_PI / 180.0, Eigen::Vector3d::UnitZ()));
  547. pcl::transformPointCloud(*t_width_extract_cloud, *t_width_extract_cloud, t_affine.matrix());
  548. // 车宽重计算,并赋值到当前车宽
  549. pcl::PointXYZ t_min_p, t_max_p;
  550. pcl::getMinMax3D(*t_width_extract_cloud, t_min_p, t_max_p);
  551. double accurate_width = t_max_p.x - t_min_p.x;
  552. last_result.width = accurate_width;
  553. // !!!暂时不限制宽度数据
  554. // char valid_info[255];
  555. // sprintf(valid_info, "validation for car width, origin/accurate: (%.3f, %.3f)", last_result.width, accurate_width);
  556. // // 允许一边5cm误差,且保证车宽应比车轮识别计算出的大,否则为错误宽度数据
  557. // if (accurate_width - last_result.width > 0.1 || accurate_width < last_result.width)
  558. // {
  559. // return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, valid_info);
  560. // }
  561. // if (m_region.region_id() == 0 || m_region.region_id() == 4)
  562. // {
  563. // LOG(WARNING) << valid_info;
  564. // // 保存车宽数据,统计用
  565. // if (m_file_out.is_open())
  566. // m_file_out << std::setprecision(5) << std::to_string(1.883) << "," << last_result.width << "," << accurate_width << std::endl;
  567. // }
  568. }
  569. // LOG_IF(INFO, m_region.region_id() == 4) << last_result.to_string();
  570. return SUCCESS;
  571. }
  572. int Ground_region::outOfRangeDetection(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double plate_cx, double plate_cy, double theta)
  573. {
  574. if(cloud->size() <= 0)
  575. return Range_status::Range_correct;
  576. int res = Range_status::Range_correct;
  577. // 计算转盘旋转后点云坐标
  578. double theta_rad = theta * M_PI / 180.0;
  579. pcl::PointCloud<pcl::PointXYZ> t_cloud;
  580. for (size_t i = 0; i < cloud->size(); i++)
  581. {
  582. Eigen::Vector2d t_point(cloud->points[i].x - plate_cx, cloud->points[i].y - plate_cy);
  583. pcl::PointXYZ t_pcl_point;
  584. t_pcl_point.x = (t_point.x() * cos(theta_rad) - t_point.y() * sin(theta_rad)) + plate_cx;
  585. t_pcl_point.y = (t_point.x() * sin(theta_rad) + t_point.y() * cos(theta_rad)) + plate_cy;
  586. t_pcl_point.z = cloud->points[i].z;
  587. t_cloud.push_back(t_pcl_point);
  588. }
  589. pcl::PointXYZ min_p, max_p;
  590. pcl::getMinMax3D(t_cloud, min_p, max_p);
  591. // 判断左右超界情况
  592. if(min_p.x < m_region.border_minx())
  593. res |= Range_status::Range_left;
  594. if(max_p.x > m_region.border_maxx())
  595. res |= Range_status::Range_right;
  596. // LOG_IF(WARNING, m_region.region_id() == 4)<< "border minmax x: "<< min_p.x<<", "<<max_p.x<<", res: "<<res;
  597. return res;
  598. }
  599. int Ground_region::outOfRangeDetection(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, Common_data::Car_wheel_information measure_result, double plate_cx, double plate_cy, double theta)
  600. {
  601. int res = Range_status::Range_correct;
  602. if(cloud->size() <= 0)
  603. return res;
  604. // 计算转盘旋转后车辆中心点坐标
  605. Eigen::Vector2d car_center(measure_result.car_center_x, measure_result.car_center_y);
  606. Eigen::Vector2d car_uniform_center;
  607. double theta_rad = theta * M_PI / 180.0;
  608. car_uniform_center.x() = car_center.x() * cos(theta_rad) - car_center.y() * sin(theta_rad);
  609. car_uniform_center.y() = car_center.x() * sin(theta_rad) + car_center.y() * cos(theta_rad);
  610. // 车位位于y负方向,判断后轮超界情况
  611. //yct old program 20221101
  612. // double rear_wheel_y = car_uniform_center.y() + m_region.plc_offsety() - 0.5 * measure_result.car_wheel_base;
  613. // if(rear_wheel_y < m_region.plc_border_miny())
  614. // {
  615. // res |= Range_status::Range_back;
  616. // }
  617. //huli new program 20221101
  618. double t_center_y = 0.0 - (car_uniform_center.y() + m_region.plc_offsety()); // 汽车中心y, 参照plc坐标,并且进行偏移, 绝对值。结果大约为 5~6左右
  619. if( t_center_y - 4.88 + 0.5*(measure_result.car_wheel_base - 2.7) < m_region.plc_border_maxy() &&
  620. t_center_y - 4.88 - 0.5*(measure_result.car_wheel_base - 2.7) < m_region.plc_border_miny() )
  621. {
  622. //normal
  623. } else
  624. {
  625. res |= Range_status::Range_back;
  626. }
  627. // 判断车辆宽度超界情况
  628. if (measure_result.car_wheel_width < m_region.car_min_width() || measure_result.car_wheel_width > m_region.car_max_width())
  629. {
  630. res |= Range_status::Range_car_width;
  631. }
  632. // 判断车辆轴距超界情况
  633. if (measure_result.car_wheel_base < m_region.car_min_wheelbase() || measure_result.car_wheel_base > m_region.car_max_wheelbase())
  634. {
  635. res |= Range_status::Range_car_wheelbase;
  636. }
  637. //yct old program 20221103 , 使用 velodyne_manager.prototxt 里面的 turnplate_angle_limit 来做边界判断
  638. // 判断车辆旋转角超界情况
  639. // double dtheta = 90-measure_result.car_angle;
  640. // if (dtheta > m_region.turnplate_angle_limit_anti_clockwise())
  641. // {
  642. // res |= Range_status::Range_angle_clock;
  643. // }
  644. // if (dtheta < -m_region.turnplate_angle_limit_clockwise())
  645. // {
  646. // res |= Range_status::Range_angle_anti_clock;
  647. // }
  648. //huli new program 20221103, 使用 plc dispatch_1_statu_port 里面的 来做边界判断
  649. // double t_dtheta = 90-measure_result.car_angle; // 车身的旋转角, 修正到正负5度,
  650. double t_dtheta = measure_result.car_angle + m_region.plc_offset_degree(); // 车身的旋转角, 修正到正5度, (m_region.plc_offset_degree():-89)
  651. int t_terminal_id = m_region.region_id() +1; //region_id:0~5, terminal_id:1~6
  652. //turnplate_angle_min = -5, turnplate_angle_max = 5,
  653. if (t_dtheta > System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_max())
  654. {
  655. res |= Range_status::Range_angle_anti_clock;
  656. }
  657. if (t_dtheta < System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_min())
  658. {
  659. res |= Range_status::Range_angle_clock;
  660. }
  661. // if (t_terminal_id == 3)
  662. // {
  663. //
  664. // LOG(INFO) << "hulixxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx t_terminal_id = " << t_terminal_id << " ";
  665. //
  666. // LOG(INFO) << "hulixxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx m_region.plc_offset_degree() = " << m_region.plc_offset_degree() << " ";
  667. //
  668. //
  669. // LOG(INFO) << "hulixxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx t_dtheta = " << t_dtheta << " ";
  670. // LOG(INFO) << "hulixxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx turnplate_angle_min = " << System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_min() << " ";
  671. // LOG(INFO) << "hulixxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx turnplate_angle_max = " << System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_max() << " ";
  672. //
  673. // }
  674. // // 判断车辆前轮角回正情况
  675. // if (fabs(measure_result.car_front_theta) > 8.0)
  676. // {
  677. // res |= Range_status::Range_steering_wheel_nozero;
  678. // }
  679. res |= outOfRangeDetection(cloud, plate_cx, plate_cy, theta);
  680. return res;
  681. }
  682. //外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待
  683. Error_manager Ground_region::get_current_wheel_information(Common_data::Car_wheel_information *p_car_wheel_information, std::chrono::system_clock::time_point command_time)
  684. {
  685. if ( p_car_wheel_information == NULL )
  686. {
  687. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  688. " POINTER IS NULL ");
  689. }
  690. //获取指令时间之后的信息, 如果没有就会报错, 不会等待
  691. if( m_detect_update_time > command_time )
  692. {
  693. std::lock_guard<std::mutex> lck(m_car_result_mutex);
  694. *p_car_wheel_information = m_car_wheel_information;
  695. if(m_car_wheel_information.correctness)
  696. return Error_code::SUCCESS;
  697. else
  698. return Error_manager(Error_code::VELODYNE_REGION_CERES_SOLVE_ERROR, Error_level::MINOR_ERROR, " Ground_region detect error");
  699. }
  700. else
  701. {
  702. return Error_manager(Error_code::VELODYNE_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
  703. " Ground_region::get_current_wheel_information error ");
  704. }
  705. }
  706. //外部调用获取最新的车轮定位信息, 获取指令时间往前一个周期内的车轮定位信息, 如果没有就会报错, 不会等待
  707. Error_manager Ground_region::get_last_wheel_information(Common_data::Car_wheel_information *p_car_wheel_information, std::chrono::system_clock::time_point command_time)
  708. {
  709. if ( p_car_wheel_information == NULL )
  710. {
  711. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  712. " POINTER IS NULL ");
  713. }
  714. //获取指令时间之后的信息, 如果没有就会报错, 不会等待
  715. // LOG(WARNING) << std::chrono::duration_cast<std::chrono::milliseconds>(command_time-m_detect_update_time).count()/1000.0 <<", "
  716. // <<std::chrono::duration_cast<std::chrono::milliseconds>(command_time-m_cloud_collection_time).count()/1000.0;
  717. if( m_detect_update_time > command_time - std::chrono::milliseconds(GROUND_REGION_DETECT_CYCLE_MS))
  718. {
  719. std::lock_guard<std::mutex> lck(m_car_result_mutex);
  720. *p_car_wheel_information = m_car_wheel_information;
  721. if(m_car_wheel_information.correctness)
  722. return Error_code::SUCCESS;
  723. else
  724. return Error_manager(Error_code::VELODYNE_REGION_CERES_SOLVE_ERROR, Error_level::MINOR_ERROR, " Ground_region detect error");
  725. }
  726. else
  727. {
  728. return Error_manager(Error_code::VELODYNE_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
  729. " Ground_region::get_current_wheel_information error ");
  730. }
  731. }
  732. Error_manager Ground_region::update_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
  733. {
  734. // // 点云z转90度,调试用
  735. //Eigen::AngleAxisd rot_z = Eigen::AngleAxisd(M_PI_2, Eigen::Vector3d::UnitZ());
  736. //for (size_t i = 0; i < cloud->size(); i++)
  737. //{
  738. // Eigen::Vector3d t_point(cloud->points[i].x, cloud->points[i].y, cloud->points[i].z);
  739. // t_point = rot_z.toRotationMatrix() * t_point;
  740. // cloud->points[i].x = t_point.x();
  741. // cloud->points[i].y = t_point.y();
  742. // cloud->points[i].z = t_point.z();
  743. //}
  744. // 限定锁区域,解决因条件变量在析构时无法获得内部mutex导致此互斥锁卡住,造成死锁无法结束程序的问题。
  745. {
  746. std::lock_guard<std::mutex> lck(m_cloud_collection_mutex);
  747. mp_cloud_collection = cloud;
  748. // LOG(WARNING) << "update region cloud size: " << mp_cloud_collection->size() << ",,, input size: " << cloud->size();
  749. m_cloud_collection_time = std::chrono::system_clock::now();
  750. }
  751. m_measure_condition.notify_one(false, true);
  752. // std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  753. // std::chrono::duration<double> time_used_update = std::chrono::duration_cast<std::chrono::duration<double>>(t1 - t0);
  754. // std::cout << "update cloud time: " << time_used_update.count() << std::endl;
  755. return SUCCESS;
  756. }
  757. void Ground_region::thread_measure_func()
  758. {
  759. LOG(INFO) << " Ground_region::thread_measure_func() start " << this;
  760. while (m_measure_condition.is_alive())
  761. {
  762. m_measure_condition.wait();
  763. if (m_measure_condition.is_alive())
  764. {
  765. m_region_status = E_BUSY;
  766. detect_wheel_ceres3d::Detect_result t_result;
  767. Error_manager ec = detect(mp_cloud_collection, t_result);
  768. std::lock_guard<std::mutex> lck(m_car_result_mutex);
  769. m_detect_update_time = std::chrono::system_clock::now();
  770. // 增加滤波轴距
  771. Common_data::Car_wheel_information_stamped t_wheel_info_stamped;
  772. // 车辆移动检测
  773. Common_data::Car_wheel_information_stamped t_wheel_info_stamped_for_car_move;
  774. if (ec == SUCCESS)
  775. {
  776. m_car_wheel_information.correctness = true;
  777. m_car_wheel_information.car_center_x = t_result.cx;
  778. m_car_wheel_information.car_center_y = t_result.cy;
  779. m_car_wheel_information.car_angle = t_result.theta;
  780. m_car_wheel_information.car_wheel_base = t_result.wheel_base;
  781. m_car_wheel_information.car_wheel_width = t_result.width;
  782. m_car_wheel_information.car_front_theta = t_result.front_theta;
  783. // 220110 added by yct, single wheel width filtering
  784. m_car_wheel_information.single_wheel_width = t_result.single_wheel_width;
  785. m_car_wheel_information.single_wheel_length = t_result.single_wheel_length;
  786. m_car_wheel_information.theta_uniform(m_region.turnplate_cx(), m_region.turnplate_cy());
  787. // 超界校验
  788. {
  789. std::lock_guard<std::mutex> lck(m_filtered_cloud_mutex);
  790. int res = outOfRangeDetection(mp_cloud_filtered, m_car_wheel_information, m_region.turnplate_cx(), m_region.turnplate_cy(), 90.0 - t_result.theta);
  791. m_car_wheel_information.range_status = res;
  792. }
  793. // 添加plc偏移
  794. m_car_wheel_information.car_center_x += m_region.plc_offsetx();
  795. m_car_wheel_information.car_center_y += m_region.plc_offsety();
  796. m_car_wheel_information.uniform_car_x += m_region.plc_offsetx();
  797. m_car_wheel_information.uniform_car_y += m_region.plc_offsety();
  798. m_car_wheel_information.car_angle += m_region.plc_offset_degree();
  799. // LOG(INFO) << "yyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyy t_result.theta = " << t_result.theta << " ";
  800. // LOG(INFO) << "yyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyy m_region.plc_offset_degree() = " << m_region.plc_offset_degree() << " ";
  801. // LOG(INFO) << "yyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyy m_car_wheel_information.car_angle= " << m_car_wheel_information.car_angle << " ";
  802. t_wheel_info_stamped.wheel_data = m_car_wheel_information;
  803. t_wheel_info_stamped.measure_time = m_detect_update_time;
  804. Measure_filter::get_instance_references().update_data(m_region.region_id(), t_wheel_info_stamped);
  805. // 20211228 added by yct, car movement checking, human and door detection
  806. t_wheel_info_stamped_for_car_move = t_wheel_info_stamped;
  807. t_wheel_info_stamped_for_car_move.wheel_data.car_center_x -= m_region.plc_offsetx();
  808. t_wheel_info_stamped_for_car_move.wheel_data.car_center_y -= m_region.plc_offsety();
  809. t_wheel_info_stamped_for_car_move.wheel_data.uniform_car_x -= m_region.plc_offsetx();
  810. t_wheel_info_stamped_for_car_move.wheel_data.uniform_car_y -= m_region.plc_offsety();
  811. t_wheel_info_stamped_for_car_move.wheel_data.car_angle -= m_region.plc_offset_degree();
  812. Error_manager car_status_res = Region_status_checker::get_instance_references().get_region_parking_status(m_region.region_id(), t_wheel_info_stamped_for_car_move, *mp_cloud_filtered);
  813. // success means car stable
  814. if(car_status_res == SUCCESS)
  815. {
  816. m_car_wheel_information.range_status &= ~((int)Range_status::Range_car_moving);
  817. }else
  818. {
  819. m_car_wheel_information.range_status |= Range_status::Range_car_moving;
  820. // if(m_region.region_id()==4){
  821. // std::cout<<"success: "<<car_status_res.to_string()<<std::endl;
  822. // }
  823. }
  824. Region_status_checker::get_instance_references().add_measure_data(m_region.region_id(), t_wheel_info_stamped_for_car_move, *mp_cloud_filtered);
  825. ec = Measure_filter::get_instance_references().get_filtered_wheel_information(m_region.region_id(), t_wheel_info_stamped.wheel_data);
  826. if (ec == SUCCESS)
  827. {
  828. m_car_wheel_information.car_wheel_base = t_wheel_info_stamped.wheel_data.car_wheel_base;
  829. m_car_wheel_information.car_front_theta = t_wheel_info_stamped.wheel_data.car_front_theta;
  830. // 临时添加,滤波后前轮超界
  831. if(fabs(m_car_wheel_information.car_front_theta)>8.0)
  832. {
  833. m_car_wheel_information.range_status |= Range_status::Range_steering_wheel_nozero;
  834. }
  835. }
  836. // else{
  837. // std::cout<<ec.to_string()<<std::endl;
  838. // }
  839. // LOG_IF(INFO, m_region.region_id() == 1) << m_car_wheel_information.to_string();
  840. }
  841. else
  842. {
  843. m_car_wheel_information.correctness = false;
  844. // LOG_IF(ERROR, m_region.region_id() == 1) << ec.to_string();
  845. // 20211228 added by yct, car movement checking, human and door detection
  846. Error_manager car_status_res = Region_status_checker::get_instance_references().get_region_parking_status(m_region.region_id(), t_wheel_info_stamped_for_car_move, *mp_cloud_filtered);
  847. // success means car stable
  848. if(car_status_res == SUCCESS)
  849. {
  850. m_car_wheel_information.range_status &= ~((int)Range_status::Range_car_moving);
  851. }else
  852. {
  853. m_car_wheel_information.range_status |= Range_status::Range_car_moving;
  854. // if(m_region.region_id()==1){
  855. // std::cout<<"failed: "<<car_status_res.to_string()<<std::endl;
  856. // }
  857. }
  858. }
  859. }
  860. m_region_status = E_READY;
  861. }
  862. LOG(INFO) << " Ground_region::thread_measure_func() end " << this;
  863. }