ground_region.cpp 47 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085
  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. m_range_status_last = 0;
  292. Region_status_checker::get_instance_references().Region_status_checker_init();
  293. m_region = region;
  294. m_detector = new detect_wheel_ceres3d(left_model,right_model);
  295. mp_cloud_collection = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  296. mp_cloud_filtered = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  297. mp_cloud_detect_z = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  298. m_measure_thread = new std::thread(&Ground_region::thread_measure_func, this);
  299. m_measure_condition.reset();
  300. m_region_status = E_READY;
  301. return SUCCESS;
  302. }
  303. // 计算均方误差
  304. bool computer_var(std::vector<double> data, double &var)
  305. {
  306. if (data.size() == 0)
  307. return false;
  308. Eigen::VectorXd dis_vec(data.size());
  309. for (int i = 0; i < data.size(); ++i)
  310. {
  311. dis_vec[i] = data[i];
  312. }
  313. double mean = dis_vec.mean();
  314. Eigen::VectorXd mean_vec(data.size());
  315. Eigen::VectorXd mat = dis_vec - (mean_vec.setOnes() * mean);
  316. Eigen::MatrixXd result = (mat.transpose()) * mat;
  317. var = sqrt(result(0) / double(data.size()));
  318. return true;
  319. }
  320. Error_manager Ground_region::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, detect_wheel_ceres3d::Detect_result &last_result)
  321. {
  322. // 1.*********点云合法性检验*********
  323. if (cloud->size() == 0){
  324. // 更新过滤点
  325. m_filtered_cloud_mutex.lock();
  326. mp_cloud_filtered->clear();
  327. m_filtered_cloud_mutex.unlock();
  328. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "no input point");
  329. }
  330. // 2.*********点云预处理*********
  331. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  332. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_cut(new pcl::PointCloud<pcl::PointXYZ>);
  333. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_clean(new pcl::PointCloud<pcl::PointXYZ>);
  334. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered(new pcl::PointCloud<pcl::PointXYZ>);
  335. for (int i = 0; i < cloud->size(); ++i)
  336. {
  337. pcl::PointXYZ pt = cloud->points[i];
  338. 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())
  339. {
  340. cloud_cut->push_back(pt);
  341. }
  342. }
  343. if(cloud_cut->size() <= 0)
  344. {
  345. // 更新过滤点
  346. m_filtered_cloud_mutex.lock();
  347. mp_cloud_filtered->clear();
  348. m_filtered_cloud_mutex.unlock();
  349. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "cut no point");
  350. }
  351. //下采样
  352. pcl::VoxelGrid<pcl::PointXYZ> vox; //创建滤波对象
  353. vox.setInputCloud(cloud_cut); //设置需要过滤的点云给滤波对象
  354. vox.setLeafSize(0.02f, 0.02f, 0.02f); //设置滤波时创建的体素体积为1cm的立方体
  355. vox.filter(*cloud_clean); //执行滤波处理,存储输出
  356. // cloud_filtered = cloud_clean;
  357. if (cloud_clean->size() == 0){
  358. // 更新过滤点
  359. m_filtered_cloud_mutex.lock();
  360. mp_cloud_filtered->clear();
  361. m_filtered_cloud_mutex.unlock();
  362. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "ApproximateVoxelGrid no point");
  363. }
  364. //离群点过滤
  365. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
  366. sor.setInputCloud(cloud_clean);
  367. sor.setMeanK(5); //K近邻搜索点个数
  368. sor.setStddevMulThresh(3.0); //标准差倍数
  369. sor.setNegative(false); //保留未滤波点(内点)
  370. sor.filter(*cloud_filtered); //保存滤波结果到cloud_filter
  371. if (cloud_filtered->size() == 0){
  372. // 更新过滤点
  373. m_filtered_cloud_mutex.lock();
  374. mp_cloud_filtered->clear();
  375. m_filtered_cloud_mutex.unlock();
  376. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "StatisticalOutlierRemoval no point");
  377. }
  378. // 更新过滤点
  379. m_filtered_cloud_mutex.lock();
  380. mp_cloud_filtered->clear();
  381. mp_cloud_filtered->operator+=(*cloud_filtered);
  382. m_filtered_cloud_mutex.unlock();
  383. // 3.*********位姿优化,获取中心xy与角度*********
  384. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_detect_z(new pcl::PointCloud<pcl::PointXYZ>);
  385. double car_pose_x, car_pose_y, car_pose_theta, car_pose_width, z_value=0.2;
  386. // 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))
  387. 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))
  388. {
  389. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, "find general car pose value failed.");
  390. }
  391. // 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;
  392. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  393. std::chrono::duration<double> time_used_bowl = std::chrono::duration_cast<std::chrono::duration<double>>(t2 - t1);
  394. // 4.*********xoz优化获取底盘高度*********
  395. // 重新取包含地面点的点云,用于底盘优化
  396. double z_solver_x = car_pose_x;
  397. double z_solver_y = car_pose_y;
  398. double z_solver_theta = car_pose_theta;
  399. double z_solver_width = 1.0;
  400. chassis_ceres_solver t_solver;
  401. // !!!重新筛选地面点并滤波,融入第一步位姿使用的滤波后点云,传入第二步获取底盘高度
  402. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_z_solver(new pcl::PointCloud<pcl::PointXYZ>);
  403. for (int i = 0; i < cloud->size(); ++i)
  404. {
  405. pcl::PointXYZ pt = cloud->points[i];
  406. 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())
  407. {
  408. cloud_z_solver->push_back(pt);
  409. }
  410. }
  411. if (cloud_z_solver->size() == 0){
  412. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NEGLIGIBLE_ERROR, "cloud z no point for outlier removal");
  413. }
  414. //离群点过滤
  415. sor.setInputCloud(cloud_z_solver);
  416. sor.setMeanK(5); //K近邻搜索点个数
  417. sor.setStddevMulThresh(3.0); //标准差倍数
  418. sor.setNegative(false); //保留未滤波点(内点)
  419. sor.filter(*cloud_z_solver); //保存滤波结果到cloud_filter
  420. // 补上车身与车轮点
  421. cloud_z_solver->operator+=(*mp_cloud_filtered);
  422. // 去中心,角度调正
  423. Car_pose_detector::get_instance_references().inv_trans_cloud(cloud_z_solver, z_solver_x, z_solver_y, z_solver_theta);
  424. if (cloud_z_solver->size() == 0)
  425. return Error_manager(VELODYNE_REGION_EMPTY_CLOUD, NORMAL, "z solver no point");
  426. // 给予底盘z中心与高度初值
  427. double mid_z = 0.05, height = 0.08;
  428. z_solver_x = 0.0;
  429. // Error_manager ec = t_solver.solve(cloud_z_solver, z_solver_x, mid_z, z_solver_width, height);
  430. Error_manager ec = t_solver.solve_mat(cloud_z_solver, z_solver_x, mid_z, z_solver_width, height, false);
  431. // 切除大于height高度以外点,并显示width直线
  432. // 根据z值切原始点云
  433. pcl::PassThrough<pcl::PointXYZ> pass;
  434. pass.setInputCloud(cloud_z_solver);
  435. pass.setFilterFieldName("z");
  436. pass.setFilterLimits(m_region.minz(), mid_z + height / 2.0);
  437. pass.setFilterLimitsNegative(false);
  438. pass.filter(*cloud_z_solver);
  439. // // 车宽方向画线
  440. // for (double i = -3.0; i < 3.0; i+=0.02)
  441. // {
  442. // cloud_z_solver->push_back(pcl::PointXYZ(-width/2.0, i, 0));
  443. // cloud_z_solver->push_back(pcl::PointXYZ(width/2.0, i, 0));
  444. // }
  445. // std::cout << "\n------------------------------------ chassis z1: " << mid_z + height / 2.0 << ", mid z: "<< mid_z << std::endl;
  446. if(ec != SUCCESS)
  447. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NORMAL, "failed to find chassis z value.");
  448. std::chrono::steady_clock::time_point t3 = std::chrono::steady_clock::now();
  449. std::chrono::duration<double> time_used_block = std::chrono::duration_cast<std::chrono::duration<double>>(t3 - t2);
  450. // 更新z中间点
  451. m_detect_z_cloud_mutex.lock();
  452. mp_cloud_detect_z->clear();
  453. mp_cloud_detect_z->operator+=(*cloud_z_solver);
  454. m_detect_z_cloud_mutex.unlock();
  455. // 二分法存在错误弃用!!!直接使用底盘z值
  456. std::vector<detect_wheel_ceres3d::Detect_result> results;
  457. detect_wheel_ceres3d::Detect_result result;
  458. double chassis_z = mid_z + height / 2.0; // + 0.02;
  459. if(chassis_z > m_region.maxz() || chassis_z < m_region.minz())
  460. {
  461. 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());
  462. }
  463. bool ret = false;
  464. while (chassis_z > (mid_z - height / 2.0))
  465. {
  466. // LOG_IF(WARNING, m_region.region_id() == 0) << "chassis z: " << chassis_z << ", midz: " << mid_z - height / 2.0;
  467. // 初值中x使用第一步优化的值
  468. result.cx = car_pose_x;
  469. // 传入整车角度,用于准确判断轮宽,此处需要的是点云的角度,通常逆时针90度到x轴
  470. result.theta = -(M_PI_2 - car_pose_theta);
  471. ret = classify_ceres_detect(cloud_filtered, chassis_z, result);
  472. // changed by yct, 根据底盘z识别,失败则向下移动直至成功或超过底盘内空中点
  473. if(ret)
  474. {
  475. results.push_back(result);
  476. break;
  477. }else{
  478. chassis_z -= 0.01;
  479. }
  480. }
  481. // } while (fabs(center_z - last_center_z) > 0.01);
  482. std::chrono::steady_clock::time_point t4 = std::chrono::steady_clock::now();
  483. std::chrono::duration<double> time_used_div = std::chrono::duration_cast<std::chrono::duration<double>>(t4 - t3);
  484. // 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;
  485. if (results.size() == 0)
  486. {
  487. // std::cout << "\n-------- no result: " << std::endl;
  488. //LOG_IF(INFO, m_region.region_id() == 4) << "failed with midz, currz: " << mid_z << ", " << chassis_z;
  489. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, "3d wheel detect failed.");
  490. }
  491. else
  492. {
  493. // // 20201010, may lead to problem in chutian, uncomment in debug only
  494. // // changed by yct, save 3d wheel detect result.
  495. // static int save_debug = 0;
  496. // if (m_region.region_id() == 0 && save_debug++ == 5)
  497. // m_detector->save_debug_data("/home/zx/yct/chutian_measure_2021/build");
  498. // LOG_IF(INFO, m_region.region_id() == 4) << "detected with suitable z value: " << chassis_z;
  499. }
  500. /// to be
  501. float min_mean_loss = 1.0;
  502. for (int i = 0; i < results.size(); ++i)
  503. {
  504. detect_wheel_ceres3d::Detect_result result = results[i];
  505. std::vector<double> loss;
  506. loss.push_back(result.loss.lf_loss);
  507. loss.push_back(result.loss.rf_loss);
  508. loss.push_back(result.loss.lb_loss);
  509. loss.push_back(result.loss.rb_loss);
  510. double mean = (result.loss.lf_loss + result.loss.rf_loss + result.loss.lb_loss + result.loss.rb_loss) / 4.0;
  511. double var = -1.;
  512. computer_var(loss, var);
  513. if (mean < min_mean_loss)
  514. {
  515. last_result = result;
  516. min_mean_loss = mean;
  517. }
  518. }
  519. // printf("z : %.3f angle : %.3f front : %.3f wheel_base:%.3f,width:%.3f, mean:%.5f\n",
  520. // center_z, last_result.theta, last_result.front_theta, last_result.wheel_base, last_result.width,
  521. // min_mean_loss);
  522. // std::cout << "\n-------- final z: " << chassis_z << std::endl;
  523. // std::cout << "cx: " << last_result.cx << ", cy: " << last_result.cy << ", theta: " << last_result.theta
  524. // << ", front: " << last_result.front_theta << ", wheelbase: " << last_result.wheel_base << ", width: " << last_result.width << std::endl << std::endl;
  525. // last_result.cx -= x;
  526. // last_result.cy -= y;
  527. // last_result.theta -= theta;
  528. // 角度校验,理论上car pose检测使用车身点云,应与车轮点云识别得到的车身 x偏移(0.035)与角度(<1°)一致
  529. double car_pose_theta_deg = 90 - car_pose_theta * 180.0 / M_PI;
  530. if (fabs(car_pose_x - last_result.cx) > 0.035 || fabs(car_pose_theta_deg - last_result.theta) > 1)
  531. {
  532. char valid_info[255];
  533. 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);
  534. return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, valid_info);
  535. }
  536. // 车宽精度优化
  537. {
  538. pcl::PointCloud<pcl::PointXYZ>::Ptr t_width_extract_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  539. t_width_extract_cloud->operator+=(*mp_cloud_filtered);
  540. //离群点过滤
  541. sor.setInputCloud(t_width_extract_cloud);
  542. sor.setMeanK(5); //K近邻搜索点个数
  543. sor.setStddevMulThresh(1.0); //标准差倍数
  544. sor.setNegative(false); //保留未滤波点(内点)
  545. sor.filter(*t_width_extract_cloud); //保存滤波结果到cloud_filter
  546. Eigen::Affine3d t_affine = Eigen::Affine3d::Identity();
  547. t_affine.prerotate(Eigen::AngleAxisd((90 - last_result.theta) * M_PI / 180.0, Eigen::Vector3d::UnitZ()));
  548. pcl::transformPointCloud(*t_width_extract_cloud, *t_width_extract_cloud, t_affine.matrix());
  549. // 车宽重计算,并赋值到当前车宽
  550. pcl::PointXYZ t_min_p, t_max_p;
  551. pcl::getMinMax3D(*t_width_extract_cloud, t_min_p, t_max_p);
  552. double accurate_width = t_max_p.x - t_min_p.x;
  553. last_result.width = accurate_width;
  554. // !!!暂时不限制宽度数据
  555. // char valid_info[255];
  556. // sprintf(valid_info, "validation for car width, origin/accurate: (%.3f, %.3f)", last_result.width, accurate_width);
  557. // // 允许一边5cm误差,且保证车宽应比车轮识别计算出的大,否则为错误宽度数据
  558. // if (accurate_width - last_result.width > 0.1 || accurate_width < last_result.width)
  559. // {
  560. // return Error_manager(VELODYNE_REGION_CERES_SOLVE_ERROR, NEGLIGIBLE_ERROR, valid_info);
  561. // }
  562. // if (m_region.region_id() == 0 || m_region.region_id() == 4)
  563. // {
  564. // LOG(WARNING) << valid_info;
  565. // // 保存车宽数据,统计用
  566. // if (m_file_out.is_open())
  567. // m_file_out << std::setprecision(5) << std::to_string(1.883) << "," << last_result.width << "," << accurate_width << std::endl;
  568. // }
  569. }
  570. // LOG_IF(INFO, m_region.region_id() == 4) << last_result.to_string();
  571. return SUCCESS;
  572. }
  573. int Ground_region::outOfRangeDetection(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double plate_cx, double plate_cy, double theta)
  574. {
  575. // LOG(WARNING) << m_range_status_last;
  576. if(cloud->size() <= 0)
  577. return Range_status::Range_correct;
  578. int res = Range_status::Range_correct;
  579. // 计算转盘旋转后点云坐标
  580. double theta_rad = theta * M_PI / 180.0;
  581. pcl::PointCloud<pcl::PointXYZ> t_cloud;
  582. for (size_t i = 0; i < cloud->size(); i++)
  583. {
  584. Eigen::Vector2d t_point(cloud->points[i].x - plate_cx, cloud->points[i].y - plate_cy);
  585. pcl::PointXYZ t_pcl_point;
  586. t_pcl_point.x = (t_point.x() * cos(theta_rad) - t_point.y() * sin(theta_rad)) + plate_cx;
  587. t_pcl_point.y = (t_point.x() * sin(theta_rad) + t_point.y() * cos(theta_rad)) + plate_cy;
  588. t_pcl_point.z = cloud->points[i].z;
  589. t_cloud.push_back(t_pcl_point);
  590. }
  591. pcl::PointXYZ min_p, max_p;
  592. pcl::getMinMax3D(t_cloud, min_p, max_p);
  593. #ifndef ANTI_SHAKE
  594. // 判断左右超界情况
  595. if(min_p.x < m_region.border_minx())
  596. res |= Range_status::Range_left;
  597. if(max_p.x > m_region.border_maxx())
  598. res |= Range_status::Range_right;
  599. // LOG_IF(WARNING, m_region.region_id() == 4)<< "border minmax x: "<< min_p.x<<", "<<max_p.x<<", res: "<<res;
  600. return res;
  601. #else
  602. /*
  603. if(min_p.x < m_region.border_minx()-0.000)
  604. {
  605. m_range_status_last |= Range_status::Range_left;
  606. }
  607. else if(min_p.x > m_region.border_minx()+0.010)
  608. {
  609. int t = Range_status::Range_left;
  610. m_range_status_last &= (~t);
  611. }
  612. //else m_range_status_last no change
  613. if(max_p.x > m_region.border_maxx()+0.000)
  614. {
  615. m_range_status_last |= Range_status::Range_right;
  616. }
  617. else if(max_p.x < m_region.border_maxx()-0.010)
  618. {
  619. int t = Range_status::Range_right;
  620. m_range_status_last &= (~t);
  621. }
  622. //else m_range_status_last no change
  623. */
  624. //huli 不再使用汽车左右边界来判断,直接使用中心点x值判断左右超界。
  625. //plc坐标,1 3 5入口x为-1.8左右, 2 4 6入口为1.8左右
  626. //要求x取值范围,1650~2150左右
  627. float t_center_x = (min_p.x + max_p.x) / 2 + m_region.plc_offsetx();
  628. if(t_center_x < m_region.border_minx()-0.000)
  629. {
  630. m_range_status_last |= Range_status::Range_left;
  631. }
  632. else if(t_center_x > m_region.border_minx()+0.010)
  633. {
  634. int t = Range_status::Range_left;
  635. m_range_status_last &= (~t);
  636. }
  637. //else m_range_status_last no change
  638. if(t_center_x > m_region.border_maxx()+0.000)
  639. {
  640. m_range_status_last |= Range_status::Range_right;
  641. }
  642. else if(t_center_x < m_region.border_maxx()-0.010)
  643. {
  644. int t = Range_status::Range_right;
  645. m_range_status_last &= (~t);
  646. }
  647. //else m_range_status_last no change
  648. // LOG(WARNING) << "-------------------------------------------------------" <<std::endl;
  649. // LOG(WARNING) << "min_p.x = " << min_p.x <<std::endl;
  650. // LOG(WARNING) << "max_p.x = " << max_p.x <<std::endl;
  651. // LOG(WARNING) << "t_center_x = " << t_center_x <<std::endl;
  652. // LOG(WARNING) << "+++++++++++++++++++++++++++++++++++++++++++++++++++++++" <<std::endl;
  653. return m_range_status_last;
  654. #endif //ANTI_SHAKE
  655. }
  656. 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)
  657. {
  658. int res = Range_status::Range_correct;
  659. if(cloud->size() <= 0)
  660. return res;
  661. // 计算转盘旋转后车辆中心点坐标
  662. Eigen::Vector2d car_center(measure_result.car_center_x, measure_result.car_center_y);
  663. Eigen::Vector2d car_uniform_center;
  664. double theta_rad = theta * M_PI / 180.0;
  665. car_uniform_center.x() = car_center.x() * cos(theta_rad) - car_center.y() * sin(theta_rad);
  666. car_uniform_center.y() = car_center.x() * sin(theta_rad) + car_center.y() * cos(theta_rad);
  667. #ifndef ANTI_SHAKE
  668. // 车位位于y负方向,判断后轮超界情况
  669. //yct old program 20221101
  670. // double rear_wheel_y = car_uniform_center.y() + m_region.plc_offsety() - 0.5 * measure_result.car_wheel_base;
  671. // if(rear_wheel_y < m_region.plc_border_miny())
  672. // {
  673. // res |= Range_status::Range_back;
  674. // }
  675. //huli new program 20221101
  676. double t_center_y = 0.0 - (car_uniform_center.y() + m_region.plc_offsety()); // 汽车中心y, 参照plc坐标,并且进行偏移, 绝对值。结果大约为 5~6左右
  677. if( t_center_y - 4.88 + 0.5*(measure_result.car_wheel_base - 2.7) < m_region.plc_border_maxy() &&
  678. t_center_y - 4.88 - 0.5*(measure_result.car_wheel_base - 2.7) < m_region.plc_border_miny() )
  679. {
  680. //normal
  681. } else
  682. {
  683. res |= Range_status::Range_back;
  684. }
  685. // 判断车辆宽度超界情况
  686. if (measure_result.car_wheel_width < m_region.car_min_width() || measure_result.car_wheel_width > m_region.car_max_width())
  687. {
  688. res |= Range_status::Range_car_width;
  689. }
  690. // 判断车辆轴距超界情况
  691. if (measure_result.car_wheel_base < m_region.car_min_wheelbase() || measure_result.car_wheel_base > m_region.car_max_wheelbase())
  692. {
  693. res |= Range_status::Range_car_wheelbase;
  694. }
  695. //yct old program 20221103 , 使用 velodyne_manager.prototxt 里面的 turnplate_angle_limit 来做边界判断
  696. // 判断车辆旋转角超界情况
  697. // double dtheta = 90-measure_result.car_angle;
  698. // if (dtheta > m_region.turnplate_angle_limit_anti_clockwise())
  699. // {
  700. // res |= Range_status::Range_angle_clock;
  701. // }
  702. // if (dtheta < -m_region.turnplate_angle_limit_clockwise())
  703. // {
  704. // res |= Range_status::Range_angle_anti_clock;
  705. // }
  706. //huli new program 20221103, 使用 plc dispatch_1_statu_port 里面的 来做边界判断
  707. // double t_dtheta = 90-measure_result.car_angle; // 车身的旋转角, 修正到正负5度,
  708. double t_dtheta = measure_result.car_angle + m_region.plc_offset_degree(); // 车身的旋转角, 修正到正5度, (m_region.plc_offset_degree():-89)
  709. int t_terminal_id = m_region.region_id() +1; //region_id:0~5, terminal_id:1~6
  710. //turnplate_angle_min = -5, turnplate_angle_max = 5,
  711. if (t_dtheta > System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_max())
  712. {
  713. res |= Range_status::Range_angle_anti_clock;
  714. }
  715. if (t_dtheta < System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_min())
  716. {
  717. res |= Range_status::Range_angle_clock;
  718. }
  719. // // 判断车辆前轮角回正情况
  720. // if (fabs(measure_result.car_front_theta) > 8.0)
  721. // {
  722. // res |= Range_status::Range_steering_wheel_nozero;
  723. // }
  724. res |= outOfRangeDetection(cloud, plate_cx, plate_cy, theta);
  725. return res;
  726. #else
  727. // LOG(WARNING) << m_range_status_last;
  728. // 车位位于y负方向,判断后轮超界情况
  729. double t_center_y = 0.0 - (car_uniform_center.y() + m_region.plc_offsety()); // 汽车中心y, 参照plc坐标,并且进行偏移, 绝对值。结果大约为 5~6左右
  730. if( t_center_y - 4.88 + 0.5*(measure_result.car_wheel_base - 2.7) < m_region.plc_border_maxy()-0.000 &&
  731. t_center_y - 4.88 - 0.5*(measure_result.car_wheel_base - 2.7) < m_region.plc_border_miny()-0.000 )
  732. {
  733. int t = Range_status::Range_back;
  734. m_range_status_last &= (~t);
  735. }
  736. else if( t_center_y - 4.88 + 0.5*(measure_result.car_wheel_base - 2.7) > m_region.plc_border_maxy()+0.010 ||
  737. t_center_y - 4.88 - 0.5*(measure_result.car_wheel_base - 2.7) > m_region.plc_border_miny()+0.010 )
  738. {
  739. m_range_status_last |= Range_status::Range_back;
  740. }
  741. //else m_range_status_last no change
  742. // LOG(WARNING) << m_range_status_last;
  743. // 判断车辆宽度超界情况
  744. if (measure_result.car_wheel_width < m_region.car_min_width()-0.000 ||
  745. measure_result.car_wheel_width > m_region.car_max_width()+0.000)
  746. {
  747. m_range_status_last |= Range_status::Range_car_width;
  748. }
  749. else if (measure_result.car_wheel_width > m_region.car_min_width()+0.010 &&
  750. measure_result.car_wheel_width < m_region.car_max_width()-0.010)
  751. {
  752. int t = Range_status::Range_car_width;
  753. m_range_status_last &= (~t);
  754. }
  755. //else m_range_status_last no change
  756. // LOG(WARNING) << m_range_status_last;
  757. // 判断车辆轴距超界情况
  758. if (measure_result.car_wheel_base < m_region.car_min_wheelbase()-0.000 ||
  759. measure_result.car_wheel_base > m_region.car_max_wheelbase()+0.000)
  760. {
  761. res |= Range_status::Range_car_wheelbase;
  762. }
  763. else if (measure_result.car_wheel_base > m_region.car_min_wheelbase()+0.010 ||
  764. measure_result.car_wheel_base < m_region.car_max_wheelbase()-0.010)
  765. {
  766. int t = Range_status::Range_car_wheelbase;
  767. m_range_status_last &= (~t);
  768. }
  769. //else m_range_status_last no change
  770. // LOG(WARNING) << m_range_status_last;
  771. // 判断车辆旋转角超界情况
  772. //huli new program 20221103, 使用 plc dispatch_1_statu_port 里面的 来做边界判断
  773. // double t_dtheta = 90-measure_result.car_angle; // 车身的旋转角, 修正到正负5度,
  774. double t_dtheta = measure_result.car_angle + m_region.plc_offset_degree(); // 车身的旋转角, 修正到正5度, (m_region.plc_offset_degree():-89)
  775. int t_terminal_id = m_region.region_id() +1; //region_id:0~5, terminal_id:1~6
  776. //turnplate_angle_min = -5, turnplate_angle_max = 5,
  777. if (t_dtheta > System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_max()+0.00)
  778. {
  779. m_range_status_last |= Range_status::Range_angle_anti_clock;
  780. }
  781. else if (t_dtheta < System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_max()-0.10)
  782. {
  783. int t = Range_status::Range_angle_anti_clock;
  784. m_range_status_last &= (~t);
  785. }
  786. // LOG(WARNING) << m_range_status_last;
  787. //else m_range_status_last no change
  788. if (t_dtheta < System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_min()-0.00)
  789. {
  790. res |= Range_status::Range_angle_clock;
  791. }
  792. else if (t_dtheta > System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_min()+0.10)
  793. {
  794. int t = Range_status::Range_angle_clock;
  795. m_range_status_last &= (~t);
  796. }
  797. // LOG(WARNING) << m_range_status_last;
  798. // LOG(INFO) << t_dtheta<<", "<<System_communication_mq::get_instance_references().dispatch_region_info_map[t_terminal_id].turnplate_angle_min()<<std::endl;
  799. //else m_range_status_last no change
  800. m_range_status_last |= outOfRangeDetection(cloud, plate_cx, plate_cy, theta);
  801. return m_range_status_last;
  802. #endif
  803. }
  804. //外部调用获取当前车轮定位信息, 获取指令时间之后的车轮定位信息, 如果没有就会报错, 不会等待
  805. 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)
  806. {
  807. if ( p_car_wheel_information == NULL )
  808. {
  809. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  810. " POINTER IS NULL ");
  811. }
  812. //获取指令时间之后的信息, 如果没有就会报错, 不会等待
  813. if( m_detect_update_time > command_time )
  814. {
  815. std::lock_guard<std::mutex> lck(m_car_result_mutex);
  816. *p_car_wheel_information = m_car_wheel_information;
  817. if(m_car_wheel_information.correctness)
  818. return Error_code::SUCCESS;
  819. else
  820. return Error_manager(Error_code::VELODYNE_REGION_CERES_SOLVE_ERROR, Error_level::MINOR_ERROR, " Ground_region detect error");
  821. }
  822. else
  823. {
  824. return Error_manager(Error_code::VELODYNE_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
  825. " Ground_region::get_current_wheel_information error ");
  826. }
  827. }
  828. //外部调用获取最新的车轮定位信息, 获取指令时间往前一个周期内的车轮定位信息, 如果没有就会报错, 不会等待
  829. 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)
  830. {
  831. if ( p_car_wheel_information == NULL )
  832. {
  833. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  834. " POINTER IS NULL ");
  835. }
  836. //获取指令时间之后的信息, 如果没有就会报错, 不会等待
  837. // LOG(WARNING) << std::chrono::duration_cast<std::chrono::milliseconds>(command_time-m_detect_update_time).count()/1000.0 <<", "
  838. // <<std::chrono::duration_cast<std::chrono::milliseconds>(command_time-m_cloud_collection_time).count()/1000.0;
  839. if( m_detect_update_time > command_time - std::chrono::milliseconds(GROUND_REGION_DETECT_CYCLE_MS))
  840. {
  841. std::lock_guard<std::mutex> lck(m_car_result_mutex);
  842. *p_car_wheel_information = m_car_wheel_information;
  843. if(m_car_wheel_information.correctness)
  844. return Error_code::SUCCESS;
  845. else
  846. return Error_manager(Error_code::VELODYNE_REGION_CERES_SOLVE_ERROR, Error_level::MINOR_ERROR, " Ground_region detect error");
  847. }
  848. else
  849. {
  850. return Error_manager(Error_code::VELODYNE_REGION_EMPTY_NO_WHEEL_INFORMATION, Error_level::MINOR_ERROR,
  851. " Ground_region::get_current_wheel_information error ");
  852. }
  853. }
  854. Error_manager Ground_region::update_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
  855. {
  856. // // 点云z转90度,调试用
  857. //Eigen::AngleAxisd rot_z = Eigen::AngleAxisd(M_PI_2, Eigen::Vector3d::UnitZ());
  858. //for (size_t i = 0; i < cloud->size(); i++)
  859. //{
  860. // Eigen::Vector3d t_point(cloud->points[i].x, cloud->points[i].y, cloud->points[i].z);
  861. // t_point = rot_z.toRotationMatrix() * t_point;
  862. // cloud->points[i].x = t_point.x();
  863. // cloud->points[i].y = t_point.y();
  864. // cloud->points[i].z = t_point.z();
  865. //}
  866. // 限定锁区域,解决因条件变量在析构时无法获得内部mutex导致此互斥锁卡住,造成死锁无法结束程序的问题。
  867. {
  868. std::lock_guard<std::mutex> lck(m_cloud_collection_mutex);
  869. mp_cloud_collection = cloud;
  870. // LOG(WARNING) << "update region cloud size: " << mp_cloud_collection->size() << ",,, input size: " << cloud->size();
  871. m_cloud_collection_time = std::chrono::system_clock::now();
  872. }
  873. m_measure_condition.notify_one(false, true);
  874. // std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  875. // std::chrono::duration<double> time_used_update = std::chrono::duration_cast<std::chrono::duration<double>>(t1 - t0);
  876. // std::cout << "update cloud time: " << time_used_update.count() << std::endl;
  877. return SUCCESS;
  878. }
  879. void Ground_region::thread_measure_func()
  880. {
  881. LOG(INFO) << " Ground_region::thread_measure_func() start " << this;
  882. while (m_measure_condition.is_alive())
  883. {
  884. m_measure_condition.wait();
  885. if (m_measure_condition.is_alive())
  886. {
  887. m_region_status = E_BUSY;
  888. detect_wheel_ceres3d::Detect_result t_result;
  889. Error_manager ec = detect(mp_cloud_collection, t_result);
  890. std::lock_guard<std::mutex> lck(m_car_result_mutex);
  891. m_detect_update_time = std::chrono::system_clock::now();
  892. // 增加滤波轴距
  893. Common_data::Car_wheel_information_stamped t_wheel_info_stamped;
  894. // 车辆移动检测
  895. Common_data::Car_wheel_information_stamped t_wheel_info_stamped_for_car_move;
  896. if (ec == SUCCESS)
  897. {
  898. m_car_wheel_information.correctness = true;
  899. m_car_wheel_information.car_center_x = t_result.cx;
  900. m_car_wheel_information.car_center_y = t_result.cy;
  901. m_car_wheel_information.car_angle = t_result.theta;
  902. m_car_wheel_information.car_wheel_base = t_result.wheel_base;
  903. m_car_wheel_information.car_wheel_width = t_result.width;
  904. m_car_wheel_information.car_front_theta = t_result.front_theta;
  905. // 220110 added by yct, single wheel width filtering
  906. m_car_wheel_information.single_wheel_width = t_result.single_wheel_width;
  907. m_car_wheel_information.single_wheel_length = t_result.single_wheel_length;
  908. m_car_wheel_information.theta_uniform(m_region.turnplate_cx(), m_region.turnplate_cy());
  909. // 超界校验
  910. {
  911. std::lock_guard<std::mutex> lck(m_filtered_cloud_mutex);
  912. int res = outOfRangeDetection(mp_cloud_filtered, m_car_wheel_information, m_region.turnplate_cx(), m_region.turnplate_cy(), 90.0 - t_result.theta);
  913. m_car_wheel_information.range_status = res;
  914. }
  915. // 添加plc偏移
  916. m_car_wheel_information.car_center_x += m_region.plc_offsetx();
  917. m_car_wheel_information.car_center_y += m_region.plc_offsety();
  918. m_car_wheel_information.uniform_car_x += m_region.plc_offsetx();
  919. m_car_wheel_information.uniform_car_y += m_region.plc_offsety();
  920. m_car_wheel_information.car_angle += m_region.plc_offset_degree();
  921. // LOG(INFO) << "yyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyy t_result.theta = " << t_result.theta << " ";
  922. // LOG(INFO) << "yyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyy m_region.plc_offset_degree() = " << m_region.plc_offset_degree() << " ";
  923. // LOG(INFO) << "yyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyy m_car_wheel_information.car_angle= " << m_car_wheel_information.car_angle << " ";
  924. t_wheel_info_stamped.wheel_data = m_car_wheel_information;
  925. t_wheel_info_stamped.measure_time = m_detect_update_time;
  926. Measure_filter::get_instance_references().update_data(m_region.region_id(), t_wheel_info_stamped);
  927. // 20211228 added by yct, car movement checking, human and door detection
  928. t_wheel_info_stamped_for_car_move = t_wheel_info_stamped;
  929. t_wheel_info_stamped_for_car_move.wheel_data.car_center_x -= m_region.plc_offsetx();
  930. t_wheel_info_stamped_for_car_move.wheel_data.car_center_y -= m_region.plc_offsety();
  931. t_wheel_info_stamped_for_car_move.wheel_data.uniform_car_x -= m_region.plc_offsetx();
  932. t_wheel_info_stamped_for_car_move.wheel_data.uniform_car_y -= m_region.plc_offsety();
  933. t_wheel_info_stamped_for_car_move.wheel_data.car_angle -= m_region.plc_offset_degree();
  934. 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);
  935. // success means car stable
  936. if(car_status_res == SUCCESS)
  937. {
  938. m_car_wheel_information.range_status &= ~((int)Range_status::Range_car_moving);
  939. }else
  940. {
  941. m_car_wheel_information.range_status |= Range_status::Range_car_moving;
  942. // if(m_region.region_id()==4){
  943. // std::cout<<"success: "<<car_status_res.to_string()<<std::endl;
  944. // }
  945. }
  946. Region_status_checker::get_instance_references().add_measure_data(m_region.region_id(), t_wheel_info_stamped_for_car_move, *mp_cloud_filtered);
  947. ec = Measure_filter::get_instance_references().get_filtered_wheel_information(m_region.region_id(), t_wheel_info_stamped.wheel_data);
  948. if (ec == SUCCESS)
  949. {
  950. // 20221208 added by yct, use avg car angle and width data.
  951. // LOG(WARNING)<<m_region.region_id()<<" angles: "<<m_car_wheel_information.car_angle<<", "<<t_wheel_info_stamped.wheel_data.car_angle;
  952. LOG(WARNING)<<m_region.region_id()<<" filter res: "<<t_wheel_info_stamped.wheel_data.to_string()<<std::endl;
  953. // m_car_wheel_information.car_angle = t_wheel_info_stamped.wheel_data.car_angle;
  954. // m_car_wheel_information.car_wheel_width = t_wheel_info_stamped.wheel_data.car_wheel_width;
  955. m_car_wheel_information.car_wheel_base = t_wheel_info_stamped.wheel_data.car_wheel_base;
  956. m_car_wheel_information.car_front_theta = t_wheel_info_stamped.wheel_data.car_front_theta;
  957. // 临时添加,滤波后前轮超界
  958. if(fabs(m_car_wheel_information.car_front_theta)>8.0)
  959. {
  960. m_car_wheel_information.range_status |= Range_status::Range_steering_wheel_nozero;
  961. }
  962. }
  963. // else{
  964. // std::cout<<ec.to_string()<<std::endl;
  965. // }
  966. // LOG_IF(INFO, m_region.region_id() == 1) << m_car_wheel_information.to_string();
  967. }
  968. else
  969. {
  970. m_car_wheel_information.correctness = false;
  971. // LOG_IF(ERROR, m_region.region_id() == 1) << ec.to_string();
  972. // 20211228 added by yct, car movement checking, human and door detection
  973. 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);
  974. // success means car stable
  975. if(car_status_res == SUCCESS)
  976. {
  977. m_car_wheel_information.range_status &= ~((int)Range_status::Range_car_moving);
  978. }else
  979. {
  980. m_car_wheel_information.range_status |= Range_status::Range_car_moving;
  981. // if(m_region.region_id()==1){
  982. // std::cout<<"failed: "<<car_status_res.to_string()<<std::endl;
  983. // }
  984. }
  985. }
  986. }
  987. m_region_status = E_READY;
  988. }
  989. LOG(INFO) << " Ground_region::thread_measure_func() end " << this;
  990. }