system_executor.cpp 54 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213
  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. PathCreator pc;
  20. pc.Mkdir("./log/");
  21. return Error_code::SUCCESS;
  22. }
  23. //反初始化
  24. Error_manager System_executor::system_executor_uninit()
  25. {
  26. // if(g_debug_file.is_open())
  27. // g_debug_file.close();
  28. m_thread_pool.thread_pool_uninit();
  29. m_system_executor_status = SYSTEM_EXECUTOR_UNKNOW;
  30. return Error_code::SUCCESS;
  31. }
  32. //检查消息是否有效, 主要检查消息类型和接受者, 判断这条消息是不是给我的.
  33. Error_manager System_executor::check_msg(Communication_message* p_msg)
  34. {
  35. if ( p_msg == NULL )
  36. {
  37. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  38. " POINTER IS NULL ");
  39. }
  40. //检查消息类型
  41. switch ( p_msg->get_message_type() )
  42. {
  43. case Communication_message::Message_type::eGround_detect_request_msg:
  44. {
  45. //检查接受人
  46. if ( p_msg->get_receiver() == Communication_message::Communicator::eGround_measurer)
  47. {
  48. message::Ground_detect_request_msg t_ground_detect_request_msg;
  49. //针对消息类型, 对消息进行二次解析
  50. if (t_ground_detect_request_msg.ParseFromString(p_msg->get_message_buf()))
  51. {
  52. // //检查终端id
  53. // 普爱不检查终端id
  54. // 楚天检查终端id
  55. // if ( t_ground_detect_request_msg.terminal_id() == m_terminal_id )
  56. // {
  57. return Error_code::SUCCESS;
  58. // }
  59. }
  60. }
  61. break;
  62. }
  63. default :
  64. ;
  65. break;
  66. }
  67. //无效的消息,
  68. return Error_manager(Error_code::INVALID_MESSAGE, Error_level::NEGLIGIBLE_ERROR,
  69. " INVALID_MESSAGE error ");
  70. }
  71. //检查执行者的状态, 判断能否处理这条消息,
  72. Error_manager System_executor::check_executer(Communication_message* p_msg)
  73. {
  74. //huli DDDDDDDDDDDDDDDDDDDDDDDDDDDDDDDD 记得删除
  75. return Error_code::SUCCESS;
  76. if ( p_msg == NULL )
  77. {
  78. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  79. " POINTER IS NULL ");
  80. }
  81. Error_manager t_error;
  82. //通过 p_msg->get_message_type() 和 p_msg->get_receiver() 找到处理模块的实例对象, 查询执行人是否可以处理这条消息
  83. switch ( p_msg->get_message_type() )
  84. {
  85. case Communication_message::Message_type::eGround_detect_request_msg:
  86. {
  87. Error_manager t_executor_result = System_executor::get_instance_references().check_status();
  88. if (t_executor_result == SUCCESS)
  89. {
  90. return Error_code::SUCCESS;
  91. }
  92. else
  93. {
  94. //整合所有的错误码
  95. t_error.compare_and_cover_error(t_executor_result);
  96. if (t_error.get_error_level() == NEGLIGIBLE_ERROR)//一级故障,轻微故障,
  97. {
  98. LOG(INFO) << "executer_is_busy , ";
  99. //返回繁忙之后, 通信模块1秒后再次调用check
  100. return Error_code::COMMUNICATION_EXCUTER_IS_BUSY;
  101. }
  102. else//返回二级故障,可以封装一条答复信息, 返回错误码
  103. {
  104. message::Ground_detect_request_msg t_ground_detect_request_msg;
  105. //针对消息类型, 对消息进行二次解析
  106. if (t_ground_detect_request_msg.ParseFromString(p_msg->get_message_buf()))
  107. {
  108. //创建一条答复消息
  109. message::Ground_detect_response_msg t_ground_detect_response_msg;
  110. t_ground_detect_response_msg.mutable_base_info()->set_msg_type(message::Message_type::eGround_detect_response_msg);
  111. t_ground_detect_response_msg.mutable_base_info()->set_timeout_ms(5000);
  112. t_ground_detect_response_msg.mutable_base_info()->set_sender(message::Communicator::eGround_measurer);
  113. t_ground_detect_response_msg.mutable_base_info()->set_receiver(message::Communicator::eMain);
  114. t_ground_detect_response_msg.set_command_key(t_ground_detect_request_msg.command_key());
  115. t_ground_detect_response_msg.mutable_id_struct()->set_terminal_id(t_ground_detect_request_msg.id_struct().terminal_id());
  116. t_ground_detect_response_msg.mutable_error_manager()->set_error_code(t_error.get_error_code());
  117. t_ground_detect_response_msg.mutable_error_manager()->set_error_level((message::Error_level)t_error.get_error_level());
  118. t_ground_detect_response_msg.mutable_error_manager()->set_error_description(t_error.get_error_description());
  119. std::string t_msg = t_ground_detect_response_msg.SerializeAsString();
  120. System_communication::get_instance_references().encapsulate_msg(t_msg);
  121. LOG(INFO) << " System_executor::check_executer executer status error "<< this;
  122. return t_error;
  123. }
  124. else
  125. {
  126. LOG(INFO) << " System_executor::check_executer second PARSE_ERROR "<< this;
  127. return Error_manager(Error_code::SYSTEM_EXECUTOR_PARSE_ERROR, Error_level::MINOR_ERROR,
  128. " message::Measure_request_msg ParseFromString error ");
  129. }
  130. }
  131. }
  132. break;
  133. }
  134. default :
  135. ;
  136. break;
  137. }
  138. return t_error;
  139. }
  140. //处理消息的执行函数
  141. Error_manager System_executor::execute_msg(Communication_message* p_msg)
  142. {
  143. if ( p_msg == NULL )
  144. {
  145. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  146. " POINTER IS NULL ");
  147. }
  148. // std::cout << " huli test ::333333333333333333333333333333:: " << " p_msg->get_message_type() = " << p_msg->get_message_type() << std::endl;
  149. switch ( p_msg->get_message_type() )
  150. {
  151. case Communication_message::eGround_detect_request_msg:
  152. {
  153. message::Ground_detect_request_msg t_ground_detect_request_msg;
  154. //针对消息类型, 对消息进行二次解析
  155. if (t_ground_detect_request_msg.ParseFromString(p_msg->get_message_buf()) && t_ground_detect_request_msg.id_struct().has_terminal_id())
  156. {
  157. //往线程池添加执行任务, 之后会唤醒一个线程去执行他.
  158. m_thread_pool.enqueue(&System_executor::execute_for_measure, this,
  159. t_ground_detect_request_msg.command_key(), t_ground_detect_request_msg.id_struct().terminal_id(),
  160. p_msg->get_receive_time());
  161. }
  162. else
  163. {
  164. return Error_manager(Error_code::SYSTEM_EXECUTOR_PARSE_ERROR, Error_level::MINOR_ERROR,
  165. " message::Measure_request_msg ParseFromString error ");
  166. }
  167. break;
  168. }
  169. default:
  170. {
  171. }
  172. }
  173. return Error_code::SUCCESS;
  174. }
  175. //检查状态
  176. Error_manager System_executor::check_status()
  177. {
  178. if ( m_system_executor_status == SYSTEM_EXECUTOR_READY )
  179. {
  180. if ( m_thread_pool.thread_is_full_load() == false )
  181. {
  182. return Error_code::SUCCESS;
  183. }
  184. else
  185. {
  186. return Error_manager(Error_code::SYSTEM_EXECUTOR_STATUS_BUSY, Error_level::NEGLIGIBLE_ERROR,
  187. " System_executor::check_status error ");
  188. }
  189. }
  190. else
  191. {
  192. return Error_manager(Error_code::SYSTEM_EXECUTOR_STATUS_ERROR, Error_level::MINOR_ERROR,
  193. " System_executor::check_status error ");
  194. }
  195. }
  196. // 更新消息中关于定位结果与超界信息的内容
  197. bool System_executor::update_measure_info(message::Ground_status_msg &msg, Common_data::Car_wheel_information &measure_info, int cloud_size)
  198. {
  199. Error_manager t_error;
  200. //无论定位结果如何, 都要填充数据, 即使全部写0, 必须保证通信格式正确.
  201. message::Locate_information t_locate_information;
  202. //= t_multi_status_msg.add_locate_information_realtime();
  203. t_locate_information.set_locate_x(measure_info.car_center_x);
  204. t_locate_information.set_locate_y(measure_info.car_center_y);
  205. t_locate_information.set_locate_angle(measure_info.car_angle);
  206. t_locate_information.set_locate_length(0);
  207. t_locate_information.set_locate_width(0);
  208. t_locate_information.set_locate_height(0);
  209. t_locate_information.set_locate_wheel_base(measure_info.car_wheel_base);
  210. t_locate_information.set_locate_wheel_width(measure_info.car_wheel_width);
  211. t_locate_information.set_locate_front_theta(measure_info.car_front_theta);
  212. t_locate_information.set_locate_correct(measure_info.correctness);
  213. t_locate_information.set_uniformed_car_x(measure_info.uniform_car_x);
  214. t_locate_information.set_uniformed_car_y(measure_info.uniform_car_y);
  215. msg.mutable_locate_information_realtime()->CopyFrom(t_locate_information);
  216. // 当前超界提示仅保留一项
  217. // 20211026已修改,分离为电子围栏状态与超界状态,只有测量正确时超界状态才有意义
  218. msg.set_border_status(measure_info.range_status);
  219. if (!measure_info.correctness)
  220. {
  221. if (cloud_size > 0)
  222. msg.set_ground_status(message::Ground_statu::Noise);
  223. else
  224. msg.set_ground_status(message::Ground_statu::Nothing);
  225. }
  226. else if (measure_info.range_status == int(Ground_region::Range_status::Range_correct))
  227. {
  228. msg.set_ground_status(message::Ground_statu::Car_correct);
  229. }
  230. else
  231. {
  232. msg.set_ground_status(message::Ground_statu::Car_border_reached);
  233. // 更新待提示错误信息
  234. std::string t_error_str;
  235. if (measure_info.range_status & Ground_region::Range_status::Range_front != 0)
  236. {
  237. t_error_str.append("前超界 ");
  238. }
  239. if (measure_info.range_status & Ground_region::Range_status::Range_back != 0)
  240. {
  241. t_error_str.append("后超界 ");
  242. }
  243. if (measure_info.range_status & Ground_region::Range_status::Range_left != 0)
  244. {
  245. t_error_str.append("左超界 ");
  246. }
  247. if (measure_info.range_status & Ground_region::Range_status::Range_right != 0)
  248. {
  249. t_error_str.append("右超界 ");
  250. }
  251. if (measure_info.range_status & Ground_region::Range_status::Range_bottom != 0)
  252. {
  253. t_error_str.append("底盘超界 ");
  254. }
  255. if (measure_info.range_status & Ground_region::Range_status::Range_top != 0)
  256. {
  257. t_error_str.append("顶超界 ");
  258. }
  259. if (measure_info.range_status & Ground_region::Range_status::Range_car_width != 0)
  260. {
  261. t_error_str.append("车宽超界 ");
  262. }
  263. if (measure_info.range_status & Ground_region::Range_status::Range_car_wheelbase != 0)
  264. {
  265. t_error_str.append("轴距超界 ");
  266. }
  267. if (measure_info.range_status & Ground_region::Range_status::Range_angle_anti_clock != 0)
  268. {
  269. t_error_str.append("车辆角度左超界 ");
  270. }
  271. if (measure_info.range_status & Ground_region::Range_status::Range_angle_clock != 0)
  272. {
  273. t_error_str.append("车辆角度右超界 ");
  274. }
  275. if (measure_info.range_status & Ground_region::Range_status::Range_steering_wheel_nozero != 0)
  276. {
  277. t_error_str.append("车辆前轮角超界 ");
  278. }
  279. t_error.set_error_description(t_error_str);
  280. }
  281. msg.mutable_error_manager()->set_error_code(t_error.get_error_code());
  282. msg.mutable_error_manager()->set_error_level((message::Error_level)t_error.get_error_level());
  283. msg.mutable_error_manager()->set_error_description(t_error.get_error_description());
  284. return true;
  285. }
  286. // ***************************** rabbitmq *********************************
  287. Error_manager System_executor::encapsulate_send_mq_status()
  288. {
  289. static int cloud_count=-1;
  290. cloud_count++;
  291. // if(!g_debug_file.is_open())
  292. // {
  293. // g_debug_file.open("./filter_debug_result.txt", std::ios::app);
  294. // }
  295. Error_manager t_error;
  296. //创建一条状态消息
  297. message::Ground_status_msg t_ground_status_msg;
  298. t_ground_status_msg.mutable_base_info()->set_msg_type(message::Message_type::eGround_status_msg);
  299. t_ground_status_msg.mutable_base_info()->set_timeout_ms(5000);
  300. t_ground_status_msg.mutable_base_info()->set_sender(message::Communicator::eGround_measurer);
  301. t_ground_status_msg.mutable_base_info()->set_receiver(message::Communicator::eEmpty);
  302. // t_ground_status_msg.set_terminal_id(m_terminal_id);
  303. t_ground_status_msg.mutable_id_struct()->set_terminal_id(m_terminal_id);
  304. // 创建各区域状态消息,
  305. // 注意!!!目前公共消息名字依旧使用wj,不做修改
  306. // manager
  307. #if WJ_VELO == 1
  308. {
  309. Velodyne_manager::Velodyne_manager_status t_velodyne_manager_status = Velodyne_manager::get_instance_references().get_status();
  310. t_ground_status_msg.set_wanji_manager_status((message::Wanji_manager_status)t_velodyne_manager_status);
  311. // lidar
  312. std::map<int, Velodyne_lidar_device *> t_velodyne_lidar_device_map = Velodyne_manager::get_instance_references().get_velodyne_lidar_device_map();
  313. std::map<int, Velodyne_lidar_device::Velodyne_lidar_device_status> t_velodyne_lidar_status_map;
  314. for (auto iter = t_velodyne_lidar_device_map.begin(); iter != t_velodyne_lidar_device_map.end(); ++iter)
  315. {
  316. 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()));
  317. }
  318. // region
  319. std::map<int, Ground_region *> t_ground_region_map = Velodyne_manager::get_instance_references().get_ground_region_map();
  320. int region_index = 0;
  321. for (auto iter = t_ground_region_map.begin(); iter != t_ground_region_map.end(); ++iter)
  322. {
  323. // 以t_ground_status_msg为模板创建各区域心跳消息
  324. message::Ground_status_msg t_multi_status_msg;
  325. t_multi_status_msg.CopyFrom(t_ground_status_msg);
  326. t_multi_status_msg.mutable_id_struct()->set_terminal_id(iter->second->get_terminal_id());
  327. t_multi_status_msg.set_region_worker_status((message::Region_worker_status)(iter->second->get_status()));
  328. velodyne::Region t_param = iter->second->get_param();
  329. for (size_t j = 0; j < t_param.lidar_exts_size(); j++)
  330. {
  331. 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());
  332. if (t_status_iter == t_velodyne_lidar_status_map.end())
  333. {
  334. LOG(WARNING) << "lidar status " << t_param.lidar_exts(j).lidar_id() << " cannot be found, param error";
  335. }
  336. else
  337. {
  338. t_multi_status_msg.add_wanji_lidar_device_status((message::Wanji_lidar_device_status)t_status_iter->second);
  339. }
  340. }
  341. //velodyne雷达的自动定位信息
  342. Common_data::Car_wheel_information t_car_wheel_information;
  343. t_error = (*iter).second->get_last_wheel_information(&t_car_wheel_information, std::chrono::system_clock::now());
  344. // 获取区域点云填入信息
  345. pcl::PointCloud<pcl::PointXYZ>::Ptr t_region_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  346. iter->second->get_region_cloud(t_region_cloud, Ground_region::Region_cloud_type::filtered);
  347. if (cloud_count == 5)
  348. {
  349. std::string t_filename = std::string("region_") + std::to_string(iter->first) + "_cloud.txt";
  350. save_cloud_txt(t_region_cloud, t_filename);
  351. LOG(INFO) << "region " << iter->first << " cloud has been saved in " + t_filename;
  352. }
  353. // for (size_t j = 0; j < t_region_cloud->size(); j++)
  354. // {
  355. // message::Cloud_coordinate *tp_cloud = t_multi_status_msg.add_cloud();
  356. // tp_cloud->set_x(t_region_cloud->points[j].x);
  357. // tp_cloud->set_y(t_region_cloud->points[j].y);
  358. // tp_cloud->set_z(t_region_cloud->points[j].z);
  359. // }
  360. update_measure_info(t_multi_status_msg, t_car_wheel_information, t_region_cloud->size());
  361. std::string t_msg = t_multi_status_msg.SerializeAsString();
  362. System_communication::get_instance_references().encapsulate_msg(t_msg);
  363. if (t_multi_status_msg.id_struct().terminal_id() == DISP_TERM_ID)
  364. std::cout << t_multi_status_msg.DebugString() << std::endl
  365. << std::endl;
  366. }
  367. }
  368. #elif WJ_VELO == 0
  369. {
  370. // wj_support 20220718
  371. Wanji_manager::Wanji_manager_status t_wj_manager_status = Wanji_manager::get_instance_references().get_status();
  372. t_ground_status_msg.set_wanji_manager_status((message::Wanji_manager_status)t_wj_manager_status);
  373. // lidar
  374. std::map<int, Wanji_lidar_device *> t_wj_lidar_device_map = Wanji_manager::get_instance_references().get_wanji_lidar_device_map();
  375. std::map<int, Wanji_lidar_device::Wanji_lidar_device_status> t_wj_lidar_status_map;
  376. for (auto iter = t_wj_lidar_device_map.begin(); iter != t_wj_lidar_device_map.end(); ++iter)
  377. {
  378. 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()));
  379. }
  380. // region
  381. std::map<int, Region_worker *> t_region_worker_map = Wanji_manager::get_instance_references().get_region_worker_map();
  382. int region_index = 0;
  383. for (auto iter = t_region_worker_map.begin(); iter != t_region_worker_map.end(); ++iter)
  384. {
  385. // 以t_ground_status_msg为模板创建各区域心跳消息
  386. message::Ground_status_msg t_multi_status_msg;
  387. t_multi_status_msg.CopyFrom(t_ground_status_msg);
  388. t_multi_status_msg.mutable_id_struct()->set_terminal_id(iter->second->get_terminal_id());
  389. t_multi_status_msg.set_region_worker_status((message::Region_worker_status)(iter->second->get_status()));
  390. wj::Region t_param = iter->second->get_param();
  391. for (size_t j = 0; j < t_param.lidar_exts_size(); j++)
  392. {
  393. 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());
  394. if (t_status_iter == t_wj_lidar_status_map.end())
  395. {
  396. LOG(WARNING) << "lidar status " << t_param.lidar_exts(j).lidar_id() << " cannot be found, param error";
  397. }
  398. else
  399. {
  400. t_multi_status_msg.add_wanji_lidar_device_status((message::Wanji_lidar_device_status)t_status_iter->second);
  401. }
  402. }
  403. //velodyne雷达的自动定位信息
  404. Common_data::Car_wheel_information t_car_wheel_information;
  405. t_error = (*iter).second->get_last_wheel_information(&t_car_wheel_information, std::chrono::system_clock::now());
  406. // 获取区域点云填入信息
  407. pcl::PointCloud<pcl::PointXYZ>::Ptr t_region_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  408. iter->second->get_region_cloud(t_region_cloud);
  409. if (cloud_count == 5)
  410. {
  411. std::string t_filename = std::string("region_") + std::to_string(iter->first) + "_cloud.txt";
  412. save_cloud_txt(t_region_cloud, t_filename);
  413. LOG(INFO) << "region " << iter->first << " cloud has been saved in " + t_filename;
  414. }
  415. // for (size_t j = 0; j < t_region_cloud->size(); j++)
  416. // {
  417. // message::Cloud_coordinate *tp_cloud = t_multi_status_msg.add_cloud();
  418. // tp_cloud->set_x(t_region_cloud->points[j].x);
  419. // tp_cloud->set_y(t_region_cloud->points[j].y);
  420. // tp_cloud->set_z(t_region_cloud->points[j].z);
  421. // }
  422. update_measure_info(t_multi_status_msg, t_car_wheel_information, t_region_cloud->size());
  423. std::string t_msg = t_multi_status_msg.SerializeAsString();
  424. System_communication::get_instance_references().encapsulate_msg(t_msg);
  425. if (t_multi_status_msg.id_struct().terminal_id() == DISP_TERM_ID)
  426. LOG(INFO) << t_multi_status_msg.DebugString();
  427. }
  428. }
  429. // std::cout << " huli test :::: " << " t_ground_status_msg.DebugString() = " << std::endl;
  430. // std::cout << t_ground_status_msg.DebugString() << std::endl;
  431. // std::cout << " huli test :::: " << " t_ground_status_msg.DebugString() = " << t_ground_status_msg.DebugString() << std::endl;
  432. #else
  433. {
  434. // mix vlp16 and wj716
  435. // 以多线雷达为主
  436. Velodyne_manager::Velodyne_manager_status t_velodyne_manager_status = Velodyne_manager::get_instance_references().get_status();
  437. t_ground_status_msg.set_wanji_manager_status((message::Wanji_manager_status)t_velodyne_manager_status);
  438. // vlp16 lidar
  439. std::map<int, Velodyne_lidar_device *> t_velodyne_lidar_device_map = Velodyne_manager::get_instance_references().get_velodyne_lidar_device_map();
  440. std::map<int, Velodyne_lidar_device::Velodyne_lidar_device_status> t_velodyne_lidar_status_map;
  441. for (auto iter = t_velodyne_lidar_device_map.begin(); iter != t_velodyne_lidar_device_map.end(); ++iter)
  442. {
  443. 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()));
  444. }
  445. // wj lidar
  446. #if LIDAR_TYPE == 1
  447. std::map<int, Wanji_lidar_device *> t_wj_lidar_device_map = Wanji_manager::get_instance_references().get_wanji_lidar_device_map();
  448. std::map<int, Wanji_lidar_device::Wanji_lidar_device_status> t_wj_lidar_status_map;
  449. for (auto iter = t_wj_lidar_device_map.begin(); iter != t_wj_lidar_device_map.end(); ++iter)
  450. {
  451. 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()));
  452. }
  453. #else
  454. std::map<int, Wanji_716N_lidar_device *> t_wj_lidar_device_map = Wanji_manager::get_instance_references().get_wanji_lidar_device_map();
  455. std::map<int, Wanji_716N_lidar_device::Wanji_716N_device_status> t_wj_lidar_status_map;
  456. for (auto iter = t_wj_lidar_device_map.begin(); iter != t_wj_lidar_device_map.end(); ++iter)
  457. {
  458. t_wj_lidar_status_map.emplace(std::pair<int, Wanji_716N_lidar_device::Wanji_716N_device_status>(iter->second->get_lidar_id(), iter->second->get_status()));
  459. }
  460. #endif
  461. // wj region
  462. std::map<int, Region_worker *> t_region_worker_map = Wanji_manager::get_instance_references().get_region_worker_map();
  463. // vlp16 region
  464. std::map<int, Ground_region *> t_ground_region_map = Velodyne_manager::get_instance_references().get_ground_region_map();
  465. int region_index = 0;
  466. for (auto iter = t_ground_region_map.begin(); iter != t_ground_region_map.end(); ++iter)
  467. {
  468. // 以t_ground_status_msg为模板创建各区域心跳消息
  469. message::Ground_status_msg t_multi_status_msg;
  470. t_multi_status_msg.CopyFrom(t_ground_status_msg);
  471. t_multi_status_msg.mutable_id_struct()->set_terminal_id(iter->second->get_terminal_id());
  472. t_multi_status_msg.set_region_worker_status((message::Region_worker_status)(iter->second->get_status()));
  473. // 查找多线区域内对应多线激光雷达
  474. velodyne::Region t_param = iter->second->get_param();
  475. for (size_t j = 0; j < t_param.lidar_exts_size(); j++)
  476. {
  477. 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());
  478. if (t_status_iter == t_velodyne_lidar_status_map.end())
  479. {
  480. LOG(WARNING) << "vlp16 lidar status " << t_param.lidar_exts(j).lidar_id() << " cannot be found, param error";
  481. }
  482. else
  483. {
  484. t_multi_status_msg.add_wanji_lidar_device_status((message::Wanji_lidar_device_status)t_status_iter->second);
  485. }
  486. }
  487. //velodyne雷达的自动定位信息
  488. Common_data::Car_wheel_information t_car_wheel_information;
  489. t_error = (*iter).second->get_last_wheel_information(&t_car_wheel_information, std::chrono::system_clock::now());
  490. // 获取区域点云填入信息
  491. pcl::PointCloud<pcl::PointXYZ>::Ptr t_region_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  492. iter->second->get_region_cloud(t_region_cloud, Ground_region::Region_cloud_type::filtered);
  493. if (cloud_count == 10)
  494. {
  495. std::string t_filename = std::string("vlp16_region_") + std::to_string(iter->first) + "_cloud.txt";
  496. save_cloud_txt(t_region_cloud, t_filename);
  497. LOG(INFO) << " vlp16 region " << iter->first << " cloud has been saved in " + t_filename;
  498. }
  499. // for (size_t j = 0; j < t_region_cloud->size(); j++)
  500. // {
  501. // message::Cloud_coordinate *tp_cloud = t_multi_status_msg.add_cloud();
  502. // tp_cloud->set_x(t_region_cloud->points[j].x);
  503. // tp_cloud->set_y(t_region_cloud->points[j].y);
  504. // tp_cloud->set_z(t_region_cloud->points[j].z);
  505. // }
  506. // 检查vlp16区域与wj区域对应关系,wj存在对应区域则填充设备状态,并融合测量结果
  507. auto t_wj_region_iter = t_region_worker_map.find(iter->first);
  508. if(t_wj_region_iter != t_region_worker_map.end())
  509. {
  510. wj::Region t_param = t_wj_region_iter->second->get_param();
  511. //
  512. for (size_t j = 0; j < t_param.lidar_exts_size(); j++)
  513. {
  514. #if LIDAR_TYPE == 1
  515. 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());
  516. #else
  517. std::map<int, Wanji_716N_lidar_device::Wanji_716N_device_status>::iterator t_status_iter = t_wj_lidar_status_map.find(t_param.lidar_exts(j).lidar_id());
  518. #endif
  519. if (t_status_iter == t_wj_lidar_status_map.end())
  520. {
  521. LOG(WARNING) << "wj lidar status " << t_param.lidar_exts(j).lidar_id() << " cannot be found, param error";
  522. }
  523. else
  524. {
  525. t_multi_status_msg.add_wanji_lidar_device_status((message::Wanji_lidar_device_status)t_status_iter->second);
  526. }
  527. }
  528. //wj雷达的自动定位信息
  529. Common_data::Car_wheel_information t_wj_car_wheel_information;
  530. t_error = t_wj_region_iter->second->get_last_wheel_information(&t_wj_car_wheel_information, std::chrono::system_clock::now());
  531. // 获取区域点云填入信息
  532. pcl::PointCloud<pcl::PointXYZ>::Ptr t_wj_region_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  533. t_wj_region_iter->second->get_region_cloud(t_wj_region_cloud);
  534. if (cloud_count == 8)
  535. {
  536. std::string t_filename = std::string("wj_region_") + std::to_string(t_wj_region_iter->first) + "_cloud.txt";
  537. save_cloud_txt(t_wj_region_cloud, t_filename);
  538. LOG(INFO) << "wj region " << t_wj_region_iter->first << " cloud has been saved in " + t_filename;
  539. }
  540. // for (size_t j = 0; j < t_wj_region_cloud->size(); j++)
  541. // {
  542. // message::Cloud_coordinate *tp_cloud = t_multi_status_msg.add_cloud();
  543. // tp_cloud->set_x(t_wj_region_cloud->points[j].x);
  544. // tp_cloud->set_y(t_wj_region_cloud->points[j].y);
  545. // tp_cloud->set_z(t_wj_region_cloud->points[j].z);
  546. // }
  547. // LOG_IF(WARNING, iter->second->get_terminal_id() == DISP_TERM_ID)<<"\n"<<t_car_wheel_information.to_string()<<"\n"
  548. // <<t_wj_car_wheel_information.to_string()<<"\n"
  549. // <<t_car_wheel_information.range_status<<", "<<t_wj_car_wheel_information.range_status;
  550. // 融合测量结果,验证中心点差异x<0.03, y<0.06, 角度差异ang<0.6, 轴距差异wb<0.055
  551. double dx = t_car_wheel_information.car_center_x - t_wj_car_wheel_information.car_center_x;
  552. double dy = t_car_wheel_information.car_center_y - t_wj_car_wheel_information.car_center_y;
  553. double dang = t_car_wheel_information.car_angle - t_wj_car_wheel_information.car_angle;
  554. double dwb = t_car_wheel_information.car_wheel_base - t_wj_car_wheel_information.car_wheel_base;
  555. if(fabs(dx) < 0.03 && fabs(dy) < 0.06 && fabs(dang) < 0.6 && fabs(dwb) < 0.055)
  556. {
  557. t_car_wheel_information.car_wheel_base = t_car_wheel_information.car_wheel_base*0.3 + t_car_wheel_information.car_wheel_base*0.7;
  558. }else
  559. {
  560. LOG_IF(WARNING, iter->second->get_terminal_id() == DISP_TERM_ID)<<
  561. "detect mismatch, region "<<iter->first<<", dx dy dang dwb: "<<dx<<", "<<dy<<", "<<dang<<", "<< dwb << std::endl
  562. << t_car_wheel_information.to_string() << std::endl
  563. << t_wj_car_wheel_information.to_string() << std::endl;
  564. }
  565. }else{
  566. LOG_IF(WARNING, iter->second->get_terminal_id() == DISP_TERM_ID)<<"region mismatch, vlp16 "<<iter->first<<", wj doesn't have corresponding region id";
  567. }
  568. update_measure_info(t_multi_status_msg, t_car_wheel_information, t_region_cloud->size());
  569. if(t_multi_status_msg.id_struct().terminal_id() == 4 ||
  570. t_multi_status_msg.id_struct().terminal_id() == 0||
  571. t_multi_status_msg.id_struct().terminal_id() == 5||
  572. t_multi_status_msg.id_struct().terminal_id() == 1||
  573. t_multi_status_msg.id_struct().terminal_id() == 3||
  574. t_multi_status_msg.id_struct().terminal_id() == 2)
  575. {
  576. // rabbitmq new measure info
  577. measure_info t_multi_measure_info_msg;
  578. t_multi_measure_info_msg.set_cx(t_car_wheel_information.uniform_car_x);
  579. t_multi_measure_info_msg.set_cy(t_car_wheel_information.uniform_car_y);
  580. t_multi_measure_info_msg.set_theta(t_car_wheel_information.car_angle);
  581. t_multi_measure_info_msg.set_length(0.0f);
  582. t_multi_measure_info_msg.set_width(t_car_wheel_information.car_wheel_width);
  583. t_multi_measure_info_msg.set_height(0.0f);
  584. t_multi_measure_info_msg.set_wheelbase(t_car_wheel_information.car_wheel_base);
  585. t_multi_measure_info_msg.set_front_theta(t_car_wheel_information.car_front_theta);
  586. t_multi_measure_info_msg.set_border_statu(t_car_wheel_information.range_status);
  587. auto t_ground_status = t_multi_status_msg.ground_status();
  588. if(t_ground_status == message::Ground_statu::Car_correct)
  589. {
  590. t_multi_measure_info_msg.set_ground_status(0);
  591. }else if(t_ground_status == message::Ground_statu::Nothing)
  592. {
  593. t_multi_measure_info_msg.set_ground_status(1);
  594. }else if(t_ground_status == message::Ground_statu::Noise)
  595. {
  596. t_multi_measure_info_msg.set_ground_status(2);
  597. }
  598. else if(t_ground_status == message::Ground_statu::Car_border_reached)
  599. {
  600. t_multi_measure_info_msg.set_ground_status(3);
  601. }else
  602. {
  603. t_multi_measure_info_msg.set_ground_status(2);
  604. std::cout<<"system executor 661, original status "<<t_ground_status<<std::endl;
  605. }
  606. // LOG(WARNING) << t_multi_status_msg.error_manager().error_description()<<std::endl;
  607. std::string t_msg = t_multi_measure_info_msg.DebugString();
  608. System_communication_mq::get_instance_references().encapsulate_status_msg(t_msg, t_multi_status_msg.id_struct().terminal_id());
  609. // if (t_multi_status_msg.id_struct().terminal_id() == 1)
  610. // {
  611. // LOG(WARNING) << "-------------------------------------------------------" <<std::endl;
  612. // LOG(WARNING) << "t_msg = " << t_msg <<std::endl;
  613. // LOG(WARNING) << "+++++++++++++++++++++++++++++++++++++++++++++++++++++++" <<std::endl;
  614. // LOG(WARNING) << "t_multi_status_msg.ground_status() = " << t_ground_status <<std::endl;
  615. // LOG(WARNING) << "t_multi_measure_info_msg.set_ground_status(0) = " << t_multi_measure_info_msg.ground_status() <<std::endl;
  616. // }
  617. }
  618. if (t_multi_status_msg.id_struct().terminal_id() == DISP_TERM_ID)
  619. {
  620. // LOG(WARNING) << t_car_wheel_information.range_status<<std::endl;
  621. LOG(INFO) << t_multi_status_msg.DebugString() << std::endl
  622. << std::endl;
  623. }
  624. }
  625. }
  626. #endif
  627. return Error_code::SUCCESS;
  628. }
  629. // ***************************** nanomsg *********************************
  630. //定时发送状态信息
  631. Error_manager System_executor::encapsulate_send_status()
  632. {
  633. static int cloud_count=-1;
  634. cloud_count++;
  635. // if(!g_debug_file.is_open())
  636. // {
  637. // g_debug_file.open("./filter_debug_result.txt", std::ios::app);
  638. // }
  639. Error_manager t_error;
  640. //创建一条状态消息
  641. message::Ground_status_msg t_ground_status_msg;
  642. t_ground_status_msg.mutable_base_info()->set_msg_type(message::Message_type::eGround_status_msg);
  643. t_ground_status_msg.mutable_base_info()->set_timeout_ms(5000);
  644. t_ground_status_msg.mutable_base_info()->set_sender(message::Communicator::eGround_measurer);
  645. t_ground_status_msg.mutable_base_info()->set_receiver(message::Communicator::eEmpty);
  646. // t_ground_status_msg.set_terminal_id(m_terminal_id);
  647. t_ground_status_msg.mutable_id_struct()->set_terminal_id(m_terminal_id);
  648. // 创建各区域状态消息,
  649. // 注意!!!目前公共消息名字依旧使用wj,不做修改
  650. // manager
  651. #if WJ_VELO == 1
  652. {
  653. Velodyne_manager::Velodyne_manager_status t_velodyne_manager_status = Velodyne_manager::get_instance_references().get_status();
  654. t_ground_status_msg.set_wanji_manager_status((message::Wanji_manager_status)t_velodyne_manager_status);
  655. // lidar
  656. std::map<int, Velodyne_lidar_device *> t_velodyne_lidar_device_map = Velodyne_manager::get_instance_references().get_velodyne_lidar_device_map();
  657. std::map<int, Velodyne_lidar_device::Velodyne_lidar_device_status> t_velodyne_lidar_status_map;
  658. for (auto iter = t_velodyne_lidar_device_map.begin(); iter != t_velodyne_lidar_device_map.end(); ++iter)
  659. {
  660. 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()));
  661. }
  662. // region
  663. std::map<int, Ground_region *> t_ground_region_map = Velodyne_manager::get_instance_references().get_ground_region_map();
  664. int region_index = 0;
  665. for (auto iter = t_ground_region_map.begin(); iter != t_ground_region_map.end(); ++iter)
  666. {
  667. // 以t_ground_status_msg为模板创建各区域心跳消息
  668. message::Ground_status_msg t_multi_status_msg;
  669. t_multi_status_msg.CopyFrom(t_ground_status_msg);
  670. t_multi_status_msg.mutable_id_struct()->set_terminal_id(iter->second->get_terminal_id());
  671. t_multi_status_msg.set_region_worker_status((message::Region_worker_status)(iter->second->get_status()));
  672. velodyne::Region t_param = iter->second->get_param();
  673. for (size_t j = 0; j < t_param.lidar_exts_size(); j++)
  674. {
  675. 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());
  676. if (t_status_iter == t_velodyne_lidar_status_map.end())
  677. {
  678. LOG(WARNING) << "lidar status " << t_param.lidar_exts(j).lidar_id() << " cannot be found, param error";
  679. }
  680. else
  681. {
  682. t_multi_status_msg.add_wanji_lidar_device_status((message::Wanji_lidar_device_status)t_status_iter->second);
  683. }
  684. }
  685. //velodyne雷达的自动定位信息
  686. Common_data::Car_wheel_information t_car_wheel_information;
  687. t_error = (*iter).second->get_last_wheel_information(&t_car_wheel_information, std::chrono::system_clock::now());
  688. // 获取区域点云填入信息
  689. pcl::PointCloud<pcl::PointXYZ>::Ptr t_region_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  690. iter->second->get_region_cloud(t_region_cloud, Ground_region::Region_cloud_type::filtered);
  691. // if (cloud_count == 5)
  692. // {
  693. // std::string t_filename = std::string("region_") + std::to_string(iter->first) + "_cloud.txt";
  694. // save_cloud_txt(t_region_cloud, t_filename);
  695. // LOG(INFO) << "region " << iter->first << " cloud has been saved in " + t_filename;
  696. // }
  697. // for (size_t j = 0; j < t_region_cloud->size(); j++)
  698. // {
  699. // message::Cloud_coordinate *tp_cloud = t_multi_status_msg.add_cloud();
  700. // tp_cloud->set_x(t_region_cloud->points[j].x);
  701. // tp_cloud->set_y(t_region_cloud->points[j].y);
  702. // tp_cloud->set_z(t_region_cloud->points[j].z);
  703. // }
  704. update_measure_info(t_multi_status_msg, t_car_wheel_information, t_region_cloud->size());
  705. std::string t_msg = t_multi_status_msg.SerializeAsString();
  706. System_communication::get_instance_references().encapsulate_msg(t_msg);
  707. if (t_multi_status_msg.id_struct().terminal_id() == DISP_TERM_ID)
  708. std::cout << t_multi_status_msg.DebugString() << std::endl
  709. << std::endl;
  710. }
  711. }
  712. #elif WJ_VELO == 0
  713. {
  714. // wj_support 20220718
  715. Wanji_manager::Wanji_manager_status t_wj_manager_status = Wanji_manager::get_instance_references().get_status();
  716. t_ground_status_msg.set_wanji_manager_status((message::Wanji_manager_status)t_wj_manager_status);
  717. // lidar
  718. std::map<int, Wanji_lidar_device *> t_wj_lidar_device_map = Wanji_manager::get_instance_references().get_wanji_lidar_device_map();
  719. std::map<int, Wanji_lidar_device::Wanji_lidar_device_status> t_wj_lidar_status_map;
  720. for (auto iter = t_wj_lidar_device_map.begin(); iter != t_wj_lidar_device_map.end(); ++iter)
  721. {
  722. 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()));
  723. }
  724. // region
  725. std::map<int, Region_worker *> t_region_worker_map = Wanji_manager::get_instance_references().get_region_worker_map();
  726. int region_index = 0;
  727. for (auto iter = t_region_worker_map.begin(); iter != t_region_worker_map.end(); ++iter)
  728. {
  729. // 以t_ground_status_msg为模板创建各区域心跳消息
  730. message::Ground_status_msg t_multi_status_msg;
  731. t_multi_status_msg.CopyFrom(t_ground_status_msg);
  732. t_multi_status_msg.mutable_id_struct()->set_terminal_id(iter->second->get_terminal_id());
  733. t_multi_status_msg.set_region_worker_status((message::Region_worker_status)(iter->second->get_status()));
  734. wj::Region t_param = iter->second->get_param();
  735. for (size_t j = 0; j < t_param.lidar_exts_size(); j++)
  736. {
  737. 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());
  738. if (t_status_iter == t_wj_lidar_status_map.end())
  739. {
  740. LOG(WARNING) << "lidar status " << t_param.lidar_exts(j).lidar_id() << " cannot be found, param error";
  741. }
  742. else
  743. {
  744. t_multi_status_msg.add_wanji_lidar_device_status((message::Wanji_lidar_device_status)t_status_iter->second);
  745. }
  746. }
  747. //velodyne雷达的自动定位信息
  748. Common_data::Car_wheel_information t_car_wheel_information;
  749. t_error = (*iter).second->get_last_wheel_information(&t_car_wheel_information, std::chrono::system_clock::now());
  750. // 获取区域点云填入信息
  751. pcl::PointCloud<pcl::PointXYZ>::Ptr t_region_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  752. iter->second->get_region_cloud(t_region_cloud);
  753. // if (cloud_count == 5)
  754. // {
  755. // std::string t_filename = std::string("region_") + std::to_string(iter->first) + "_cloud.txt";
  756. // save_cloud_txt(t_region_cloud, t_filename);
  757. // LOG(INFO) << "region " << iter->first << " cloud has been saved in " + t_filename;
  758. // }
  759. // for (size_t j = 0; j < t_region_cloud->size(); j++)
  760. // {
  761. // message::Cloud_coordinate *tp_cloud = t_multi_status_msg.add_cloud();
  762. // tp_cloud->set_x(t_region_cloud->points[j].x);
  763. // tp_cloud->set_y(t_region_cloud->points[j].y);
  764. // tp_cloud->set_z(t_region_cloud->points[j].z);
  765. // }
  766. update_measure_info(t_multi_status_msg, t_car_wheel_information, t_region_cloud->size());
  767. std::string t_msg = t_multi_status_msg.SerializeAsString();
  768. System_communication::get_instance_references().encapsulate_msg(t_msg);
  769. if (t_multi_status_msg.id_struct().terminal_id() == DISP_TERM_ID)
  770. LOG(INFO) << t_multi_status_msg.DebugString();
  771. }
  772. }
  773. // std::cout << " huli test :::: " << " t_ground_status_msg.DebugString() = " << std::endl;
  774. // std::cout << t_ground_status_msg.DebugString() << std::endl;
  775. // std::cout << " huli test :::: " << " t_ground_status_msg.DebugString() = " << t_ground_status_msg.DebugString() << std::endl;
  776. #else
  777. {
  778. // mix vlp16 and wj716
  779. // 以多线雷达为主
  780. Velodyne_manager::Velodyne_manager_status t_velodyne_manager_status = Velodyne_manager::get_instance_references().get_status();
  781. t_ground_status_msg.set_wanji_manager_status((message::Wanji_manager_status)t_velodyne_manager_status);
  782. // vlp16 lidar
  783. std::map<int, Velodyne_lidar_device *> t_velodyne_lidar_device_map = Velodyne_manager::get_instance_references().get_velodyne_lidar_device_map();
  784. std::map<int, Velodyne_lidar_device::Velodyne_lidar_device_status> t_velodyne_lidar_status_map;
  785. for (auto iter = t_velodyne_lidar_device_map.begin(); iter != t_velodyne_lidar_device_map.end(); ++iter)
  786. {
  787. 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()));
  788. }
  789. // wj lidar
  790. #if LIDAR_TYPE == 1
  791. std::map<int, Wanji_lidar_device *> t_wj_lidar_device_map = Wanji_manager::get_instance_references().get_wanji_lidar_device_map();
  792. std::map<int, Wanji_lidar_device::Wanji_lidar_device_status> t_wj_lidar_status_map;
  793. for (auto iter = t_wj_lidar_device_map.begin(); iter != t_wj_lidar_device_map.end(); ++iter)
  794. {
  795. 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()));
  796. }
  797. #else
  798. std::map<int, Wanji_716N_lidar_device *> t_wj_lidar_device_map = Wanji_manager::get_instance_references().get_wanji_lidar_device_map();
  799. std::map<int, Wanji_716N_lidar_device::Wanji_716N_device_status> t_wj_lidar_status_map;
  800. for (auto iter = t_wj_lidar_device_map.begin(); iter != t_wj_lidar_device_map.end(); ++iter)
  801. {
  802. t_wj_lidar_status_map.emplace(std::pair<int, Wanji_716N_lidar_device::Wanji_716N_device_status>(iter->second->get_lidar_id(), iter->second->get_status()));
  803. }
  804. #endif
  805. // wj region
  806. std::map<int, Region_worker *> t_region_worker_map = Wanji_manager::get_instance_references().get_region_worker_map();
  807. // vlp16 region
  808. std::map<int, Ground_region *> t_ground_region_map = Velodyne_manager::get_instance_references().get_ground_region_map();
  809. int region_index = 0;
  810. for (auto iter = t_ground_region_map.begin(); iter != t_ground_region_map.end(); ++iter)
  811. {
  812. // 以t_ground_status_msg为模板创建各区域心跳消息
  813. message::Ground_status_msg t_multi_status_msg;
  814. t_multi_status_msg.CopyFrom(t_ground_status_msg);
  815. t_multi_status_msg.mutable_id_struct()->set_terminal_id(iter->second->get_terminal_id());
  816. t_multi_status_msg.set_region_worker_status((message::Region_worker_status)(iter->second->get_status()));
  817. // 查找多线区域内对应多线激光雷达
  818. velodyne::Region t_param = iter->second->get_param();
  819. for (size_t j = 0; j < t_param.lidar_exts_size(); j++)
  820. {
  821. 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());
  822. if (t_status_iter == t_velodyne_lidar_status_map.end())
  823. {
  824. LOG(WARNING) << "vlp16 lidar status " << t_param.lidar_exts(j).lidar_id() << " cannot be found, param error";
  825. }
  826. else
  827. {
  828. t_multi_status_msg.add_wanji_lidar_device_status((message::Wanji_lidar_device_status)t_status_iter->second);
  829. }
  830. }
  831. //velodyne雷达的自动定位信息
  832. Common_data::Car_wheel_information t_car_wheel_information;
  833. t_error = (*iter).second->get_last_wheel_information(&t_car_wheel_information, std::chrono::system_clock::now());
  834. // 获取区域点云填入信息
  835. // 20221211 changed by yct, nanomsg dont save cloud
  836. pcl::PointCloud<pcl::PointXYZ>::Ptr t_region_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  837. iter->second->get_region_cloud(t_region_cloud, Ground_region::Region_cloud_type::filtered);
  838. // if (cloud_count == 5)
  839. // {
  840. // std::string t_filename = std::string("vlp16_region_") + std::to_string(iter->first) + "_cloud.txt";
  841. // save_cloud_txt(t_region_cloud, t_filename);
  842. // LOG(INFO) << "vlp16 region " << iter->first << " cloud has been saved in " + t_filename;
  843. // }
  844. // for (size_t j = 0; j < t_region_cloud->size(); j++)
  845. // {
  846. // message::Cloud_coordinate *tp_cloud = t_multi_status_msg.add_cloud();
  847. // tp_cloud->set_x(t_region_cloud->points[j].x);
  848. // tp_cloud->set_y(t_region_cloud->points[j].y);
  849. // tp_cloud->set_z(t_region_cloud->points[j].z);
  850. // }
  851. // 检查vlp16区域与wj区域对应关系,wj存在对应区域则填充设备状态,并融合测量结果
  852. auto t_wj_region_iter = t_region_worker_map.find(iter->first);
  853. if(t_wj_region_iter != t_region_worker_map.end())
  854. {
  855. wj::Region t_param = t_wj_region_iter->second->get_param();
  856. //
  857. for (size_t j = 0; j < t_param.lidar_exts_size(); j++)
  858. {
  859. #if LIDAR_TYPE == 1
  860. 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());
  861. #else
  862. std::map<int, Wanji_716N_lidar_device::Wanji_716N_device_status>::iterator t_status_iter = t_wj_lidar_status_map.find(t_param.lidar_exts(j).lidar_id());
  863. #endif
  864. if (t_status_iter == t_wj_lidar_status_map.end())
  865. {
  866. LOG(WARNING) << "wj lidar status " << t_param.lidar_exts(j).lidar_id() << " cannot be found, param error";
  867. }
  868. else
  869. {
  870. t_multi_status_msg.add_wanji_lidar_device_status((message::Wanji_lidar_device_status)t_status_iter->second);
  871. }
  872. }
  873. //wj雷达的自动定位信息
  874. Common_data::Car_wheel_information t_wj_car_wheel_information;
  875. t_error = t_wj_region_iter->second->get_last_wheel_information(&t_wj_car_wheel_information, std::chrono::system_clock::now());
  876. // 获取区域点云填入信息
  877. pcl::PointCloud<pcl::PointXYZ>::Ptr t_wj_region_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  878. t_wj_region_iter->second->get_region_cloud(t_wj_region_cloud);
  879. // if (cloud_count == 8)
  880. // {
  881. // std::string t_filename = std::string("wj_region_") + std::to_string(t_wj_region_iter->first) + "_cloud.txt";
  882. // save_cloud_txt(t_wj_region_cloud, t_filename);
  883. // LOG(INFO) << "wj region " << t_wj_region_iter->first << " cloud has been saved in " + t_filename;
  884. // }
  885. // for (size_t j = 0; j < t_wj_region_cloud->size(); j++)
  886. // {
  887. // message::Cloud_coordinate *tp_cloud = t_multi_status_msg.add_cloud();
  888. // tp_cloud->set_x(t_wj_region_cloud->points[j].x);
  889. // tp_cloud->set_y(t_wj_region_cloud->points[j].y);
  890. // tp_cloud->set_z(t_wj_region_cloud->points[j].z);
  891. // }
  892. // LOG_IF(WARNING, iter->second->get_terminal_id() == DISP_TERM_ID)<<"\n"<<t_car_wheel_information.to_string()<<"\n"
  893. // <<t_wj_car_wheel_information.to_string()<<"\n"
  894. // <<t_car_wheel_information.range_status<<", "<<t_wj_car_wheel_information.range_status;
  895. // 融合测量结果,验证中心点差异x<0.03, y<0.06, 角度差异ang<0.6, 轴距差异wb<0.055
  896. double dx = t_car_wheel_information.car_center_x - t_wj_car_wheel_information.car_center_x;
  897. double dy = t_car_wheel_information.car_center_y - t_wj_car_wheel_information.car_center_y;
  898. double dang = t_car_wheel_information.car_angle - t_wj_car_wheel_information.car_angle;
  899. double dwb = t_car_wheel_information.car_wheel_base - t_wj_car_wheel_information.car_wheel_base;
  900. // 使用rabbit mq 中函数计算偏差与提示,此处不处理!!
  901. if(fabs(dx) < 0.03 && fabs(dy) < 0.06 && fabs(dang) < 0.6 && fabs(dwb) < 0.055)
  902. {
  903. // t_car_wheel_information.car_wheel_base = t_car_wheel_information.car_wheel_base*0.3 + t_car_wheel_information.car_wheel_base*0.7;
  904. }else
  905. {
  906. // LOG_IF(WARNING, iter->second->get_terminal_id() == DISP_TERM_ID)<<
  907. // "detect mismatch, region "<<iter->first<<", dx dy dang dwb: "<<dx<<", "<<dy<<", "<<dang<<", "<< dwb << std::endl
  908. // << t_car_wheel_information.to_string() << std::endl
  909. // << t_wj_car_wheel_information.to_string() << std::endl;
  910. }
  911. }else{
  912. LOG_IF(WARNING, iter->second->get_terminal_id() == DISP_TERM_ID)<<"region mismatch, vlp16 "<<iter->first<<", wj doesn't have corresponding region id";
  913. }
  914. update_measure_info(t_multi_status_msg, t_car_wheel_information, t_region_cloud->size());
  915. std::string t_msg = t_multi_status_msg.SerializeAsString();
  916. System_communication::get_instance_references().encapsulate_msg(t_msg);
  917. // if (t_multi_status_msg.id_struct().terminal_id() == DISP_TERM_ID)
  918. // std::cout << t_multi_status_msg.DebugString() << std::endl
  919. // << std::endl;
  920. }
  921. }
  922. #endif
  923. return Error_code::SUCCESS;
  924. }
  925. //判断是否为待机,如果已经准备好,则可以执行任务。
  926. bool System_executor::is_ready()
  927. {
  928. if (m_system_executor_status == SYSTEM_EXECUTOR_READY && m_thread_pool.thread_is_full_load() == false)
  929. {
  930. return true;
  931. }
  932. else
  933. {
  934. return false;
  935. }
  936. }
  937. System_executor::System_executor_status System_executor::get_system_executor_status()
  938. {
  939. return m_system_executor_status;
  940. }
  941. int System_executor::get_terminal_id()
  942. {
  943. return m_terminal_id;
  944. }
  945. //雷达感测定位 的处理函数
  946. //input::command_id, 消息指令id, 由主控制系统生成的唯一码
  947. //input::command_id, 终端id, 对应具体的某个车位
  948. //return::void, 没有返回, 执行结果直接生成一条答复消息, 然后通过通信返回
  949. void System_executor::execute_for_measure(std::string command_info, int terminal_id, std::chrono::system_clock::time_point receive_time)
  950. {
  951. Error_manager t_error;
  952. Error_manager t_result;
  953. LOG(INFO) << " System_executor::execute_for_measure run " << this;
  954. //第1步, 按照时间生成中间文件的保存路径
  955. time_t nowTime;
  956. nowTime = time(NULL);
  957. struct tm *sysTime = localtime(&nowTime);
  958. char t_save_path[256] = {0};
  959. sprintf(t_save_path, "../data/%04d%02d%02d_%02d%02d%02d",
  960. sysTime->tm_year + 1900, sysTime->tm_mon + 1, sysTime->tm_mday, sysTime->tm_hour, sysTime->tm_min, sysTime->tm_sec);
  961. //第2步, 创建万集管理模块的任务单, 并发送到 wanji_manager
  962. // Wanji_manager_task t_wanji_manager_task ;
  963. // Common_data::Car_wheel_information t_car_information_by_wanji;
  964. // t_wanji_manager_task.task_init(TASK_CREATED,"",NULL,std::chrono::milliseconds(3000),
  965. // terminal_id, receive_time);
  966. // t_error = Task_command_manager::get_instance_references().execute_task(&t_wanji_manager_task);
  967. // 或者创建velodyne管理模块任务单,并发送到velodyne_manager
  968. Velodyne_manager_task t_velodyne_manager_task;
  969. Common_data::Car_wheel_information t_car_information_by_velodyne;
  970. t_velodyne_manager_task.task_init(TASK_CREATED, "", NULL, std::chrono::milliseconds(3000),
  971. terminal_id, receive_time);
  972. t_error = Task_command_manager::get_instance_references().execute_task(&t_velodyne_manager_task);
  973. //第3步, 等待任务单完成
  974. if (t_error != Error_code::SUCCESS)
  975. {
  976. LOG(INFO) << " Velodyne_manager/Velodyne_manager execute_task error " << this;
  977. }
  978. else
  979. {
  980. // //判断任务是否结束, 阻塞 等待, 直到任务完成或者超时
  981. // while ( t_wanji_manager_task.is_task_end() == false)
  982. // {
  983. // if ( t_wanji_manager_task.is_over_time() )
  984. // {
  985. // //超时处理。取消任务。
  986. // Wanji_manager::get_instance_pointer()->cancel_task(&t_wanji_manager_task);
  987. // t_error.error_manager_reset(Error_code::WJ_MANAGER_TASK_OVER_TIME, Error_level::MINOR_ERROR,
  988. // " t_wanjestaui_manager_task is_over_time ");
  989. // t_wanji_manager_task.set_task_error_manager(t_error);
  990. // }
  991. // else
  992. // {
  993. // //继续等待
  994. // std::this_thread::sleep_for(std::chrono::microseconds(1));
  995. // std::this_thread::yield();
  996. // }
  997. // }
  998. // //提取任务单 的错误码
  999. // t_error = t_wanji_manager_task.get_task_error_manager();
  1000. // if ( t_error == Error_code::SUCCESS )
  1001. // {
  1002. // t_car_information_by_wanji = t_wanji_manager_task.get_car_wheel_information();
  1003. // }
  1004. // else
  1005. // {
  1006. // LOG(INFO) << " wanji_manager_task error :::::::" << t_wanji_manager_task.get_task_error_manager().to_string() << this;
  1007. // }
  1008. // ------------------- 切换为velodyne ------------------
  1009. //判断任务是否结束, 阻塞 等待, 直到任务完成或者超时
  1010. while (t_velodyne_manager_task.is_task_end() == false)
  1011. {
  1012. if (t_velodyne_manager_task.is_over_time())
  1013. {
  1014. //超时处理。取消任务。
  1015. Velodyne_manager::get_instance_pointer()->cancel_task(&t_velodyne_manager_task);
  1016. t_error.error_manager_reset(Error_code::VELODYNE_MANAGER_TASK_OVER_TIME, Error_level::MINOR_ERROR,
  1017. " t_velodyne_manager_task is_over_time ");
  1018. t_velodyne_manager_task.set_task_error_manager(t_error);
  1019. }
  1020. else
  1021. {
  1022. //继续等待
  1023. std::this_thread::sleep_for(std::chrono::microseconds(1));
  1024. std::this_thread::yield();
  1025. }
  1026. }
  1027. //提取任务单 的错误码
  1028. t_error = t_velodyne_manager_task.get_task_error_manager();
  1029. if (t_error == Error_code::SUCCESS)
  1030. {
  1031. t_car_information_by_velodyne = t_velodyne_manager_task.get_car_wheel_information();
  1032. }
  1033. else
  1034. {
  1035. LOG(INFO) << " velodyne_manager_task error :::::::" << t_velodyne_manager_task.get_task_error_manager().to_string() << this;
  1036. }
  1037. }
  1038. t_result.compare_and_cover_error(t_error);
  1039. //measure 测量模块的最终结果
  1040. Common_data::Car_measure_information t_car_information_result;
  1041. //第4步, 生成反馈消息
  1042. // if(t_car_information_by_wanji.correctness == true )
  1043. // {
  1044. // t_car_information_result.center_x = t_car_information_by_wanji.center_x;
  1045. // t_car_information_result.center_y = t_car_information_by_wanji.center_y;
  1046. // t_car_information_result.car_angle = t_car_information_by_wanji.car_angle;
  1047. // t_car_information_result.wheel_base = t_car_information_by_wanji.wheel_base;
  1048. // t_car_information_result.wheel_width = t_car_information_by_wanji.wheel_width;
  1049. // t_car_information_result.correctness = true;
  1050. // }else{
  1051. // t_result.set_error_level_down(NEGLIGIBLE_ERROR);
  1052. // }
  1053. // ------------------- 切换为velodyne ------------------
  1054. if (t_car_information_by_velodyne.correctness == true)
  1055. {
  1056. t_car_information_result.car_center_x = t_car_information_by_velodyne.car_center_x;
  1057. t_car_information_result.car_center_y = t_car_information_by_velodyne.car_center_y;
  1058. t_car_information_result.car_angle = t_car_information_by_velodyne.car_angle;
  1059. t_car_information_result.car_wheel_base = t_car_information_by_velodyne.car_wheel_base;
  1060. t_car_information_result.car_wheel_width = t_car_information_by_velodyne.car_wheel_width;
  1061. t_car_information_result.correctness = true;
  1062. }
  1063. else
  1064. {
  1065. t_result.set_error_level_down(NEGLIGIBLE_ERROR);
  1066. }
  1067. //第七步, 创建一条答复消息
  1068. message::Ground_detect_response_msg t_ground_detect_response_msg;
  1069. t_ground_detect_response_msg.mutable_base_info()->set_msg_type(message::Message_type::eGround_detect_response_msg);
  1070. t_ground_detect_response_msg.mutable_base_info()->set_timeout_ms(5000);
  1071. t_ground_detect_response_msg.mutable_base_info()->set_sender(message::Communicator::eGround_measurer);
  1072. t_ground_detect_response_msg.mutable_base_info()->set_receiver(message::Communicator::eMain);
  1073. t_ground_detect_response_msg.set_command_key(command_info);
  1074. t_ground_detect_response_msg.mutable_id_struct()->set_terminal_id(terminal_id);
  1075. t_ground_detect_response_msg.mutable_error_manager()->set_error_code(t_result.get_error_code());
  1076. t_ground_detect_response_msg.mutable_error_manager()->set_error_level((message::Error_level)t_result.get_error_level());
  1077. t_ground_detect_response_msg.mutable_error_manager()->set_error_description(t_result.get_error_description());
  1078. t_ground_detect_response_msg.mutable_locate_information()->set_locate_x(t_car_information_result.car_center_x);
  1079. t_ground_detect_response_msg.mutable_locate_information()->set_locate_y(t_car_information_result.car_center_y);
  1080. t_ground_detect_response_msg.mutable_locate_information()->set_locate_angle(t_car_information_result.car_angle);
  1081. t_ground_detect_response_msg.mutable_locate_information()->set_locate_length(t_car_information_result.car_length);
  1082. t_ground_detect_response_msg.mutable_locate_information()->set_locate_width(t_car_information_result.car_width);
  1083. t_ground_detect_response_msg.mutable_locate_information()->set_locate_height(t_car_information_result.car_height);
  1084. t_ground_detect_response_msg.mutable_locate_information()->set_locate_wheel_base(t_car_information_result.car_wheel_base);
  1085. t_ground_detect_response_msg.mutable_locate_information()->set_locate_wheel_width(t_car_information_result.car_wheel_width);
  1086. t_ground_detect_response_msg.mutable_locate_information()->set_locate_front_theta(t_car_information_result.car_front_theta);
  1087. t_ground_detect_response_msg.mutable_locate_information()->set_locate_correct(t_car_information_result.correctness);
  1088. std::string t_msg = t_ground_detect_response_msg.SerializeAsString();
  1089. System_communication::get_instance_references().encapsulate_msg(t_msg);
  1090. std::cout << "huli t_measure_response_msg = " << t_ground_detect_response_msg.DebugString() << std::endl;
  1091. return;
  1092. }