system_executor.cpp 34 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805
  1. //
  2. // Created by huli on 2020/7/2.
  3. //
  4. #include "system_executor.h"
  5. // std::ofstream g_debug_file; // 用于测试滤波功能
  6. System_executor::System_executor()
  7. {
  8. }
  9. System_executor::~System_executor()
  10. {
  11. system_executor_uninit();
  12. }
  13. //初始化
  14. Error_manager System_executor::system_executor_init(int threads_size, int terminal_id)
  15. {
  16. m_thread_pool.thread_pool_init(threads_size);
  17. m_system_executor_status = SYSTEM_EXECUTOR_READY;
  18. m_terminal_id = terminal_id;
  19. return Error_code::SUCCESS;
  20. }
  21. //反初始化
  22. Error_manager System_executor::system_executor_uninit()
  23. {
  24. // if(g_debug_file.is_open())
  25. // g_debug_file.close();
  26. m_thread_pool.thread_pool_uninit();
  27. m_system_executor_status = SYSTEM_EXECUTOR_UNKNOW;
  28. return Error_code::SUCCESS;
  29. }
  30. //检查消息是否有效, 主要检查消息类型和接受者, 判断这条消息是不是给我的.
  31. Error_manager System_executor::check_msg(Communication_message* p_msg)
  32. {
  33. if ( p_msg == NULL )
  34. {
  35. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  36. " POINTER IS NULL ");
  37. }
  38. //检查消息类型
  39. switch ( p_msg->get_message_type() )
  40. {
  41. case Communication_message::Message_type::eGround_detect_request_msg:
  42. {
  43. //检查接受人
  44. if ( p_msg->get_receiver() == Communication_message::Communicator::eGround_measurer)
  45. {
  46. message::Ground_detect_request_msg t_ground_detect_request_msg;
  47. //针对消息类型, 对消息进行二次解析
  48. if (t_ground_detect_request_msg.ParseFromString(p_msg->get_message_buf()))
  49. {
  50. // //检查终端id
  51. // 普爱不检查终端id
  52. // 楚天检查终端id
  53. // if ( t_ground_detect_request_msg.terminal_id() == m_terminal_id )
  54. // {
  55. return Error_code::SUCCESS;
  56. // }
  57. }
  58. }
  59. break;
  60. }
  61. default :
  62. ;
  63. break;
  64. }
  65. //无效的消息,
  66. return Error_manager(Error_code::INVALID_MESSAGE, Error_level::NEGLIGIBLE_ERROR,
  67. " INVALID_MESSAGE error ");
  68. }
  69. //检查执行者的状态, 判断能否处理这条消息,
  70. Error_manager System_executor::check_executer(Communication_message* p_msg)
  71. {
  72. //huli DDDDDDDDDDDDDDDDDDDDDDDDDDDDDDDD 记得删除
  73. return Error_code::SUCCESS;
  74. if ( p_msg == NULL )
  75. {
  76. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  77. " POINTER IS NULL ");
  78. }
  79. Error_manager t_error;
  80. //通过 p_msg->get_message_type() 和 p_msg->get_receiver() 找到处理模块的实例对象, 查询执行人是否可以处理这条消息
  81. switch ( p_msg->get_message_type() )
  82. {
  83. case Communication_message::Message_type::eGround_detect_request_msg:
  84. {
  85. Error_manager t_executor_result = System_executor::get_instance_references().check_status();
  86. if (t_executor_result == SUCCESS)
  87. {
  88. return Error_code::SUCCESS;
  89. }
  90. else
  91. {
  92. //整合所有的错误码
  93. t_error.compare_and_cover_error(t_executor_result);
  94. if (t_error.get_error_level() == NEGLIGIBLE_ERROR)//一级故障,轻微故障,
  95. {
  96. LOG(INFO) << "executer_is_busy , ";
  97. //返回繁忙之后, 通信模块1秒后再次调用check
  98. return Error_code::COMMUNICATION_EXCUTER_IS_BUSY;
  99. }
  100. else//返回二级故障,可以封装一条答复信息, 返回错误码
  101. {
  102. message::Ground_detect_request_msg t_ground_detect_request_msg;
  103. //针对消息类型, 对消息进行二次解析
  104. if (t_ground_detect_request_msg.ParseFromString(p_msg->get_message_buf()))
  105. {
  106. //创建一条答复消息
  107. message::Ground_detect_response_msg t_ground_detect_response_msg;
  108. t_ground_detect_response_msg.mutable_base_info()->set_msg_type(message::Message_type::eGround_detect_response_msg);
  109. t_ground_detect_response_msg.mutable_base_info()->set_timeout_ms(5000);
  110. t_ground_detect_response_msg.mutable_base_info()->set_sender(message::Communicator::eGround_measurer);
  111. t_ground_detect_response_msg.mutable_base_info()->set_receiver(message::Communicator::eMain);
  112. t_ground_detect_response_msg.set_command_key(t_ground_detect_request_msg.command_key());
  113. t_ground_detect_response_msg.mutable_id_struct()->set_terminal_id(t_ground_detect_request_msg.id_struct().terminal_id());
  114. t_ground_detect_response_msg.mutable_error_manager()->set_error_code(t_error.get_error_code());
  115. t_ground_detect_response_msg.mutable_error_manager()->set_error_level((message::Error_level)t_error.get_error_level());
  116. t_ground_detect_response_msg.mutable_error_manager()->set_error_description(t_error.get_error_description());
  117. std::string t_msg = t_ground_detect_response_msg.SerializeAsString();
  118. System_communication::get_instance_references().encapsulate_msg(t_msg);
  119. LOG(INFO) << " System_executor::check_executer executer status error "<< this;
  120. return t_error;
  121. }
  122. else
  123. {
  124. LOG(INFO) << " System_executor::check_executer second PARSE_ERROR "<< this;
  125. return Error_manager(Error_code::SYSTEM_EXECUTOR_PARSE_ERROR, Error_level::MINOR_ERROR,
  126. " message::Measure_request_msg ParseFromString error ");
  127. }
  128. }
  129. }
  130. break;
  131. }
  132. default :
  133. ;
  134. break;
  135. }
  136. return t_error;
  137. }
  138. //处理消息的执行函数
  139. Error_manager System_executor::execute_msg(Communication_message* p_msg)
  140. {
  141. if ( p_msg == NULL )
  142. {
  143. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  144. " POINTER IS NULL ");
  145. }
  146. // std::cout << " huli test ::333333333333333333333333333333:: " << " p_msg->get_message_type() = " << p_msg->get_message_type() << std::endl;
  147. switch ( p_msg->get_message_type() )
  148. {
  149. case Communication_message::eGround_detect_request_msg:
  150. {
  151. message::Ground_detect_request_msg t_ground_detect_request_msg;
  152. //针对消息类型, 对消息进行二次解析
  153. if (t_ground_detect_request_msg.ParseFromString(p_msg->get_message_buf()) && t_ground_detect_request_msg.id_struct().has_terminal_id())
  154. {
  155. //往线程池添加执行任务, 之后会唤醒一个线程去执行他.
  156. m_thread_pool.enqueue(&System_executor::execute_for_measure, this,
  157. t_ground_detect_request_msg.command_key(), t_ground_detect_request_msg.id_struct().terminal_id(),
  158. p_msg->get_receive_time());
  159. }
  160. else
  161. {
  162. return Error_manager(Error_code::SYSTEM_EXECUTOR_PARSE_ERROR, Error_level::MINOR_ERROR,
  163. " message::Measure_request_msg ParseFromString error ");
  164. }
  165. break;
  166. }
  167. default:
  168. {
  169. }
  170. }
  171. return Error_code::SUCCESS;
  172. }
  173. //检查状态
  174. Error_manager System_executor::check_status()
  175. {
  176. if ( m_system_executor_status == SYSTEM_EXECUTOR_READY )
  177. {
  178. if ( m_thread_pool.thread_is_full_load() == false )
  179. {
  180. return Error_code::SUCCESS;
  181. }
  182. else
  183. {
  184. return Error_manager(Error_code::SYSTEM_EXECUTOR_STATUS_BUSY, Error_level::NEGLIGIBLE_ERROR,
  185. " System_executor::check_status error ");
  186. }
  187. }
  188. else
  189. {
  190. return Error_manager(Error_code::SYSTEM_EXECUTOR_STATUS_ERROR, Error_level::MINOR_ERROR,
  191. " System_executor::check_status error ");
  192. }
  193. }
  194. // 更新消息中关于定位结果与超界信息的内容
  195. bool System_executor::update_measure_info(message::Ground_status_msg &msg, Common_data::Car_wheel_information &measure_info, int cloud_size)
  196. {
  197. Error_manager t_error;
  198. //无论定位结果如何, 都要填充数据, 即使全部写0, 必须保证通信格式正确.
  199. message::Locate_information t_locate_information;
  200. //= t_multi_status_msg.add_locate_information_realtime();
  201. t_locate_information.set_locate_x(measure_info.car_center_x);
  202. t_locate_information.set_locate_y(measure_info.car_center_y);
  203. t_locate_information.set_locate_angle(measure_info.car_angle);
  204. t_locate_information.set_locate_length(0);
  205. t_locate_information.set_locate_width(0);
  206. t_locate_information.set_locate_height(0);
  207. t_locate_information.set_locate_wheel_base(measure_info.car_wheel_base);
  208. t_locate_information.set_locate_wheel_width(measure_info.car_wheel_width);
  209. t_locate_information.set_locate_front_theta(measure_info.car_front_theta);
  210. t_locate_information.set_locate_correct(measure_info.correctness);
  211. t_locate_information.set_uniformed_car_x(measure_info.uniform_car_x);
  212. t_locate_information.set_uniformed_car_y(measure_info.uniform_car_y);
  213. msg.mutable_locate_information_realtime()->CopyFrom(t_locate_information);
  214. // 当前超界提示仅保留一项
  215. // 20211026已修改,分离为电子围栏状态与超界状态,只有测量正确时超界状态才有意义
  216. msg.set_border_status(measure_info.range_status);
  217. if (!measure_info.correctness)
  218. {
  219. if (cloud_size > 0)
  220. msg.set_ground_status(message::Ground_statu::Noise);
  221. else
  222. msg.set_ground_status(message::Ground_statu::Nothing);
  223. }
  224. else if (measure_info.range_status == int(Ground_region::Range_status::Range_correct))
  225. {
  226. msg.set_ground_status(message::Ground_statu::Car_correct);
  227. }
  228. else
  229. {
  230. msg.set_ground_status(message::Ground_statu::Car_border_reached);
  231. // 更新待提示错误信息
  232. std::string t_error_str;
  233. if (measure_info.range_status & Ground_region::Range_status::Range_front != 0)
  234. {
  235. t_error_str.append("前超界 ");
  236. }
  237. if (measure_info.range_status & Ground_region::Range_status::Range_back != 0)
  238. {
  239. t_error_str.append("后超界 ");
  240. }
  241. if (measure_info.range_status & Ground_region::Range_status::Range_left != 0)
  242. {
  243. t_error_str.append("左超界 ");
  244. }
  245. if (measure_info.range_status & Ground_region::Range_status::Range_right != 0)
  246. {
  247. t_error_str.append("右超界 ");
  248. }
  249. if (measure_info.range_status & Ground_region::Range_status::Range_bottom != 0)
  250. {
  251. t_error_str.append("底盘超界 ");
  252. }
  253. if (measure_info.range_status & Ground_region::Range_status::Range_top != 0)
  254. {
  255. t_error_str.append("顶超界 ");
  256. }
  257. if (measure_info.range_status & Ground_region::Range_status::Range_car_width != 0)
  258. {
  259. t_error_str.append("车宽超界 ");
  260. }
  261. if (measure_info.range_status & Ground_region::Range_status::Range_car_wheelbase != 0)
  262. {
  263. t_error_str.append("轴距超界 ");
  264. }
  265. if (measure_info.range_status & Ground_region::Range_status::Range_angle_anti_clock != 0)
  266. {
  267. t_error_str.append("车辆角度左超界 ");
  268. }
  269. if (measure_info.range_status & Ground_region::Range_status::Range_angle_clock != 0)
  270. {
  271. t_error_str.append("车辆角度右超界 ");
  272. }
  273. if (measure_info.range_status & Ground_region::Range_status::Range_steering_wheel_nozero != 0)
  274. {
  275. t_error_str.append("车辆前轮角超界 ");
  276. }
  277. t_error.set_error_description(t_error_str);
  278. }
  279. msg.mutable_error_manager()->set_error_code(t_error.get_error_code());
  280. msg.mutable_error_manager()->set_error_level((message::Error_level)t_error.get_error_level());
  281. msg.mutable_error_manager()->set_error_description(t_error.get_error_description());
  282. return true;
  283. }
  284. //定时发送状态信息
  285. Error_manager System_executor::encapsulate_send_status()
  286. {
  287. static int cloud_count=-1;
  288. cloud_count++;
  289. // if(!g_debug_file.is_open())
  290. // {
  291. // g_debug_file.open("./filter_debug_result.txt", std::ios::app);
  292. // }
  293. Error_manager t_error;
  294. //创建一条状态消息
  295. message::Ground_status_msg t_ground_status_msg;
  296. t_ground_status_msg.mutable_base_info()->set_msg_type(message::Message_type::eGround_status_msg);
  297. t_ground_status_msg.mutable_base_info()->set_timeout_ms(5000);
  298. t_ground_status_msg.mutable_base_info()->set_sender(message::Communicator::eGround_measurer);
  299. t_ground_status_msg.mutable_base_info()->set_receiver(message::Communicator::eEmpty);
  300. // t_ground_status_msg.set_terminal_id(m_terminal_id);
  301. t_ground_status_msg.mutable_id_struct()->set_terminal_id(m_terminal_id);
  302. // 创建各区域状态消息,
  303. // 注意!!!目前公共消息名字依旧使用wj,不做修改
  304. // manager
  305. #if WJ_VELO == 1
  306. {
  307. Velodyne_manager::Velodyne_manager_status t_velodyne_manager_status = Velodyne_manager::get_instance_references().get_status();
  308. t_ground_status_msg.set_wanji_manager_status((message::Wanji_manager_status)t_velodyne_manager_status);
  309. // lidar
  310. std::map<int, Velodyne_lidar_device *> t_velodyne_lidar_device_map = Velodyne_manager::get_instance_references().get_velodyne_lidar_device_map();
  311. std::map<int, Velodyne_lidar_device::Velodyne_lidar_device_status> t_velodyne_lidar_status_map;
  312. for (auto iter = t_velodyne_lidar_device_map.begin(); iter != t_velodyne_lidar_device_map.end(); ++iter)
  313. {
  314. t_velodyne_lidar_status_map.emplace(std::pair<int, Velodyne_lidar_device::Velodyne_lidar_device_status>(iter->second->get_lidar_id(), iter->second->get_status()));
  315. }
  316. // region
  317. std::map<int, Ground_region *> t_ground_region_map = Velodyne_manager::get_instance_references().get_ground_region_map();
  318. int region_index = 0;
  319. for (auto iter = t_ground_region_map.begin(); iter != t_ground_region_map.end(); ++iter)
  320. {
  321. // 以t_ground_status_msg为模板创建各区域心跳消息
  322. message::Ground_status_msg t_multi_status_msg;
  323. t_multi_status_msg.CopyFrom(t_ground_status_msg);
  324. t_multi_status_msg.mutable_id_struct()->set_terminal_id(iter->second->get_terminal_id());
  325. t_multi_status_msg.set_region_worker_status((message::Region_worker_status)(iter->second->get_status()));
  326. velodyne::Region t_param = iter->second->get_param();
  327. for (size_t j = 0; j < t_param.lidar_exts_size(); j++)
  328. {
  329. std::map<int, Velodyne_lidar_device::Velodyne_lidar_device_status>::iterator t_status_iter = t_velodyne_lidar_status_map.find(t_param.lidar_exts(j).lidar_id());
  330. if (t_status_iter == t_velodyne_lidar_status_map.end())
  331. {
  332. LOG(WARNING) << "lidar status " << t_param.lidar_exts(j).lidar_id() << " cannot be found, param error";
  333. }
  334. else
  335. {
  336. t_multi_status_msg.add_wanji_lidar_device_status((message::Wanji_lidar_device_status)t_status_iter->second);
  337. }
  338. }
  339. //velodyne雷达的自动定位信息
  340. Common_data::Car_wheel_information t_car_wheel_information;
  341. t_error = (*iter).second->get_last_wheel_information(&t_car_wheel_information, std::chrono::system_clock::now());
  342. // 获取区域点云填入信息
  343. pcl::PointCloud<pcl::PointXYZ>::Ptr t_region_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  344. iter->second->get_region_cloud(t_region_cloud, Ground_region::Region_cloud_type::filtered);
  345. if (cloud_count == 5)
  346. {
  347. std::string t_filename = std::string("region_") + std::to_string(iter->first) + "_cloud.txt";
  348. save_cloud_txt(t_region_cloud, t_filename);
  349. LOG(INFO) << "region " << iter->first << " cloud has been saved in " + t_filename;
  350. }
  351. // for (size_t j = 0; j < t_region_cloud->size(); j++)
  352. // {
  353. // message::Cloud_coordinate *tp_cloud = t_multi_status_msg.add_cloud();
  354. // tp_cloud->set_x(t_region_cloud->points[j].x);
  355. // tp_cloud->set_y(t_region_cloud->points[j].y);
  356. // tp_cloud->set_z(t_region_cloud->points[j].z);
  357. // }
  358. update_measure_info(t_multi_status_msg, t_car_wheel_information, t_region_cloud->size());
  359. std::string t_msg = t_multi_status_msg.SerializeAsString();
  360. System_communication::get_instance_references().encapsulate_msg(t_msg);
  361. if (t_multi_status_msg.id_struct().terminal_id() == DISP_TERM_ID)
  362. std::cout << t_multi_status_msg.DebugString() << std::endl
  363. << std::endl;
  364. }
  365. }
  366. #elif WJ_VELO == 0
  367. {
  368. // wj_support 20220718
  369. Wanji_manager::Wanji_manager_status t_wj_manager_status = Wanji_manager::get_instance_references().get_status();
  370. t_ground_status_msg.set_wanji_manager_status((message::Wanji_manager_status)t_wj_manager_status);
  371. // lidar
  372. std::map<int, Wanji_lidar_device *> t_wj_lidar_device_map = Wanji_manager::get_instance_references().get_wanji_lidar_device_map();
  373. std::map<int, Wanji_lidar_device::Wanji_lidar_device_status> t_wj_lidar_status_map;
  374. for (auto iter = t_wj_lidar_device_map.begin(); iter != t_wj_lidar_device_map.end(); ++iter)
  375. {
  376. t_wj_lidar_status_map.emplace(std::pair<int, Wanji_lidar_device::Wanji_lidar_device_status>(iter->second->get_lidar_id(), iter->second->get_status()));
  377. }
  378. // region
  379. std::map<int, Region_worker *> t_region_worker_map = Wanji_manager::get_instance_references().get_region_worker_map();
  380. int region_index = 0;
  381. for (auto iter = t_region_worker_map.begin(); iter != t_region_worker_map.end(); ++iter)
  382. {
  383. // 以t_ground_status_msg为模板创建各区域心跳消息
  384. message::Ground_status_msg t_multi_status_msg;
  385. t_multi_status_msg.CopyFrom(t_ground_status_msg);
  386. t_multi_status_msg.mutable_id_struct()->set_terminal_id(iter->second->get_terminal_id());
  387. t_multi_status_msg.set_region_worker_status((message::Region_worker_status)(iter->second->get_status()));
  388. wj::Region t_param = iter->second->get_param();
  389. for (size_t j = 0; j < t_param.lidar_exts_size(); j++)
  390. {
  391. std::map<int, Wanji_lidar_device::Wanji_lidar_device_status>::iterator t_status_iter = t_wj_lidar_status_map.find(t_param.lidar_exts(j).lidar_id());
  392. if (t_status_iter == t_wj_lidar_status_map.end())
  393. {
  394. LOG(WARNING) << "lidar status " << t_param.lidar_exts(j).lidar_id() << " cannot be found, param error";
  395. }
  396. else
  397. {
  398. t_multi_status_msg.add_wanji_lidar_device_status((message::Wanji_lidar_device_status)t_status_iter->second);
  399. }
  400. }
  401. //velodyne雷达的自动定位信息
  402. Common_data::Car_wheel_information t_car_wheel_information;
  403. t_error = (*iter).second->get_last_wheel_information(&t_car_wheel_information, std::chrono::system_clock::now());
  404. // 获取区域点云填入信息
  405. pcl::PointCloud<pcl::PointXYZ>::Ptr t_region_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  406. iter->second->get_region_cloud(t_region_cloud);
  407. if (cloud_count == 5)
  408. {
  409. std::string t_filename = std::string("region_") + std::to_string(iter->first) + "_cloud.txt";
  410. save_cloud_txt(t_region_cloud, t_filename);
  411. LOG(INFO) << "region " << iter->first << " cloud has been saved in " + t_filename;
  412. }
  413. // for (size_t j = 0; j < t_region_cloud->size(); j++)
  414. // {
  415. // message::Cloud_coordinate *tp_cloud = t_multi_status_msg.add_cloud();
  416. // tp_cloud->set_x(t_region_cloud->points[j].x);
  417. // tp_cloud->set_y(t_region_cloud->points[j].y);
  418. // tp_cloud->set_z(t_region_cloud->points[j].z);
  419. // }
  420. update_measure_info(t_multi_status_msg, t_car_wheel_information, t_region_cloud->size());
  421. std::string t_msg = t_multi_status_msg.SerializeAsString();
  422. System_communication::get_instance_references().encapsulate_msg(t_msg);
  423. if (t_multi_status_msg.id_struct().terminal_id() == DISP_TERM_ID)
  424. LOG(INFO) << t_multi_status_msg.DebugString();
  425. }
  426. }
  427. // std::cout << " huli test :::: " << " t_ground_status_msg.DebugString() = " << std::endl;
  428. // std::cout << t_ground_status_msg.DebugString() << std::endl;
  429. // std::cout << " huli test :::: " << " t_ground_status_msg.DebugString() = " << t_ground_status_msg.DebugString() << std::endl;
  430. #else
  431. {
  432. // mix vlp16 and wj716
  433. // 以多线雷达为主
  434. Velodyne_manager::Velodyne_manager_status t_velodyne_manager_status = Velodyne_manager::get_instance_references().get_status();
  435. t_ground_status_msg.set_wanji_manager_status((message::Wanji_manager_status)t_velodyne_manager_status);
  436. // vlp16 lidar
  437. std::map<int, Velodyne_lidar_device *> t_velodyne_lidar_device_map = Velodyne_manager::get_instance_references().get_velodyne_lidar_device_map();
  438. std::map<int, Velodyne_lidar_device::Velodyne_lidar_device_status> t_velodyne_lidar_status_map;
  439. for (auto iter = t_velodyne_lidar_device_map.begin(); iter != t_velodyne_lidar_device_map.end(); ++iter)
  440. {
  441. t_velodyne_lidar_status_map.emplace(std::pair<int, Velodyne_lidar_device::Velodyne_lidar_device_status>(iter->second->get_lidar_id(), iter->second->get_status()));
  442. }
  443. // wj lidar
  444. std::map<int, Wanji_lidar_device *> t_wj_lidar_device_map = Wanji_manager::get_instance_references().get_wanji_lidar_device_map();
  445. std::map<int, Wanji_lidar_device::Wanji_lidar_device_status> t_wj_lidar_status_map;
  446. for (auto iter = t_wj_lidar_device_map.begin(); iter != t_wj_lidar_device_map.end(); ++iter)
  447. {
  448. t_wj_lidar_status_map.emplace(std::pair<int, Wanji_lidar_device::Wanji_lidar_device_status>(iter->second->get_lidar_id(), iter->second->get_status()));
  449. }
  450. // wj region
  451. std::map<int, Region_worker *> t_region_worker_map = Wanji_manager::get_instance_references().get_region_worker_map();
  452. // vlp16 region
  453. std::map<int, Ground_region *> t_ground_region_map = Velodyne_manager::get_instance_references().get_ground_region_map();
  454. int region_index = 0;
  455. for (auto iter = t_ground_region_map.begin(); iter != t_ground_region_map.end(); ++iter)
  456. {
  457. // 以t_ground_status_msg为模板创建各区域心跳消息
  458. message::Ground_status_msg t_multi_status_msg;
  459. t_multi_status_msg.CopyFrom(t_ground_status_msg);
  460. t_multi_status_msg.mutable_id_struct()->set_terminal_id(iter->second->get_terminal_id());
  461. t_multi_status_msg.set_region_worker_status((message::Region_worker_status)(iter->second->get_status()));
  462. // 查找多线区域内对应多线激光雷达
  463. velodyne::Region t_param = iter->second->get_param();
  464. for (size_t j = 0; j < t_param.lidar_exts_size(); j++)
  465. {
  466. std::map<int, Velodyne_lidar_device::Velodyne_lidar_device_status>::iterator t_status_iter = t_velodyne_lidar_status_map.find(t_param.lidar_exts(j).lidar_id());
  467. if (t_status_iter == t_velodyne_lidar_status_map.end())
  468. {
  469. LOG(WARNING) << "vlp16 lidar status " << t_param.lidar_exts(j).lidar_id() << " cannot be found, param error";
  470. }
  471. else
  472. {
  473. t_multi_status_msg.add_wanji_lidar_device_status((message::Wanji_lidar_device_status)t_status_iter->second);
  474. }
  475. }
  476. //velodyne雷达的自动定位信息
  477. Common_data::Car_wheel_information t_car_wheel_information;
  478. t_error = (*iter).second->get_last_wheel_information(&t_car_wheel_information, std::chrono::system_clock::now());
  479. // 获取区域点云填入信息
  480. pcl::PointCloud<pcl::PointXYZ>::Ptr t_region_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  481. iter->second->get_region_cloud(t_region_cloud, Ground_region::Region_cloud_type::filtered);
  482. if (cloud_count == 5)
  483. {
  484. std::string t_filename = std::string("vlp16_region_") + std::to_string(iter->first) + "_cloud.txt";
  485. save_cloud_txt(t_region_cloud, t_filename);
  486. LOG(INFO) << "vlp16 region " << iter->first << " cloud has been saved in " + t_filename;
  487. }
  488. // for (size_t j = 0; j < t_region_cloud->size(); j++)
  489. // {
  490. // message::Cloud_coordinate *tp_cloud = t_multi_status_msg.add_cloud();
  491. // tp_cloud->set_x(t_region_cloud->points[j].x);
  492. // tp_cloud->set_y(t_region_cloud->points[j].y);
  493. // tp_cloud->set_z(t_region_cloud->points[j].z);
  494. // }
  495. // 检查vlp16区域与wj区域对应关系,wj存在对应区域则填充设备状态,并融合测量结果
  496. auto t_wj_region_iter = t_region_worker_map.find(iter->first);
  497. if(t_wj_region_iter != t_region_worker_map.end())
  498. {
  499. wj::Region t_param = t_wj_region_iter->second->get_param();
  500. //
  501. for (size_t j = 0; j < t_param.lidar_exts_size(); j++)
  502. {
  503. std::map<int, Wanji_lidar_device::Wanji_lidar_device_status>::iterator t_status_iter = t_wj_lidar_status_map.find(t_param.lidar_exts(j).lidar_id());
  504. if (t_status_iter == t_wj_lidar_status_map.end())
  505. {
  506. LOG(WARNING) << "wj lidar status " << t_param.lidar_exts(j).lidar_id() << " cannot be found, param error";
  507. }
  508. else
  509. {
  510. t_multi_status_msg.add_wanji_lidar_device_status((message::Wanji_lidar_device_status)t_status_iter->second);
  511. }
  512. }
  513. //wj雷达的自动定位信息
  514. Common_data::Car_wheel_information t_wj_car_wheel_information;
  515. t_error = t_wj_region_iter->second->get_last_wheel_information(&t_wj_car_wheel_information, std::chrono::system_clock::now());
  516. // 获取区域点云填入信息
  517. pcl::PointCloud<pcl::PointXYZ>::Ptr t_wj_region_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  518. t_wj_region_iter->second->get_region_cloud(t_wj_region_cloud);
  519. if (cloud_count == 5)
  520. {
  521. std::string t_filename = std::string("wj_region_") + std::to_string(t_wj_region_iter->first) + "_cloud.txt";
  522. save_cloud_txt(t_wj_region_cloud, t_filename);
  523. LOG(INFO) << "wj region " << t_wj_region_iter->first << " cloud has been saved in " + t_filename;
  524. }
  525. // for (size_t j = 0; j < t_wj_region_cloud->size(); j++)
  526. // {
  527. // message::Cloud_coordinate *tp_cloud = t_multi_status_msg.add_cloud();
  528. // tp_cloud->set_x(t_wj_region_cloud->points[j].x);
  529. // tp_cloud->set_y(t_wj_region_cloud->points[j].y);
  530. // tp_cloud->set_z(t_wj_region_cloud->points[j].z);
  531. // }
  532. // 融合测量结果,验证中心点差异x<0.03, y<0.03, 角度差异ang<0.6, 轴距差异wb<0.055
  533. double dx = t_car_wheel_information.car_center_x - t_wj_car_wheel_information.car_center_x;
  534. double dy = t_car_wheel_information.car_center_y - t_wj_car_wheel_information.car_center_y;
  535. double dang = t_car_wheel_information.car_angle - t_wj_car_wheel_information.car_angle;
  536. double dwb = t_car_wheel_information.car_wheel_base - t_wj_car_wheel_information.car_wheel_base;
  537. if(fabs(dx) < 0.03 && fabs(dy) < 0.03 && fabs(dang) < 0.6 && fabs(dwb) < 0.055)
  538. {
  539. t_car_wheel_information.car_wheel_base = t_car_wheel_information.car_wheel_base*0.2 + t_car_wheel_information.car_wheel_base*0.8;
  540. }else
  541. {
  542. LOG_IF(WARNING, iter->second->get_terminal_id() == DISP_TERM_ID)<<
  543. "detect mismatch, region "<<iter->first<<", dx dy dang dwb: "<<dx<<", "<<dy<<", "<<dang<<", "<< dwb;
  544. }
  545. }else{
  546. LOG_IF(WARNING, iter->second->get_terminal_id() == DISP_TERM_ID)<<"region mismatch, vlp16 "<<iter->first<<", wj doesn't have corresponding region id";
  547. }
  548. update_measure_info(t_multi_status_msg, t_car_wheel_information, t_region_cloud->size());
  549. std::string t_msg = t_multi_status_msg.SerializeAsString();
  550. System_communication::get_instance_references().encapsulate_msg(t_msg);
  551. if (t_multi_status_msg.id_struct().terminal_id() == DISP_TERM_ID)
  552. std::cout << t_multi_status_msg.DebugString() << std::endl
  553. << std::endl;
  554. }
  555. }
  556. #endif
  557. return Error_code::SUCCESS;
  558. }
  559. //判断是否为待机,如果已经准备好,则可以执行任务。
  560. bool System_executor::is_ready()
  561. {
  562. if (m_system_executor_status == SYSTEM_EXECUTOR_READY && m_thread_pool.thread_is_full_load() == false)
  563. {
  564. return true;
  565. }
  566. else
  567. {
  568. return false;
  569. }
  570. }
  571. System_executor::System_executor_status System_executor::get_system_executor_status()
  572. {
  573. return m_system_executor_status;
  574. }
  575. int System_executor::get_terminal_id()
  576. {
  577. return m_terminal_id;
  578. }
  579. //雷达感测定位 的处理函数
  580. //input::command_id, 消息指令id, 由主控制系统生成的唯一码
  581. //input::command_id, 终端id, 对应具体的某个车位
  582. //return::void, 没有返回, 执行结果直接生成一条答复消息, 然后通过通信返回
  583. void System_executor::execute_for_measure(std::string command_info, int terminal_id, std::chrono::system_clock::time_point receive_time)
  584. {
  585. Error_manager t_error;
  586. Error_manager t_result;
  587. LOG(INFO) << " System_executor::execute_for_measure run " << this;
  588. //第1步, 按照时间生成中间文件的保存路径
  589. time_t nowTime;
  590. nowTime = time(NULL);
  591. struct tm *sysTime = localtime(&nowTime);
  592. char t_save_path[256] = {0};
  593. sprintf(t_save_path, "../data/%04d%02d%02d_%02d%02d%02d",
  594. sysTime->tm_year + 1900, sysTime->tm_mon + 1, sysTime->tm_mday, sysTime->tm_hour, sysTime->tm_min, sysTime->tm_sec);
  595. //第2步, 创建万集管理模块的任务单, 并发送到 wanji_manager
  596. // Wanji_manager_task t_wanji_manager_task ;
  597. // Common_data::Car_wheel_information t_car_information_by_wanji;
  598. // t_wanji_manager_task.task_init(TASK_CREATED,"",NULL,std::chrono::milliseconds(3000),
  599. // terminal_id, receive_time);
  600. // t_error = Task_command_manager::get_instance_references().execute_task(&t_wanji_manager_task);
  601. // 或者创建velodyne管理模块任务单,并发送到velodyne_manager
  602. Velodyne_manager_task t_velodyne_manager_task;
  603. Common_data::Car_wheel_information t_car_information_by_velodyne;
  604. t_velodyne_manager_task.task_init(TASK_CREATED, "", NULL, std::chrono::milliseconds(3000),
  605. terminal_id, receive_time);
  606. t_error = Task_command_manager::get_instance_references().execute_task(&t_velodyne_manager_task);
  607. //第3步, 等待任务单完成
  608. if (t_error != Error_code::SUCCESS)
  609. {
  610. LOG(INFO) << " Velodyne_manager/Velodyne_manager execute_task error " << this;
  611. }
  612. else
  613. {
  614. // //判断任务是否结束, 阻塞 等待, 直到任务完成或者超时
  615. // while ( t_wanji_manager_task.is_task_end() == false)
  616. // {
  617. // if ( t_wanji_manager_task.is_over_time() )
  618. // {
  619. // //超时处理。取消任务。
  620. // Wanji_manager::get_instance_pointer()->cancel_task(&t_wanji_manager_task);
  621. // t_error.error_manager_reset(Error_code::WJ_MANAGER_TASK_OVER_TIME, Error_level::MINOR_ERROR,
  622. // " t_wanjestaui_manager_task is_over_time ");
  623. // t_wanji_manager_task.set_task_error_manager(t_error);
  624. // }
  625. // else
  626. // {
  627. // //继续等待
  628. // std::this_thread::sleep_for(std::chrono::microseconds(1));
  629. // std::this_thread::yield();
  630. // }
  631. // }
  632. // //提取任务单 的错误码
  633. // t_error = t_wanji_manager_task.get_task_error_manager();
  634. // if ( t_error == Error_code::SUCCESS )
  635. // {
  636. // t_car_information_by_wanji = t_wanji_manager_task.get_car_wheel_information();
  637. // }
  638. // else
  639. // {
  640. // LOG(INFO) << " wanji_manager_task error :::::::" << t_wanji_manager_task.get_task_error_manager().to_string() << this;
  641. // }
  642. // ------------------- 切换为velodyne ------------------
  643. //判断任务是否结束, 阻塞 等待, 直到任务完成或者超时
  644. while (t_velodyne_manager_task.is_task_end() == false)
  645. {
  646. if (t_velodyne_manager_task.is_over_time())
  647. {
  648. //超时处理。取消任务。
  649. Velodyne_manager::get_instance_pointer()->cancel_task(&t_velodyne_manager_task);
  650. t_error.error_manager_reset(Error_code::VELODYNE_MANAGER_TASK_OVER_TIME, Error_level::MINOR_ERROR,
  651. " t_velodyne_manager_task is_over_time ");
  652. t_velodyne_manager_task.set_task_error_manager(t_error);
  653. }
  654. else
  655. {
  656. //继续等待
  657. std::this_thread::sleep_for(std::chrono::microseconds(1));
  658. std::this_thread::yield();
  659. }
  660. }
  661. //提取任务单 的错误码
  662. t_error = t_velodyne_manager_task.get_task_error_manager();
  663. if (t_error == Error_code::SUCCESS)
  664. {
  665. t_car_information_by_velodyne = t_velodyne_manager_task.get_car_wheel_information();
  666. }
  667. else
  668. {
  669. LOG(INFO) << " velodyne_manager_task error :::::::" << t_velodyne_manager_task.get_task_error_manager().to_string() << this;
  670. }
  671. }
  672. t_result.compare_and_cover_error(t_error);
  673. //measure 测量模块的最终结果
  674. Common_data::Car_measure_information t_car_information_result;
  675. //第4步, 生成反馈消息
  676. // if(t_car_information_by_wanji.correctness == true )
  677. // {
  678. // t_car_information_result.center_x = t_car_information_by_wanji.center_x;
  679. // t_car_information_result.center_y = t_car_information_by_wanji.center_y;
  680. // t_car_information_result.car_angle = t_car_information_by_wanji.car_angle;
  681. // t_car_information_result.wheel_base = t_car_information_by_wanji.wheel_base;
  682. // t_car_information_result.wheel_width = t_car_information_by_wanji.wheel_width;
  683. // t_car_information_result.correctness = true;
  684. // }else{
  685. // t_result.set_error_level_down(NEGLIGIBLE_ERROR);
  686. // }
  687. // ------------------- 切换为velodyne ------------------
  688. if (t_car_information_by_velodyne.correctness == true)
  689. {
  690. t_car_information_result.car_center_x = t_car_information_by_velodyne.car_center_x;
  691. t_car_information_result.car_center_y = t_car_information_by_velodyne.car_center_y;
  692. t_car_information_result.car_angle = t_car_information_by_velodyne.car_angle;
  693. t_car_information_result.car_wheel_base = t_car_information_by_velodyne.car_wheel_base;
  694. t_car_information_result.car_wheel_width = t_car_information_by_velodyne.car_wheel_width;
  695. t_car_information_result.correctness = true;
  696. }
  697. else
  698. {
  699. t_result.set_error_level_down(NEGLIGIBLE_ERROR);
  700. }
  701. //第七步, 创建一条答复消息
  702. message::Ground_detect_response_msg t_ground_detect_response_msg;
  703. t_ground_detect_response_msg.mutable_base_info()->set_msg_type(message::Message_type::eGround_detect_response_msg);
  704. t_ground_detect_response_msg.mutable_base_info()->set_timeout_ms(5000);
  705. t_ground_detect_response_msg.mutable_base_info()->set_sender(message::Communicator::eGround_measurer);
  706. t_ground_detect_response_msg.mutable_base_info()->set_receiver(message::Communicator::eMain);
  707. t_ground_detect_response_msg.set_command_key(command_info);
  708. t_ground_detect_response_msg.mutable_id_struct()->set_terminal_id(terminal_id);
  709. t_ground_detect_response_msg.mutable_error_manager()->set_error_code(t_result.get_error_code());
  710. t_ground_detect_response_msg.mutable_error_manager()->set_error_level((message::Error_level)t_result.get_error_level());
  711. t_ground_detect_response_msg.mutable_error_manager()->set_error_description(t_result.get_error_description());
  712. t_ground_detect_response_msg.mutable_locate_information()->set_locate_x(t_car_information_result.car_center_x);
  713. t_ground_detect_response_msg.mutable_locate_information()->set_locate_y(t_car_information_result.car_center_y);
  714. t_ground_detect_response_msg.mutable_locate_information()->set_locate_angle(t_car_information_result.car_angle);
  715. t_ground_detect_response_msg.mutable_locate_information()->set_locate_length(t_car_information_result.car_length);
  716. t_ground_detect_response_msg.mutable_locate_information()->set_locate_width(t_car_information_result.car_width);
  717. t_ground_detect_response_msg.mutable_locate_information()->set_locate_height(t_car_information_result.car_height);
  718. t_ground_detect_response_msg.mutable_locate_information()->set_locate_wheel_base(t_car_information_result.car_wheel_base);
  719. t_ground_detect_response_msg.mutable_locate_information()->set_locate_wheel_width(t_car_information_result.car_wheel_width);
  720. t_ground_detect_response_msg.mutable_locate_information()->set_locate_front_theta(t_car_information_result.car_front_theta);
  721. t_ground_detect_response_msg.mutable_locate_information()->set_locate_correct(t_car_information_result.correctness);
  722. std::string t_msg = t_ground_detect_response_msg.SerializeAsString();
  723. System_communication::get_instance_references().encapsulate_msg(t_msg);
  724. std::cout << "huli t_measure_response_msg = " << t_ground_detect_response_msg.DebugString() << std::endl;
  725. return;
  726. }