dispatch_ground_lidar.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285
  1. //
  2. // Created by huli on 2021/9/25.
  3. //
  4. #include "dispatch_ground_lidar.h"
  5. Dispatch_ground_lidar::Dispatch_ground_lidar()
  6. {
  7. m_dispatch_ground_lidar_status = DISPATCH_GROUND_LIDAR_UNKNOW;
  8. m_plc_id = 0;
  9. m_ground_lidar_id = 0;
  10. m_ground_status_msg_updata_flag = false;
  11. }
  12. Dispatch_ground_lidar::~Dispatch_ground_lidar()
  13. {
  14. dispatch_ground_lidar_uninit();
  15. }
  16. //调度地面雷达 初始化
  17. Error_manager Dispatch_ground_lidar::dispatch_ground_lidar_init(int plc_id, int ground_lidar_id)
  18. {
  19. m_plc_id = plc_id;
  20. m_ground_lidar_id = ground_lidar_id;
  21. mp_execute_thread = nullptr ;
  22. m_ground_status_msg_updata_time = std::chrono::system_clock::now();
  23. m_ground_status_msg_updata_flag = false;
  24. // 线程默认开启
  25. m_execute_condition.reset(false, true, false);
  26. mp_execute_thread = new std::thread(&Dispatch_ground_lidar::execute_thread_fun, this);
  27. m_dispatch_ground_lidar_status = DISPATCH_GROUND_LIDAR_READY;
  28. return Error_code::SUCCESS;
  29. }
  30. //调度地面雷达 反初始化
  31. Error_manager Dispatch_ground_lidar::dispatch_ground_lidar_uninit()
  32. {
  33. if (mp_execute_thread)
  34. {
  35. m_execute_condition.kill_all();
  36. }
  37. if (mp_execute_thread)
  38. {
  39. mp_execute_thread->join();
  40. delete mp_execute_thread;
  41. mp_execute_thread = NULL;
  42. }
  43. m_dispatch_ground_lidar_status = Dispatch_ground_lidar::DISPATCH_GROUND_LIDAR_UNKNOW;
  44. return Error_code::SUCCESS;
  45. }
  46. //调度地面雷达 执行状态消息
  47. //Error_manager Dispatch_ground_lidar::execute_for_ground_status_msg(message::Ground_status_msg &ground_status_msg)
  48. //{
  49. //// std::unique_lock<std::mutex> t_lock2(m_lock);
  50. //// m_ground_status_msg = ground_status_msg;
  51. //// m_ground_status_msg_updata_time = std::chrono::system_clock::now();
  52. //// m_ground_status_msg_updata_flag = true;
  53. // return Error_code::SUCCESS;
  54. //}
  55. //调度地面雷达 执行状态消息
  56. Error_manager Dispatch_ground_lidar::execute_for_ground_status_msg_new(measure_info &t_measure_info)
  57. {
  58. std::unique_lock<std::mutex> t_lock2(m_lock);
  59. m_measure_info = t_measure_info;
  60. m_ground_status_msg_updata_time = std::chrono::system_clock::now();
  61. m_ground_status_msg_updata_flag = true;
  62. //胡力 新增 接受雷达雷达 通信周期 超过1秒就打印
  63. int time_key = 10+m_ground_lidar_id;
  64. Time_tool::get_instance_references().time_end(time_key);
  65. if ( Time_tool::get_instance_references().timetool_map.find(time_key)!=Time_tool::get_instance_references().timetool_map.end() )
  66. {
  67. if ( Time_tool::get_instance_references().timetool_map[time_key].t_time_difference >= std::chrono::milliseconds(1) )
  68. {
  69. Time_tool::get_instance_references().cout_time_microsecond(time_key);
  70. double dieoutTime=(double)Time_tool::get_instance_references().timetool_map[time_key].t_time_difference.count()/1000000;
  71. // std::cout << "计时器:"<<key<<" 计时的时间为:" <<dieoutTime<<" 毫秒" << std::endl;
  72. LOG(INFO) << "计时器:"<<time_key<<" 计时的时间为:" <<dieoutTime<<" 毫秒" << " --- " << this;
  73. }
  74. }
  75. Time_tool::get_instance_references().time_start(time_key);
  76. //胡力 新增 接受雷达雷达 通信周期 超过1秒就打印
  77. return Error_code::SUCCESS;
  78. }
  79. Dispatch_ground_lidar::Dispatch_ground_lidar_status Dispatch_ground_lidar::get_dispatch_ground_lidar_status()
  80. {
  81. return m_dispatch_ground_lidar_status;
  82. }
  83. //执行外界任务的执行函数
  84. void Dispatch_ground_lidar::execute_thread_fun()
  85. {
  86. LOG(INFO) << " Dispatch_ground_lidar::execute_thread_fun() start " << this;
  87. Error_manager t_error;
  88. while (m_execute_condition.is_alive())
  89. {
  90. m_execute_condition.wait();
  91. if (m_execute_condition.is_alive())
  92. {
  93. std::this_thread::sleep_for(std::chrono::milliseconds(1));
  94. // std::this_thread::sleep_for(std::chrono::seconds(1));
  95. std::this_thread::yield();
  96. if (m_ground_status_msg_updata_flag)
  97. {
  98. std::unique_lock<std::mutex> t_lock(Dispatch_communication::get_instance_references().m_data_lock);
  99. std::unique_lock<std::mutex> t_lock2(m_lock);
  100. //将nnxx的protobuf 转化为 snap7的DB块, 把店面雷达数据转发给plc
  101. // int t_inlet_id = m_ground_status_msg.mutable_id_struct()->terminal_id() % 2;
  102. int t_inlet_id = m_ground_lidar_id;
  103. Dispatch_communication::Ground_lidar_response_from_manager_to_plc_for_data *p_response_data = &Dispatch_communication::get_instance_references().m_ground_lidar_response_from_manager_to_plc_for_data[t_inlet_id];
  104. Dispatch_communication::Ground_lidar_response_from_manager_to_plc_for_key *p_response_key = &Dispatch_communication::get_instance_references().m_ground_lidar_response_from_manager_to_plc_for_key[t_inlet_id];
  105. Dispatch_communication::Ground_lidar_request_from_plc_to_manager *p_request = &Dispatch_communication::get_instance_references().m_ground_lidar_request_from_plc_to_manager[t_inlet_id];
  106. if (p_request->m_request_communication_mode != 2)
  107. {
  108. p_response_data->m_response_heartbeat = 1+p_response_data->m_response_heartbeat;
  109. p_response_data->m_response_communication_mode = p_request->m_request_communication_mode;
  110. p_response_data->m_response_refresh_command = p_request->m_request_refresh_command;
  111. // p_response_data->m_response_car_center_x = m_ground_status_msg.locate_information_realtime().locate_x();
  112. // p_response_data->m_response_car_center_y = m_ground_status_msg.locate_information_realtime().locate_y();
  113. // p_response_data->m_response_car_angle = m_ground_status_msg.locate_information_realtime().locate_angle();
  114. // p_response_data->m_response_car_front_theta = m_ground_status_msg.locate_information_realtime().locate_front_theta();
  115. // p_response_data->m_response_car_length = m_ground_status_msg.locate_information_realtime().locate_length();
  116. // p_response_data->m_response_car_width = m_ground_status_msg.locate_information_realtime().locate_width();
  117. // p_response_data->m_response_car_height = m_ground_status_msg.locate_information_realtime().locate_height();
  118. // p_response_data->m_response_car_wheel_base = m_ground_status_msg.locate_information_realtime().locate_wheel_base();
  119. // p_response_data->m_response_car_wheel_width = m_ground_status_msg.locate_information_realtime().locate_wheel_width();
  120. // p_response_data->m_response_uniformed_car_x = m_ground_status_msg.locate_information_realtime().uniformed_car_x();
  121. // p_response_data->m_response_uniformed_car_y = m_ground_status_msg.locate_information_realtime().uniformed_car_y();
  122. // p_response_data->m_response_locate_correct = m_ground_status_msg.locate_information_realtime().locate_correct();
  123. if ( m_measure_info.ground_status() == 0 ) //ground_status :ok 1,nothing 2,noise 3,border
  124. {
  125. p_response_data->m_response_car_center_x = m_measure_info.cx();
  126. p_response_data->m_response_car_center_y = m_measure_info.cy();
  127. p_response_data->m_response_car_angle = m_measure_info.theta();
  128. p_response_data->m_response_car_front_theta = m_measure_info.front_theta();
  129. p_response_data->m_response_car_length = m_measure_info.length();
  130. p_response_data->m_response_car_width = m_measure_info.width();
  131. p_response_data->m_response_car_height = m_measure_info.height();
  132. p_response_data->m_response_car_wheel_base = m_measure_info.wheelbase();
  133. p_response_data->m_response_car_wheel_width = m_measure_info.width();
  134. p_response_data->m_response_uniformed_car_x = m_measure_info.cx();
  135. p_response_data->m_response_uniformed_car_y = m_measure_info.cy();
  136. p_response_data->m_response_locate_correct = 1; //locate_correct 0=无效, 1=有效,
  137. p_response_data->m_response_ground_status = m_measure_info.ground_status(); //0 ok 1,nothing 2,noise 3,border
  138. }
  139. else
  140. {
  141. p_response_data->m_response_car_center_x = 0;
  142. p_response_data->m_response_car_center_y = 0;
  143. p_response_data->m_response_car_angle = 0;
  144. p_response_data->m_response_car_front_theta = 0;
  145. p_response_data->m_response_car_length = 0;
  146. p_response_data->m_response_car_width = 0;
  147. p_response_data->m_response_car_height = 0;
  148. p_response_data->m_response_car_wheel_base = 0;
  149. p_response_data->m_response_car_wheel_width = 0;
  150. p_response_data->m_response_uniformed_car_x = 0;
  151. p_response_data->m_response_uniformed_car_y = 0;
  152. p_response_data->m_response_locate_correct = 0;
  153. p_response_data->m_response_ground_status = m_measure_info.ground_status(); //0 ok 1,nothing 2,noise 3,border
  154. }
  155. // LOG(WARNING) << "------------------------------------------------------------ "<<std::endl;
  156. // LOG(WARNING) << "m_measure_info = " << m_measure_info.ground_status() <<std::endl;
  157. // LOG(WARNING) << "m_measure_info = " << m_measure_info.DebugString() <<std::endl;
  158. // LOG(WARNING) << "m_measure_info.wheelbase() = " << m_measure_info.wheelbase() <<std::endl;
  159. // LOG(WARNING) << "m_measure_info.ground_status() = " << m_measure_info.ground_status() <<std::endl;
  160. // LOG(WARNING) << "p_response_data->m_response_locate_correct = " << p_response_data->m_response_locate_correct <<std::endl;
  161. // printf("p_response_data->m_response_locate_correct = %d, \n", p_response_data->m_response_locate_correct);
  162. // LOG(WARNING) << "-++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ "<<std::endl;
  163. }
  164. else if (p_response_data->m_response_refresh_command == p_request->m_request_refresh_command)
  165. {
  166. p_response_data->m_response_heartbeat = 1+p_response_data->m_response_heartbeat;
  167. p_response_data->m_response_communication_mode = p_request->m_request_communication_mode;
  168. p_response_data->m_response_refresh_command = p_request->m_request_refresh_command;
  169. }
  170. else
  171. {
  172. p_response_data->m_response_heartbeat = 1+p_response_data->m_response_heartbeat;
  173. p_response_data->m_response_communication_mode = p_request->m_request_communication_mode;
  174. p_response_data->m_response_refresh_command = p_request->m_request_refresh_command;
  175. // p_response_data->m_response_car_center_x = m_ground_status_msg.locate_information_realtime().locate_x();
  176. // p_response_data->m_response_car_center_y = m_ground_status_msg.locate_information_realtime().locate_y();
  177. // p_response_data->m_response_car_angle = m_ground_status_msg.locate_information_realtime().locate_angle();
  178. // p_response_data->m_response_car_front_theta = m_ground_status_msg.locate_information_realtime().locate_front_theta();
  179. // p_response_data->m_response_car_length = m_ground_status_msg.locate_information_realtime().locate_length();
  180. // p_response_data->m_response_car_width = m_ground_status_msg.locate_information_realtime().locate_width();
  181. // p_response_data->m_response_car_height = m_ground_status_msg.locate_information_realtime().locate_height();
  182. // p_response_data->m_response_car_wheel_base = m_ground_status_msg.locate_information_realtime().locate_wheel_base();
  183. // p_response_data->m_response_car_wheel_width = m_ground_status_msg.locate_information_realtime().locate_wheel_width();
  184. // p_response_data->m_response_uniformed_car_x = m_ground_status_msg.locate_information_realtime().uniformed_car_x();
  185. // p_response_data->m_response_uniformed_car_y = m_ground_status_msg.locate_information_realtime().uniformed_car_y();
  186. // p_response_data->m_response_locate_correct = m_ground_status_msg.locate_information_realtime().locate_correct();
  187. if ( m_measure_info.ground_status() == 0 ) //ground_status :ok 1,nothing 2,noise 3,border
  188. {
  189. p_response_data->m_response_car_center_x = m_measure_info.cx();
  190. p_response_data->m_response_car_center_y = m_measure_info.cy();
  191. p_response_data->m_response_car_angle = m_measure_info.theta();
  192. p_response_data->m_response_car_front_theta = m_measure_info.front_theta();
  193. p_response_data->m_response_car_length = m_measure_info.length();
  194. p_response_data->m_response_car_width = m_measure_info.width();
  195. p_response_data->m_response_car_height = m_measure_info.height();
  196. p_response_data->m_response_car_wheel_base = m_measure_info.wheelbase();
  197. p_response_data->m_response_car_wheel_width = m_measure_info.width();
  198. p_response_data->m_response_uniformed_car_x = m_measure_info.cx();
  199. p_response_data->m_response_uniformed_car_y = m_measure_info.cy();
  200. p_response_data->m_response_locate_correct = 1; //locate_correct 0=无效, 1=有效,
  201. p_response_data->m_response_ground_status = m_measure_info.ground_status(); //0 ok 1,nothing 2,noise 3,border
  202. }
  203. else
  204. {
  205. p_response_data->m_response_car_center_x = 0;
  206. p_response_data->m_response_car_center_y = 0;
  207. p_response_data->m_response_car_angle = 0;
  208. p_response_data->m_response_car_front_theta = 0;
  209. p_response_data->m_response_car_length = 0;
  210. p_response_data->m_response_car_width = 0;
  211. p_response_data->m_response_car_height = 0;
  212. p_response_data->m_response_car_wheel_base = 0;
  213. p_response_data->m_response_car_wheel_width = 0;
  214. p_response_data->m_response_uniformed_car_x = 0;
  215. p_response_data->m_response_uniformed_car_y = 0;
  216. p_response_data->m_response_locate_correct = 0;
  217. p_response_data->m_response_ground_status = m_measure_info.ground_status(); //0 ok 1,nothing 2,noise 3,border
  218. }
  219. }
  220. m_ground_status_msg_updata_flag = false;
  221. }
  222. //判断超时
  223. {
  224. std::unique_lock<std::mutex> t_lock3(m_lock);
  225. if (std::chrono::system_clock::now() - m_ground_status_msg_updata_time > std::chrono::seconds(5))
  226. {
  227. m_dispatch_ground_lidar_status = DISPATCH_GROUND_LIDAR_DISCONNECT;
  228. }
  229. else
  230. {
  231. m_dispatch_ground_lidar_status = DISPATCH_GROUND_LIDAR_READY;
  232. }
  233. }
  234. }
  235. }
  236. }