region_status_checker.h 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409
  1. /*
  2. * @Description: 区域状态检查类,用于判断当前各区域车辆状态(已停好、运动中),以及周围是否有障碍物
  3. * @Author: yct
  4. * @Date: 2021-12-21 19:54:34
  5. * @LastEditTime: 2021-12-28 11:53:11
  6. * @LastEditors: yct
  7. */
  8. #ifndef REGION_STATUS_CHECKER_HH
  9. #define REGION_STATUS_CHECKER_HH
  10. #include "../tool/singleton.h"
  11. #include "../tool/common_data.h"
  12. #include "../error_code/error_code.h"
  13. #include <map>
  14. #include <mutex>
  15. #include <deque>
  16. #include <chrono>
  17. #include <vector>
  18. #include <algorithm>
  19. #include <thread>
  20. #include "glog/logging.h"
  21. #include <pcl/point_types.h>
  22. #include <pcl/point_cloud.h>
  23. // #include <pcl/registration/ndt.h>
  24. #include <pcl/filters/voxel_grid.h>
  25. #include "icp_svd_registration.hpp"
  26. // #include "opencv2/opencv.hpp"
  27. #include "../tool/point_tool.h"
  28. #define DEFAULT_REGION_STATUS_TIMEOUT_MILLI 600000
  29. #define DEFAULT_REGION_STATUS_MAX_QUEUE_SIZE 600
  30. // 检测到静止后稳定时间
  31. #define MIN_STABLE_TIME_MILLI 1000
  32. // 外点差异量
  33. #define OUTSIDE_POINT_LIMIT 30
  34. class Region_status_checker : public Singleton<Region_status_checker>
  35. {
  36. // 子类必须把父类设定为友元函数,这样父类才能使用子类的私有构造函数。
  37. friend class Singleton<Region_status_checker>;
  38. struct Region_measure_info_stamped
  39. {
  40. Common_data::Car_wheel_information_stamped measure_result;
  41. pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud;
  42. Region_measure_info_stamped()
  43. {
  44. p_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  45. }
  46. // ~Region_measure_info_stamped()
  47. // {
  48. // p_cloud->clear();
  49. // }
  50. };
  51. public:
  52. // 必须关闭拷贝构造和赋值构造,只能通过 get_instance 函数来进行操作唯一的实例。
  53. Region_status_checker(const Region_status_checker &) = delete;
  54. Region_status_checker &operator=(const Region_status_checker &) = delete;
  55. ~Region_status_checker() = default;
  56. void Region_status_checker_init()
  57. {
  58. mb_exit = false;
  59. // mp_icp_svd = new ICPSVDRegistration(0.1, 0.0018, 0.036, 20);
  60. // mp_icp_svd = new ICPSVDRegistration(0.1, 0.0002, 0.036, 20);
  61. // mp_ndt = pcl::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ>::Ptr(new pcl::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ>);
  62. // mp_ndt->setMaxCorrespondenceDistance(0.2);
  63. // mp_ndt->setTransformationEpsilon(0.01);
  64. // mp_ndt->setEuclideanFitnessEpsilon(0.09);
  65. // mp_ndt->setMaximumIterations(10);
  66. m_manager_thread = new std::thread(&Region_status_checker::thread_func, this);
  67. }
  68. void Region_status_checker_uninit()
  69. {
  70. mb_exit = true;
  71. if(m_manager_thread != nullptr)
  72. {
  73. if(m_manager_thread->joinable())
  74. {
  75. m_manager_thread->join();
  76. }
  77. delete m_manager_thread;
  78. m_manager_thread = nullptr;
  79. }
  80. for (auto iter = m_icp_svd_map.begin(); iter != m_icp_svd_map.end(); iter++)
  81. {
  82. if(iter->second!= nullptr)
  83. {
  84. delete iter->second;
  85. iter->second = nullptr;
  86. }
  87. }
  88. // if(mp_icp_svd!=nullptr)
  89. // {
  90. // delete mp_icp_svd;
  91. // mp_icp_svd = nullptr;
  92. // }
  93. }
  94. // 更新测量数据回调
  95. void add_measure_data(int terminal_id, Common_data::Car_wheel_information_stamped& measure_result, pcl::PointCloud<pcl::PointXYZ>& cloud)
  96. {
  97. Region_measure_info_stamped data;
  98. data.measure_result = measure_result;
  99. std::vector<int> index;
  100. // cloud.is_dense = false;
  101. // pcl::removeNaNFromPointCloud(cloud, data.cloud, index);
  102. data.p_cloud->operator+=(cloud);
  103. if (!data.measure_result.wheel_data.correctness)
  104. return;
  105. // LOG(INFO) << data.wheel_data.to_string();
  106. // 未创建队列
  107. std::lock_guard<std::mutex> lck(m_mutex);
  108. if (m_measure_results_map.find(terminal_id) == m_measure_results_map.end())
  109. {
  110. std::deque<Region_measure_info_stamped> t_deque;
  111. t_deque.push_back(data);
  112. m_measure_results_map.insert(std::pair<int, std::deque<Region_measure_info_stamped>>(terminal_id, t_deque));
  113. m_icp_svd_map.insert(std::pair<int, ICPSVDRegistration*>(terminal_id, new ICPSVDRegistration(0.1, 0.0018, 0.036, 20)));
  114. }
  115. else//已创建
  116. {
  117. m_measure_results_map[terminal_id].push_back(data);
  118. }
  119. }
  120. // 根据当前帧判断区域停车状态
  121. // 当前帧不需要存在正确结果,利用点云判断是否车辆未移动即可
  122. Error_manager get_region_parking_status(int terminal_id, Common_data::Car_wheel_information_stamped& measure_result, pcl::PointCloud<pcl::PointXYZ>& cloud)
  123. {
  124. std::lock_guard<std::mutex> lck(m_mutex);
  125. if(cloud.size() <= 0)
  126. {
  127. return Error_manager(WJ_FILTER_LACK_OF_RESULT, MINOR_ERROR, (std::string("当前空点云 终端") + std::to_string(terminal_id)).c_str());
  128. }
  129. if(m_icp_svd_map.find(terminal_id) == m_icp_svd_map.end())
  130. {
  131. return Error_manager(WJ_FILTER_LACK_OF_RESULT, MINOR_ERROR, (std::string("当前icp空指针 终端") + std::to_string(terminal_id)).c_str());
  132. }
  133. ICPSVDRegistration* tp_icp_svd = m_icp_svd_map[terminal_id];
  134. if(m_measure_results_map.find(terminal_id) == m_measure_results_map.end() || m_measure_results_map[terminal_id].size() == 0)
  135. {
  136. return Error_manager(WJ_FILTER_LACK_OF_RESULT, MINOR_ERROR, (std::string("暂无最近历史数据用于推测当前状态 终端") + std::to_string(terminal_id)).c_str());
  137. }
  138. // 时间检查, 当前队列中数据全为正确
  139. // 计算最近一帧外框,x一边外扩4cm, y一边外扩100cm
  140. auto last_data_ref = m_measure_results_map[terminal_id].back();
  141. if(std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now()-last_data_ref.measure_result.measure_time).count() > DEFAULT_REGION_STATUS_TIMEOUT_MILLI)
  142. {
  143. return Error_manager(WJ_FILTER_LACK_OF_RESULT, MINOR_ERROR, (std::string("最近历史数据超时 终端") + std::to_string(terminal_id)).c_str());
  144. }
  145. // std::cout<<"000000"<<std::endl;
  146. // 截取当前帧框内与框外点云
  147. Eigen::Vector2d t_last_center(
  148. last_data_ref.measure_result.wheel_data.car_center_x,
  149. last_data_ref.measure_result.wheel_data.car_center_y);
  150. Eigen::Vector2d t_width_height(
  151. last_data_ref.measure_result.wheel_data.car_wheel_width + 0.08,
  152. last_data_ref.measure_result.wheel_data.car_wheel_base + 2.0);
  153. // 历史正确数据整车旋转
  154. Eigen::Rotation2Dd t_rot((90 - last_data_ref.measure_result.wheel_data.car_angle) * M_PI / 180.0);
  155. Eigen::Matrix2d t_rot_mat = t_rot.toRotationMatrix();
  156. // 计算历史(模板)框内点云与框外点云
  157. pcl::PointCloud<pcl::PointXYZ>::Ptr t_prev_cloud_inside = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  158. pcl::PointCloud<pcl::PointXYZ>::Ptr t_prev_cloud_outside = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  159. for (size_t i = 0; i < last_data_ref.p_cloud->size(); i++)
  160. {
  161. Eigen::Vector2d t_point(last_data_ref.p_cloud->points[i].x - t_last_center.x(), last_data_ref.p_cloud->points[i].y - t_last_center.y());
  162. Eigen::Vector2d t_rot_point = t_rot_mat * t_point;
  163. if (t_rot_point.x() > -t_width_height.x() / 2.0 && t_rot_point.x() < t_width_height.x() / 2.0 && t_rot_point.y() > -t_width_height.y() / 2.0 && t_rot_point.y() < t_width_height.y() / 2.0)
  164. {
  165. t_prev_cloud_inside->push_back(last_data_ref.p_cloud->points[i]);
  166. }
  167. else
  168. {
  169. t_prev_cloud_outside->push_back(last_data_ref.p_cloud->points[i]);
  170. }
  171. // if(std::isfinite(last_data_ref.cloud[i].x) && std::isfinite(last_data_ref.cloud[i].y) && std::isfinite(last_data_ref.cloud[i].z))
  172. // {
  173. // }else
  174. // {
  175. // std::cout << "!!!!!!!!!!!!!!!!!!!!!!!! prev nan point" << std::endl;
  176. // }
  177. }
  178. // std::cout<<"111111"<<std::endl;
  179. // 计算当前帧在框内与框外点云
  180. pcl::PointCloud<pcl::PointXYZ>::Ptr t_curr_cloud_inside = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  181. pcl::PointCloud<pcl::PointXYZ>::Ptr t_curr_cloud_outside = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  182. std::vector<int> index;
  183. pcl::PointCloud<pcl::PointXYZ> t_cloud_valid;
  184. t_cloud_valid = cloud;
  185. // t_cloud_valid.is_dense = false;
  186. // pcl::removeNaNFromPointCloud(t_cloud_valid, t_cloud_valid, index);
  187. for (size_t i = 0; i < t_cloud_valid.size(); i++)
  188. {
  189. Eigen::Vector2d t_point(t_cloud_valid[i].x - t_last_center.x(), t_cloud_valid[i].y - t_last_center.y());
  190. Eigen::Vector2d t_rot_point = t_rot_mat * t_point;
  191. if (t_rot_point.x() > -t_width_height.x() / 2.0 && t_rot_point.x() < t_width_height.x() / 2.0 && t_rot_point.y() > -t_width_height.y() / 2.0 && t_rot_point.y() < t_width_height.y() / 2.0)
  192. {
  193. t_curr_cloud_inside->push_back(t_cloud_valid[i]);
  194. }
  195. else
  196. {
  197. t_curr_cloud_outside->push_back(t_cloud_valid[i]);
  198. }
  199. // if(std::isfinite(t_cloud_valid[i].x) && std::isfinite(t_cloud_valid[i].y) && std::isfinite(t_cloud_valid[i].z))
  200. // {
  201. // }else{
  202. // std::cout << "!!!!!!!!!!!!!!!!!!!!!!!! curr nan point" << std::endl;
  203. // }
  204. }
  205. // std::cout<<"222222"<<std::endl;
  206. if(t_prev_cloud_inside->size() <= 30 || t_curr_cloud_inside->size() <= 30)
  207. {
  208. char buf[255];
  209. memset(buf, 0, 255);
  210. sprintf(buf, ",, prev %ld, curr %ld;; last center(%.3f, %.3f)", t_prev_cloud_inside->size(), t_curr_cloud_inside->size(), t_last_center.x(), t_last_center.y());
  211. return Error_manager(WJ_FILTER_LACK_OF_RESULT, MINOR_ERROR, (std::string("区域剪切后无点可用于匹配 终端") + std::to_string(terminal_id)+std::string(buf)).c_str());
  212. }
  213. // std::cout << "000" << std::endl;
  214. // 直接使用当前时间,测量时间传入存在变为0的情况!!!!!
  215. measure_result.measure_time = std::chrono::system_clock::now();
  216. double dtime = std::chrono::duration_cast<std::chrono::milliseconds>(measure_result.measure_time - last_data_ref.measure_result.measure_time).count();
  217. // double curr_time = std::chrono::duration_cast<std::chrono::milliseconds>(measure_result.measure_time.time_since_epoch()).count();
  218. // double last_time = std::chrono::duration_cast<std::chrono::milliseconds>(last_data_ref.measure_result.measure_time.time_since_epoch()).count();
  219. // std::cout << "dtime " << dtime / 1000.0 << ",, curr, last: " << curr_time << ", " << last_time << ", diff: " << curr_time - last_time << std::endl;
  220. // icp计算前后内点匹配情况
  221. //下采样
  222. pcl::PointCloud<pcl::PointXYZ>::Ptr t_prev_cloud_inside_filtered = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  223. pcl::PointCloud<pcl::PointXYZ>::Ptr t_curr_cloud_inside_filtered = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  224. pcl::VoxelGrid<pcl::PointXYZ> vox; //创建滤波对象
  225. vox.setInputCloud(t_prev_cloud_inside); //设置需要过滤的点云给滤波对象
  226. vox.setLeafSize(0.03f, 0.03f, 0.03f); //设置滤波时创建的体素体积为1cm的立方体
  227. vox.filter(*t_prev_cloud_inside_filtered); //执行滤波处理,存储输出
  228. vox.setInputCloud(t_curr_cloud_inside); //设置需要过滤的点云给滤波对象
  229. vox.setLeafSize(0.03f, 0.03f, 0.03f); //设置滤波时创建的体素体积为1cm的立方体
  230. vox.filter(*t_curr_cloud_inside_filtered); //执行滤波处理,存储输出
  231. tp_icp_svd->SetInputTarget(t_prev_cloud_inside_filtered);
  232. // static int count = 0;
  233. // if(count++ == 20)
  234. // {
  235. // save_cloud_txt(t_prev_cloud_inside_filtered, "./t_prev_cloud.txt");
  236. // save_cloud_txt(t_curr_cloud_inside_filtered, "./t_curr_cloud.txt");
  237. // }
  238. // std::cout << "111" << std::endl;
  239. pcl::PointCloud<pcl::PointXYZ>::Ptr t_result_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  240. Eigen::Matrix4f t_pred_pose, t_res_pose;
  241. t_pred_pose = Eigen::Matrix4f::Identity();
  242. // std::cout << "222" << std::endl;
  243. if (!tp_icp_svd->ScanMatch(t_curr_cloud_inside_filtered, t_pred_pose, t_result_cloud, t_res_pose))
  244. {
  245. return Error_manager(WJ_FILTER_FLUCTUATING, MINOR_ERROR, (std::string("icp匹配失败,终端") + std::to_string(terminal_id)).c_str());
  246. }
  247. // std::cout << "2222" << std::endl;
  248. if(is_significant(t_res_pose, dtime / 1000.0))
  249. {
  250. mb_is_stable = false;
  251. return Error_manager(WJ_FILTER_FLUCTUATING, MINOR_ERROR, (std::string("检测到车辆移动,终端") + std::to_string(terminal_id)).c_str());
  252. }else{
  253. if (!mb_is_stable)
  254. {
  255. mb_is_stable = true;
  256. m_stable_time = std::chrono::system_clock::now();
  257. return Error_manager(WJ_FILTER_FLUCTUATING, MINOR_ERROR, (std::string("开始等待稳定,终端") + std::to_string(terminal_id)).c_str());
  258. }else
  259. {
  260. auto current_time = std::chrono::system_clock::now();
  261. double duration = std::chrono::duration_cast<std::chrono::milliseconds>(current_time - m_stable_time).count();
  262. if(duration > MIN_STABLE_TIME_MILLI)
  263. {
  264. // 判断外点数量
  265. // LOG_IF(WARNING, terminal_id == 4) << "ouside point prev curr: " << t_prev_cloud_outside->size() << ", " << t_curr_cloud_outside->size();
  266. if (t_curr_cloud_outside->size() > (t_prev_cloud_outside->size() + OUTSIDE_POINT_LIMIT))
  267. {
  268. // debug提示用
  269. // LOG_IF(WARNING, terminal_id == 4) << "检测到车身外侧噪点存在!!!";
  270. }
  271. return SUCCESS;
  272. }else
  273. {
  274. return Error_manager(WJ_FILTER_FLUCTUATING, MINOR_ERROR, (std::string("等待稳定中,终端") + std::to_string(terminal_id)).c_str());
  275. }
  276. }
  277. }
  278. // std::cout << "333" << std::endl;
  279. return ERROR;
  280. }
  281. // 显著性判断,平移x方向速度0.02m/s,y方向速度0.06m/s误差,角度3deg/s误差
  282. bool is_significant(Eigen::Matrix4f trans, double dtime, double vx_eps = 0.06, double vy_eps = 0.06, double omega_eps = 0.051)
  283. {
  284. // 间隔时间为负数,或间隔超过0.5s则手动赋值
  285. if(dtime<0 || dtime>0.5)
  286. {
  287. dtime = 0.1;
  288. }
  289. // return false;
  290. Eigen::Vector3f translation = trans.block<3, 1>(0, 3);
  291. float rot_angle = fabs(acos((std::min(trans.block<3, 3>(0, 0).trace(), 2.999999f) - 1.0f) / 2.0f));
  292. // 值足够小,可当做车辆未移动
  293. Eigen::Vector3d velocity(fabs(translation.x() / dtime), fabs(translation.y() / dtime), fabs(rot_angle / dtime));
  294. if (velocity.x() <= vx_eps && velocity.y() <= vy_eps && velocity.z() <= omega_eps)
  295. {
  296. return false;
  297. }
  298. // char buf[512] = {0};
  299. // sprintf(buf, "显著性分析, 速度 %.3f %.3f %.3f", velocity.x(), velocity.y(), velocity.z());
  300. // LOG(INFO) << buf << ", dtime: " << dtime;
  301. // // LOG(WARNING) << "???????????????????????????????????显著??????";
  302. // if (velocity.x() > vx_eps)
  303. // {
  304. // LOG(WARNING) << "x:" << velocity.x();
  305. // }
  306. // if(velocity.y() > vy_eps)
  307. // {
  308. // LOG(WARNING) << "y:" << velocity.y();
  309. // }
  310. // if(velocity.z() > omega_eps)
  311. // {
  312. // LOG(WARNING) << "z:" << velocity.z();
  313. // }
  314. return true;
  315. }
  316. void thread_func()
  317. {
  318. while(!mb_exit)
  319. {
  320. {
  321. std::lock_guard<std::mutex> lck(m_mutex);
  322. for (auto iter = m_measure_results_map.begin(); iter != m_measure_results_map.end(); iter++)
  323. {
  324. std::deque<Region_measure_info_stamped> *tp_data_queue = &(iter->second);
  325. for (size_t i = 0; i < tp_data_queue->size(); i++)
  326. {
  327. // 判断队列头部(最老历史数据)是否超时,超时则丢出
  328. double dtime = std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now() - tp_data_queue->front().measure_result.measure_time).count();
  329. if(dtime > DEFAULT_REGION_STATUS_TIMEOUT_MILLI)
  330. {
  331. tp_data_queue->pop_front();
  332. }
  333. }
  334. // 维持队列长度
  335. while (tp_data_queue->size() > DEFAULT_REGION_STATUS_MAX_QUEUE_SIZE)
  336. {
  337. tp_data_queue->pop_front();
  338. }
  339. }
  340. }
  341. usleep(1000 * 100);
  342. }
  343. }
  344. private:
  345. // 父类的构造函数必须保护,子类的构造函数必须私有。
  346. Region_status_checker() = default;
  347. // map访问锁
  348. std::mutex m_mutex;
  349. // 各终端测量数据队列
  350. std::map<int, std::deque<Region_measure_info_stamped> > m_measure_results_map;
  351. bool mb_exit;
  352. // 内部管理线程
  353. std::thread *m_manager_thread;
  354. // // 配置参数
  355. // // 合法时间长度,即过去多久时间内数据有效
  356. // double m_valid_time_milli;
  357. // // 队列极限长度
  358. // double m_max_queue_size;
  359. // icp匹配
  360. // ICPSVDRegistration *mp_icp_svd;
  361. std::map<int, ICPSVDRegistration*> m_icp_svd_map;
  362. // 是否已经稳定
  363. bool mb_is_stable;
  364. // 最初稳定时刻
  365. std::chrono::system_clock::time_point m_stable_time;
  366. // // 点云高度截断,保留底层点云匹配
  367. // double height_limit;
  368. };
  369. #endif // !REGION_STATUS_CHECKER_HH