fence_controller.cpp 23 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632
  1. //
  2. // Created by zx on 2019/12/6.
  3. //
  4. #include "fence_controller.h"
  5. int Fence_controller::S_RETRY_TIMES=3;
  6. /**
  7. * 配置读取函数,暂未使用
  8. * */
  9. bool Fence_controller::read_proto_param(std::string path)
  10. {
  11. int fd = open(path.c_str(), O_RDONLY);
  12. if (fd == -1)
  13. return false;
  14. FileInputStream *input = new FileInputStream(fd);
  15. bool success = google::protobuf::TextFormat::Parse(input, &m_wj_manager_param);
  16. // std::cout<<m_global_param.data_path()<<std::endl;
  17. delete input;
  18. close(fd);
  19. return success;
  20. }
  21. /**
  22. * 保存点云为txt文件
  23. * */
  24. void Fence_controller::save_cloud_txt(std::string txt, pcl::PointCloud<pcl::PointXYZ>::Ptr pCloud)
  25. {
  26. std::ofstream os;
  27. os.open(txt, std::ios::out);
  28. for (int i = 0; i < pCloud->points.size(); i++)
  29. {
  30. pcl::PointXYZ point = pCloud->points[i];
  31. char buf[255];
  32. memset(buf, 0, 255);
  33. sprintf(buf, "%f %f %f\n", point.x, point.y, point.z);
  34. os.write(buf, strlen(buf));
  35. }
  36. os.close();
  37. }
  38. /**
  39. * 初始化函数,根据配置生成日志与数据保存路径,创建雷达,区域与plc句柄以及更新,消息接收与处理线程
  40. * */
  41. Error_manager Fence_controller::initialize(wj::wjManagerParams params)
  42. {
  43. mp_merged_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  44. // get current working directory
  45. char curr_dir[100];
  46. getcwd(curr_dir, sizeof(curr_dir));
  47. m_wj_manager_param.CopyFrom(params);
  48. // create data path
  49. if (m_wj_manager_param.has_fence_data_path() && m_wj_manager_param.fence_data_path() != "")
  50. {
  51. PathCreator path_creator;
  52. path_creator.Mkdir(m_wj_manager_param.fence_data_path());
  53. }
  54. mp_plc_data = Plc_data::get_instance(m_wj_manager_param.plc_ip_address());
  55. if (mp_plc_data != 0 && mp_plc_data->get_plc_status())
  56. {
  57. LOG(INFO) << "created plc data handler" << mp_plc_data;
  58. }
  59. else
  60. {
  61. // LOG(ERROR) << "create plc data handler error";
  62. return Error_manager(Error_code::WJ_MANAGER_UNINITIALIZED,NORMAL,"万集plc连接失败");
  63. }
  64. // init lidar instances
  65. for (int i = 0; i < m_wj_manager_param.wj_lidar_size(); ++i)
  66. {
  67. m_lidars_vector.push_back(new Wj_lidar_encapsulation());
  68. Error_manager code = m_lidars_vector[i]->initialize(m_wj_manager_param.wj_lidar(i));
  69. // 错误码信息已在内部打印
  70. if (code != SUCCESS)
  71. {
  72. return Error_manager(Error_code::WJ_MANAGER_UNINITIALIZED,NORMAL,"万集雷达连接失败");
  73. }
  74. }
  75. // init region_detector instances
  76. for (int j = 0; j < m_wj_manager_param.regions_size(); ++j)
  77. {
  78. m_region_workers_vector.push_back(new Region_worker(j, m_wj_manager_param.regions(j), mp_verify_result_tool));
  79. }
  80. LOG(INFO) << "created wj lidars and region workers";
  81. // init wheel handling thread
  82. m_cond_wheel_exit.Notify(false);
  83. if (m_wheel_soc)
  84. {
  85. m_wheel_soc.bind(CONNECTSTRING);
  86. }
  87. m_wheel_send_thread = new std::thread(wheel_msg_handling_thread, this);
  88. m_wheel_send_thread->detach();
  89. m_wheel_recv_thread = new std::thread(wheel_msg_recv_thread, this);
  90. m_wheel_recv_thread->detach();
  91. LOG(INFO) << "created wheel msg receiving and sending threads";
  92. m_cond_exit.Notify(false);
  93. m_update_thread = new std::thread(cloud_merge_update, this);
  94. m_update_thread->detach();
  95. LOG(INFO) << "created cloud merge thread";
  96. LOG(INFO) << "fence this: "<< this;
  97. mb_initialized = true;
  98. return Error_manager(Error_code::SUCCESS);
  99. }
  100. /**
  101. * 无参构造
  102. * */
  103. Fence_controller::Fence_controller(Verify_result* verify_handle) : mb_initialized(0),
  104. m_update_thread(0),
  105. m_wheel_recv_thread(0),
  106. m_wheel_send_thread(0),
  107. mp_verify_result_tool(0)
  108. {
  109. m_lidars_vector.clear();
  110. m_region_workers_vector.clear();
  111. if(verify_handle!=0)
  112. mp_verify_result_tool = verify_handle;
  113. }
  114. /**
  115. * 析构函数
  116. * */
  117. Fence_controller::~Fence_controller()
  118. {
  119. m_cond_exit.Notify(true);
  120. m_cond_wheel_exit.Notify(true);
  121. if (m_update_thread)
  122. {
  123. if (m_update_thread->joinable())
  124. {
  125. m_update_thread->join();
  126. }
  127. delete m_update_thread;
  128. m_update_thread = 0;
  129. }
  130. LOG(INFO) << "exit update cloud thread";
  131. if (m_wheel_recv_thread)
  132. {
  133. if (m_wheel_recv_thread->joinable())
  134. {
  135. m_wheel_recv_thread->join();
  136. }
  137. delete m_wheel_recv_thread;
  138. m_wheel_recv_thread = 0;
  139. }
  140. LOG(INFO) << "exit receive wheel msg thread";
  141. if (m_wheel_send_thread)
  142. {
  143. if (m_wheel_send_thread->joinable())
  144. {
  145. m_wheel_send_thread->join();
  146. }
  147. delete m_wheel_send_thread;
  148. m_wheel_send_thread = 0;
  149. }
  150. LOG(INFO) << "exit send wheel result thread";
  151. // delete lidar instances
  152. for (int i = 0; i < m_lidars_vector.size(); ++i)
  153. {
  154. if (m_lidars_vector[i])
  155. {
  156. delete m_lidars_vector[i];
  157. m_lidars_vector[i] = 0;
  158. }
  159. }
  160. LOG(INFO) << "exit lidar handlers";
  161. // delete region_detector instances
  162. for (int j = 0; j < m_region_workers_vector.size(); ++j)
  163. {
  164. if (m_region_workers_vector[j])
  165. {
  166. delete m_region_workers_vector[j];
  167. m_region_workers_vector[j] = 0;
  168. }
  169. }
  170. LOG(INFO) << "exit region worker handles";
  171. //PlcData::Release();
  172. LOG(INFO) << "exit plc communicator";
  173. }
  174. /**
  175. * 外部获取点云
  176. * */
  177. Error_manager Fence_controller::get_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_out)
  178. {
  179. // LOG(INFO) << "try to get cloud";
  180. if (!mb_initialized)
  181. return Error_manager(Error_code::WJ_MANAGER_UNINITIALIZED);
  182. std::lock_guard<std::mutex> t_lck(m_cloud_mutex);
  183. // LOG(INFO) << "get cloud check cloud size";
  184. if (mp_merged_cloud->size() <= 0){
  185. return Error_manager(Error_code::WJ_MANAGER_EMPTY_CLOUD);
  186. }
  187. // LOG(INFO) << "get cloud push new cloud ";
  188. cloud_out->clear();
  189. cloud_out->operator+=(*mp_merged_cloud);
  190. LOG(INFO) << "cloud size: " << mp_merged_cloud->size() << ", " << cloud_out->size();
  191. return Error_manager(Error_code::SUCCESS);
  192. }
  193. /**
  194. * 获取当前软件整体状态,包括雷达、与plc连接状态
  195. * */
  196. Error_manager Fence_controller::get_current_status()
  197. {
  198. Error_manager code;
  199. // 1.检查初始化状态
  200. if (!mb_initialized)
  201. return Error_manager(Error_code::WJ_MANAGER_UNINITIALIZED);
  202. bool disconnected_lidar_exist = false;
  203. char buf[50];
  204. memset(buf, 0, 50);
  205. sprintf(buf, "lidar disconnected: ");
  206. // 2.检查雷达初始化与连接状态
  207. for (size_t i = 0; i < m_lidars_vector.size(); i++)
  208. {
  209. if (m_lidars_vector[i] == 0)
  210. {
  211. LOG(ERROR) << i << "号雷达检测到空雷达指针";
  212. return Error_manager(Error_code::POINTER_IS_NULL);
  213. }
  214. else if (!m_lidars_vector[i]->get_initialize_status())
  215. {
  216. LOG(WARNING) << i << "号雷达初始化未完成";
  217. return Error_manager(Error_code::WJ_MANAGER_UNINITIALIZED);
  218. }
  219. else if (!m_lidars_vector[i]->get_connection_status())
  220. {
  221. LOG(ERROR) << i << "号雷达检测到连接断开";
  222. sprintf(buf+strlen(buf), "%d ", i);
  223. disconnected_lidar_exist = true;
  224. }
  225. }
  226. if (disconnected_lidar_exist)
  227. {
  228. LOG(WARNING) << buf;
  229. return Error_manager(Error_code::WJ_MANAGER_LIDAR_DISCONNECTED);
  230. }
  231. // 3.检查plc状态
  232. if (mp_plc_data == 0)
  233. {
  234. LOG(ERROR) << "检测plc为空指针";
  235. return Error_manager(Error_code::POINTER_IS_NULL);
  236. }
  237. else if (!mp_plc_data->get_plc_status())
  238. {
  239. LOG(WARNING) << "检测到plc掉线";
  240. return Error_manager(Error_code::WJ_MANAGER_PLC_DISCONNECTED);
  241. }
  242. else
  243. {
  244. return Error_manager(Error_code::SUCCESS);
  245. }
  246. }
  247. /**
  248. * 获取controller初始化状态
  249. * */
  250. bool Fence_controller::get_initialize_status()
  251. {
  252. return mb_initialized;
  253. }
  254. /**
  255. * 执行任务单
  256. * */
  257. Error_manager Fence_controller::execute_task(Task_Base* task)
  258. {
  259. // 参数合法性判断
  260. if(task == 0)
  261. return Error_manager(Error_code::WJ_LIDAR_TASK_EMPTY_TASK);
  262. if (task->get_task_type() != Task_type::WJ_TASK)
  263. {
  264. return Error_manager(Error_code::WJ_LIDAR_TASK_WRONG_TYPE,NORMAL,"电子围栏接收到非万集任务");
  265. }
  266. Wj_lidar_Task* task_temp = (Wj_lidar_Task*)task;
  267. wj_command command_temp;
  268. Error_manager code = task_temp->get_command(command_temp);
  269. if(code != SUCCESS)
  270. return code;
  271. int terminal_id = command_temp.terminal_id;
  272. if(terminal_id < 0)
  273. {
  274. return Error_manager(Error_code::WJ_LIDAR_TASK_INVALID_TASK,NORMAL,"电子围栏接收到错误万集任务,id异常");
  275. }
  276. // 初始化重试次数
  277. int count = S_RETRY_TIMES > 0 ? S_RETRY_TIMES : 1;
  278. // 创建保存结果容器
  279. wj_measure_result wj_measure_temp;
  280. wj_measure_temp.terminal_id = terminal_id;
  281. wj_measure_temp.correctness = false;
  282. std::lock_guard<std::mutex> t_lck(m_cloud_mutex);
  283. while(count-->0 && !task_temp->get_result_flag()){
  284. for (int i = 0; i < m_region_workers_vector.size(); ++i)
  285. {
  286. if (m_region_workers_vector[i]->get_id() == terminal_id)
  287. {
  288. char cloud_txt_filename[255];
  289. memset(cloud_txt_filename, 0, 255);
  290. char whole_filename[255];
  291. memset(whole_filename, 0, 255);
  292. bool correctness = false;
  293. LOG(INFO) << "--------callback find terminal------" << terminal_id;
  294. double x = 0, y = 0, c = 0, wheelbase = 0, width = 0,front_theta=0;
  295. // 获取最新点云并保存到total_cloud中
  296. pcl::PointCloud<pcl::PointXYZ>::Ptr total_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  297. bool has_few_cloud = false;
  298. for (int i = 0; i < m_lidars_vector.size(); ++i)
  299. {
  300. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
  301. if (m_lidars_vector[i]->get_cloud(cloud, command_temp.command_time, command_temp.timeout_in_milliseconds) == SUCCESS)
  302. {
  303. total_cloud->operator+=(*cloud);
  304. // added yc yct, 区域四角雷达是否有点融合判断
  305. std::string t_laser_ip = m_lidars_vector[i]->get_ip();
  306. int t_laser_id = std::stoi(t_laser_ip.substr(t_laser_ip.size()-2));
  307. if(t_laser_id == terminal_id+1 || t_laser_id == terminal_id+2||t_laser_id == terminal_id+8||t_laser_id == terminal_id+9)
  308. {
  309. has_few_cloud |= cloud->size() <= 5;
  310. }
  311. }
  312. }
  313. LOG(INFO) << "--------callback get cloud, size: " << total_cloud->size();
  314. // 获取检测结果
  315. Error_manager code = m_region_workers_vector[i]->get_wheel_result(total_cloud, x, y, c, wheelbase, width,front_theta);
  316. time_t tt = time(0);
  317. struct tm *tc = localtime(&tt);
  318. char buf[255] = {0};
  319. memset(buf, 0, 255);
  320. sprintf(buf, "%d-%02d-%02d_%02d:%02d:%02d", tc->tm_year + 1900,
  321. tc->tm_mon + 1, tc->tm_mday, tc->tm_hour, tc->tm_min, tc->tm_sec);
  322. // 根据是否成功生成对应文件名
  323. if (code == SUCCESS)
  324. {
  325. correctness = true;
  326. sprintf(cloud_txt_filename, "/%s.txt", buf);
  327. }
  328. else
  329. {
  330. LOG(WARNING) << "get wheel result failed: " << code.to_string();
  331. correctness = false;
  332. sprintf(cloud_txt_filename, "/%s%s.txt", buf, "_failed");
  333. }
  334. // save cloud txt
  335. if (m_wj_manager_param.has_fence_data_path() && m_wj_manager_param.fence_data_path() != "")
  336. {
  337. PathCreator path_creator;
  338. path_creator.CreateDatePath(m_wj_manager_param.fence_data_path(), false);
  339. sprintf(whole_filename, "%s%s", path_creator.GetCurPath().c_str(), cloud_txt_filename);
  340. save_cloud_txt(whole_filename, total_cloud);
  341. }
  342. wj_measure_temp.x = x * 1000.0;
  343. wj_measure_temp.y = y * 1000.0;
  344. wj_measure_temp.angle = c;
  345. wj_measure_temp.wheel_base = wheelbase*1000.0;
  346. wj_measure_temp.width = width * 1000.0;
  347. wj_measure_temp.correctness = correctness;
  348. // 20201109 added by yct. 6号车位机械累计误差,测量17407与机械手17370同位置,软件修正-15mm
  349. if(terminal_id == 5)
  350. {
  351. wj_measure_temp.x -= 15;
  352. }
  353. if (wj_measure_temp.correctness){
  354. // 20210527 added by yct. 一旦存在雷达没有点而结果正确,此时将结果改为错误
  355. Error_code ec=Error_code::SUCCESS;
  356. if(has_few_cloud)
  357. {
  358. wj_measure_temp.correctness = false;
  359. ec = Error_code::WJ_MANAGER_EMPTY_CLOUD;
  360. }
  361. task_temp->set_result(wj_measure_temp);
  362. task_temp->set_cloud(*total_cloud);
  363. char description[480] = {0};
  364. sprintf(description, "WJ center(%.1f, %.1f) size:(%.1f, %.1f) angle:%.2f %s",
  365. x * 1000.0, y * 1000.0, wheelbase * 1000.0, width * 1000.0, c, has_few_cloud?"存在空点云":"雷达正常");
  366. LOG(INFO) << description;
  367. return Error_manager(ec);
  368. }
  369. }
  370. }
  371. }
  372. task_temp->set_result(wj_measure_temp);
  373. return Error_manager(Error_code::WJ_LIDAR_TASK_MEASURE_FAILED);
  374. }
  375. /**
  376. * 点云拼接与区域状态更新线程函数
  377. * 默认点云获取超时时间为1秒
  378. * */
  379. void Fence_controller::cloud_merge_update(Fence_controller *fc)
  380. {
  381. // 句柄判空
  382. if (fc == 0)
  383. return;
  384. while (!fc->m_cond_exit.WaitFor(1))
  385. {
  386. // LOG(INFO) << "------- trying to update cloud ";
  387. // 加锁,依次获取最新点云并依次更新各区域状态
  388. // fc->m_cloud_mutex.lock();
  389. std::lock_guard<std::mutex> t_lck(fc->m_cloud_mutex);
  390. fc->mp_merged_cloud->clear();
  391. for (int i = 0; i < fc->m_lidars_vector.size(); ++i)
  392. {
  393. if(fc->m_lidars_vector[i] == 0)
  394. {
  395. LOG(WARNING) << "No " << i << " wj lidar, null pointer";
  396. continue;
  397. }
  398. if(!fc->m_lidars_vector[i]->get_initialize_status())
  399. {
  400. // LOG(WARNING) << "No " << i << " wj lidar, uninitialized";
  401. continue;
  402. }
  403. if(!fc->m_lidars_vector[i]->get_connection_status())
  404. {
  405. // LOG(WARNING) << "No " << i << " wj lidar, disconnected";
  406. continue;
  407. }
  408. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
  409. Error_manager code = fc->m_lidars_vector[i]->get_cloud(cloud, std::chrono::steady_clock::now(), 1000);
  410. if (code == SUCCESS)
  411. {
  412. fc->mp_merged_cloud->operator+=(*cloud);
  413. // LOG(INFO) << "No " << i << " wj lidar, get cloud size: " << fc->mp_merged_cloud->size();
  414. }
  415. else
  416. {
  417. LOG(WARNING) << "No " << i << " wj lidar, get cloud failed. " << code.to_string();
  418. }
  419. }
  420. if (fc->mp_merged_cloud->size() > 0)
  421. {
  422. // LOG(INFO) << "trying to update cloud in region";
  423. for (int i = 0; i < fc->m_region_workers_vector.size(); ++i)
  424. {
  425. fc->m_region_workers_vector[i]->update_cloud(fc->mp_merged_cloud);
  426. }
  427. }
  428. // fc->m_cloud_mutex.unlock();
  429. }
  430. }
  431. /**
  432. * 轮距计算任务消息接收线程函数
  433. * */
  434. void Fence_controller::wheel_msg_recv_thread(Fence_controller *fc)
  435. {
  436. // 句柄判空
  437. if (fc == 0)
  438. return;
  439. while (!fc->m_cond_wheel_exit.WaitFor(1))
  440. {
  441. if (fc->m_wheel_soc)
  442. {
  443. // LOG(INFO) << "------- trying to recv msg ";
  444. nnxx::message_control *c1 = new nnxx::message_control();
  445. fc->m_mutex_wheel_handling.lock();
  446. auto m1 = fc->m_wheel_soc.recv(1, *c1);
  447. fc->m_mutex_wheel_handling.unlock();
  448. // 接收到消息则放入任务队列
  449. if (!m1.empty())
  450. {
  451. MsgTask task;
  452. task.cmd = nnxx::to_string(m1);
  453. task.sock_controller = c1;
  454. fc->m_msg_queue.push(task);
  455. LOG(INFO) << "-------recv msg " << task.cmd.c_str() << "-------";
  456. }
  457. if(c1 != nullptr)
  458. {
  459. delete c1;
  460. }
  461. }
  462. }
  463. LOG(INFO) << "任务消息接收线程退出";
  464. }
  465. // /**
  466. // * 电子围栏主动测量函数
  467. // * */
  468. // Error_manager Fence_controller::wj_fence_measure()
  469. // {
  470. // }
  471. /**
  472. * 轮距计算任务处理线程
  473. * */
  474. #include "globalmsg.pb.h"
  475. void Fence_controller::wheel_msg_handling_thread(Fence_controller *fc)
  476. {
  477. // 句柄判空
  478. if (fc == 0)
  479. return;
  480. while (!fc->m_cond_wheel_exit.WaitFor(1))
  481. {
  482. // LOG(INFO) << "------- trying to handle msg ";
  483. // 初始化当前允许重测次数
  484. int count = fc->S_RETRY_TIMES > 0 ? fc->S_RETRY_TIMES : 1;
  485. MsgTask task;
  486. // 从队列中获取任务
  487. if (fc->m_msg_queue.try_pop(task))
  488. {
  489. // 初始化测量结果消息
  490. globalmsg::resultInfo result;
  491. time_t tt = time(0);
  492. struct tm *tc = localtime(&tt);
  493. char buf[255] = {0};
  494. memset(buf, 0, 255);
  495. sprintf(buf, "%d-%02d-%02d_%02d:%02d:%02d", tc->tm_year + 1900,
  496. tc->tm_mon + 1, tc->tm_mday, tc->tm_hour, tc->tm_min, tc->tm_sec);
  497. result.set_time(buf);
  498. result.set_correctness(false);
  499. // 解析任务指令
  500. if (task.cmd.size() > 8 && task.cmd.substr(0, 8) == "Terminal")
  501. {
  502. int terminal_id = -1;
  503. try
  504. {
  505. terminal_id = std::stoi(task.cmd.substr(8, task.cmd.length() - 8).c_str());
  506. }
  507. catch (std::exception const &e)
  508. {
  509. LOG(WARNING) << e.what() << ", 消息解析失败,无法找到对应id号";
  510. continue;
  511. }
  512. LOG(INFO) << "handling msg from terminal id: " << terminal_id;
  513. std::lock_guard<std::mutex> t_lck(fc->m_cloud_mutex);
  514. while (count-- >= 0 && !result.correctness())
  515. {
  516. LOG(INFO) << "times :" << count;
  517. // 寻找到对应区域
  518. for (int i = 0; i < fc->m_region_workers_vector.size(); ++i)
  519. {
  520. if (terminal_id >= 0 && fc->m_region_workers_vector[i]->get_id() == terminal_id)
  521. {
  522. LOG(INFO) << "--------callback find terminal------" << terminal_id;
  523. double x = 0, y = 0, c = 0, wheelbase = 0, width = 0,front_theta=0;
  524. // 获取最新点云并保存到total_cloud中
  525. // fc->m_cloud_mutex.lock();
  526. pcl::PointCloud<pcl::PointXYZ>::Ptr total_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  527. for (int i = 0; i < fc->m_lidars_vector.size(); ++i)
  528. {
  529. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
  530. if (fc->m_lidars_vector[i]->get_cloud(cloud, std::chrono::steady_clock::now()) == SUCCESS)
  531. {
  532. total_cloud->operator+=(*cloud);
  533. }
  534. }
  535. // fc->m_cloud_mutex.unlock();
  536. LOG(INFO) << "--------callback get cloud, size: " << total_cloud->size();
  537. char cloud_txt_filename[255];
  538. memset(cloud_txt_filename, 0, 255);
  539. char whole_filename[255];
  540. memset(whole_filename, 0, 255);
  541. // 获取检测结果
  542. Error_manager code = fc->m_region_workers_vector[i]->get_wheel_result(total_cloud, x, y, c, wheelbase, width,front_theta);
  543. // 根据是否成功生成对应文件名
  544. if (code == SUCCESS)
  545. {
  546. result.set_correctness(true);
  547. sprintf(cloud_txt_filename, "/%s.txt", result.time().c_str());
  548. }
  549. else
  550. {
  551. LOG(WARNING) << "get wheel result failed: " << code.to_string();
  552. result.set_correctness(false);
  553. sprintf(cloud_txt_filename, "/%s%s.txt", result.time().c_str(), "_failed");
  554. }
  555. // save cloud txt
  556. if (fc->m_wj_manager_param.has_fence_data_path() && fc->m_wj_manager_param.fence_data_path() != "")
  557. {
  558. PathCreator path_creator;
  559. path_creator.CreateDatePath(fc->m_wj_manager_param.fence_data_path(), false);
  560. sprintf(whole_filename, "%s%s", path_creator.GetCurPath().c_str(), cloud_txt_filename);
  561. fc->save_cloud_txt(whole_filename, total_cloud);
  562. LOG(INFO) << " save cloud " << whole_filename;
  563. }
  564. LOG(INFO) << "--------callback get result------";
  565. result.set_x(x * 1000.0);
  566. result.set_y(y * 1000.0);
  567. result.set_c(c);
  568. result.set_wheel_base(wheelbase * 1000.0);
  569. result.set_width(width * 1000.0);
  570. result.set_front_theta(front_theta*180.0/M_PI);
  571. if (result.correctness())
  572. break;
  573. }
  574. }
  575. }
  576. }
  577. std::string result_str = result.SerializeAsString();
  578. LOG(INFO) << "--------callback serialized: \n"
  579. << result.DebugString() << "------";
  580. fc->m_mutex_wheel_handling.lock();
  581. if (fc->m_wheel_soc)
  582. {
  583. fc->m_wheel_soc.send(result_str.data(), result_str.length(), 0,
  584. std::move(*task.sock_controller));
  585. LOG(INFO) << "------- callback msg sent -------";
  586. }
  587. fc->m_mutex_wheel_handling.unlock();
  588. delete task.sock_controller;
  589. }
  590. }
  591. }