system_executor.cpp 28 KB

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