velodyne_lidar_device.cpp 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650
  1. #include "velodyne_lidar_device.h"
  2. // 万集雷达封装类构造函数
  3. Velodyne_lidar_device::Velodyne_lidar_device()
  4. {
  5. m_velodyne_lidar_device_status = E_UNKNOWN;
  6. mp_velodyne_lidar_scan_task = NULL;
  7. }
  8. // 万集雷达封装类析构函数
  9. Velodyne_lidar_device::~Velodyne_lidar_device()
  10. {
  11. uninit();
  12. }
  13. void Velodyne_lidar_device::dev_info_config(std::string model, int rpm)
  14. {
  15. double packet_rate; // packet frequency (Hz)
  16. std::string model_full_name;
  17. if ((model == "VLS128"))
  18. {
  19. packet_rate = 6253.9; // 3 firing cycles in a data packet. 3 x 53.3 μs = 0.1599 ms is the accumulation delay per packet.
  20. // 1 packet/0.1599 ms = 6253.9 packets/second
  21. model_full_name = model;
  22. }
  23. else if ((model == "64E_S2") ||
  24. (model == "64E_S2.1")) // generates 1333312 points per second
  25. { // 1 packet holds 384 points
  26. packet_rate = 3472.17; // 1333312 / 384
  27. model_full_name = std::string("HDL-") + model;
  28. }
  29. else if (model == "64E")
  30. {
  31. packet_rate = 2600.0;
  32. model_full_name = std::string("HDL-") + model;
  33. }
  34. else if (model == "64E_S3") // generates 2222220 points per second (half for strongest and half for lastest)
  35. { // 1 packet holds 384 points
  36. packet_rate = 5787.03; // 2222220 / 384
  37. model_full_name = std::string("HDL-") + model;
  38. }
  39. else if (model == "32E")
  40. {
  41. packet_rate = 1808.0;
  42. model_full_name = std::string("HDL-") + model;
  43. }
  44. else if (model == "32C")
  45. {
  46. packet_rate = 1507.0;
  47. model_full_name = std::string("VLP-") + model;
  48. }
  49. else if (model == "VLP16")
  50. {
  51. packet_rate = 754; // 754 Packets/Second for Last or Strongest mode 1508 for dual (VLP-16 User Manual)
  52. model_full_name = "VLP-16";
  53. }
  54. else
  55. {
  56. LOG(WARNING) << "unknown Velodyne LIDAR model: " << model;
  57. packet_rate = 2600.0;
  58. }
  59. std::string deviceName(std::string("Velodyne ") + model_full_name);
  60. LOG(INFO) << deviceName << " rotating at " << rpm << " RPM";
  61. double frequency = (rpm / 60.0); // expected Hz rate
  62. // default number of packets for each scan is a single revolution
  63. // (fractions rounded up)
  64. m_num_packet_per_scan = (int)ceil(packet_rate / frequency);
  65. LOG(INFO) << "publishing " << m_num_packet_per_scan << " packets per scan";
  66. }
  67. // 初始化
  68. Error_manager Velodyne_lidar_device::init(velodyne::velodyneLidarParams params)
  69. {
  70. Error_manager t_error;
  71. LOG(INFO) << " Velodyne_lidar_device::init " << this;
  72. m_num_packet_inside = 0;
  73. dev_info_config(params.model(), params.rpm());
  74. m_velodyne_lidar_device_status = E_UNKNOWN;
  75. m_velodyne_socket_status = E_UNKNOWN;
  76. m_velodyne_protocol_status = E_UNKNOWN;
  77. // 设置雷达内参矩阵
  78. Eigen::AngleAxisd rot_x = Eigen::AngleAxisd(params.calib().r(), Eigen::Vector3d::UnitX());
  79. Eigen::AngleAxisd rot_y = Eigen::AngleAxisd(params.calib().p(), Eigen::Vector3d::UnitY());
  80. Eigen::AngleAxisd rot_z = Eigen::AngleAxisd(params.calib().y(), Eigen::Vector3d::UnitZ());
  81. Eigen::Vector3d trans(params.calib().cx(), params.calib().cy(), params.calib().cz());
  82. m_calib_matrix << rot_x.toRotationMatrix() * rot_y.toRotationMatrix() * rot_z.toRotationMatrix(), trans, 0.0, 0.0, 0.0, 1.0;
  83. //唤醒队列
  84. m_communication_data_queue.wake_queue();
  85. //初始化通信协议
  86. t_error = m_protocol.setup(params.ip(), params.calibrationfile(), params.max_range(), params.min_range(), params.min_angle(), params.max_angle()) == true ? SUCCESS : Error_manager(PARAMETER_ERROR, MINOR_ERROR, "protocol parameter error");
  87. if (t_error != SUCCESS)
  88. {
  89. return t_error;
  90. }
  91. m_velodyne_protocol_status = E_READY;
  92. //初始化雷达通信模块
  93. std::string t_ip = params.ip();
  94. int t_port = params.port();
  95. t_error = m_input_socket.init(t_ip, t_port) == true ? SUCCESS : Error_manager(VELODYNE_LIDAR_CONNECT_FAILED, MINOR_ERROR, "socket connect failed");
  96. if (t_error != SUCCESS)
  97. {
  98. return t_error;
  99. }
  100. m_velodyne_socket_status = E_READY;
  101. m_capture_condition.reset(false, false, true);
  102. mp_capture_thread = new std::thread(&Velodyne_lidar_device::capture_thread_fun, this);
  103. m_parse_condition.reset(false, false, false);
  104. mp_parse_thread = new std::thread(&Velodyne_lidar_device::parse_thread_fun, this);
  105. //启动 内部线程。默认wait。
  106. m_execute_condition.reset(false, false, false);
  107. mp_execute_thread = new std::thread(&Velodyne_lidar_device::execute_thread_fun, this);
  108. m_velodyne_lidar_device_status = E_READY;
  109. return t_error;
  110. }
  111. //反初始化
  112. Error_manager Velodyne_lidar_device::uninit()
  113. {
  114. //终止队列,防止 wait_and_pop 阻塞线程。
  115. m_communication_data_queue.termination_queue();
  116. if (mp_capture_thread)
  117. {
  118. m_capture_condition.kill_all();
  119. }
  120. if (mp_capture_thread)
  121. {
  122. mp_capture_thread->join();
  123. delete mp_capture_thread;
  124. mp_capture_thread = NULL;
  125. }
  126. if (mp_parse_thread)
  127. {
  128. m_parse_condition.kill_all();
  129. }
  130. if (mp_parse_thread)
  131. {
  132. mp_parse_thread->join();
  133. delete mp_parse_thread;
  134. mp_parse_thread = NULL;
  135. }
  136. //关闭线程
  137. if (mp_execute_thread)
  138. {
  139. m_execute_condition.kill_all();
  140. }
  141. //回收线程的资源
  142. if (mp_execute_thread)
  143. {
  144. mp_execute_thread->join();
  145. delete mp_execute_thread;
  146. mp_execute_thread = NULL;
  147. }
  148. m_input_socket.uninit();
  149. //清空队列
  150. m_communication_data_queue.clear_and_delete();
  151. if (m_velodyne_lidar_device_status != E_FAULT)
  152. {
  153. m_velodyne_lidar_device_status = E_UNKNOWN;
  154. }
  155. return Error_code::SUCCESS;
  156. }
  157. //对外的接口函数,负责接受并处理任务单,
  158. Error_manager Velodyne_lidar_device::execute_task(Task_Base *p_velodyne_lidar_scan_task)
  159. {
  160. LOG(INFO) << " ---Laser_manager::execute_task run--- " << this;
  161. Error_manager t_error;
  162. Error_manager t_result;
  163. //检查指针
  164. if (p_velodyne_lidar_scan_task == NULL)
  165. {
  166. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  167. "Velodyne_lidar_device::execute_task failed, POINTER_IS_NULL");
  168. }
  169. //检查任务类型,
  170. if (p_velodyne_lidar_scan_task->get_task_type() != VELODYNE_LIDAR_SCAN)
  171. {
  172. return Error_manager(Error_code::VELODYNE_LIDAR_DEVICE_TASK_TYPE_ERROR, Error_level::MINOR_ERROR,
  173. " task type error != VELODYNE_LIDAR_SCAN ");
  174. }
  175. //检查接收方的状态
  176. t_error = check_status();
  177. if (t_error != SUCCESS)
  178. {
  179. t_result.compare_and_cover_error(t_error);
  180. }
  181. else
  182. {
  183. //接受任务,并将任务的状态改为TASK_SIGNED已签收
  184. mp_velodyne_lidar_scan_task = (Velodyne_lidar_scan_task *)p_velodyne_lidar_scan_task;
  185. mp_velodyne_lidar_scan_task->set_task_statu(TASK_SIGNED);
  186. //检查消息内容是否正确,
  187. //检查三维点云指针
  188. if (mp_velodyne_lidar_scan_task->get_task_point_cloud().get() == NULL)
  189. {
  190. t_error.error_manager_reset(Error_code::POINTER_IS_NULL,
  191. Error_level::MINOR_ERROR,
  192. "execute_task mp_task_point_cloud is null");
  193. t_result.compare_and_cover_error(t_error);
  194. }
  195. else if (mp_velodyne_lidar_scan_task->get_task_cloud_lock() == NULL)
  196. {
  197. t_error.error_manager_reset(Error_code::POINTER_IS_NULL,
  198. Error_level::MINOR_ERROR,
  199. "execute_task mp_task_cloud_lock is null");
  200. t_result.compare_and_cover_error(t_error);
  201. }
  202. else
  203. {
  204. m_velodyne_lidar_device_status = E_BUSY;
  205. //启动雷达管理模块,的核心工作线程
  206. m_execute_condition.notify_all(true);
  207. //通知 thread_work 子线程启动。
  208. //将任务的状态改为 TASK_WORKING 处理中
  209. mp_velodyne_lidar_scan_task->set_task_statu(TASK_WORKING);
  210. }
  211. //return 之前要填充任务单里面的错误码.
  212. if (t_result != Error_code::SUCCESS)
  213. {
  214. //忽略轻微故障
  215. if (t_result.get_error_level() >= Error_level::MINOR_ERROR)
  216. {
  217. //将任务的状态改为 TASK_ERROR 结束错误
  218. mp_velodyne_lidar_scan_task->set_task_statu(TASK_ERROR);
  219. }
  220. //返回错误码
  221. mp_velodyne_lidar_scan_task->compare_and_cover_task_error_manager(t_result);
  222. }
  223. }
  224. return t_result;
  225. }
  226. //检查雷达状态,是否正常运行
  227. Error_manager Velodyne_lidar_device::check_status()
  228. {
  229. updata_status();
  230. if (m_velodyne_lidar_device_status == E_READY)
  231. {
  232. return Error_code::SUCCESS;
  233. }
  234. else if (m_velodyne_lidar_device_status == E_BUSY)
  235. {
  236. return Error_manager(Error_code::VELODYNE_LIDAR_DEVICE_STATUS_BUSY, Error_level::NEGLIGIBLE_ERROR,
  237. " Velodyne_lidar_device::check_status() error ");
  238. }
  239. else
  240. {
  241. return Error_manager(Error_code::VELODYNE_LIDAR_DEVICE_STATUS_ERROR, Error_level::MINOR_ERROR,
  242. " Velodyne_lidar_device::check_status() error ");
  243. }
  244. return Error_code::SUCCESS;
  245. }
  246. //结束任务单,里面会根据任务的故障等级修正雷达管理模块的状态和任务单的状态
  247. Error_manager Velodyne_lidar_device::end_task()
  248. {
  249. m_execute_condition.notify_all(false);
  250. if (m_velodyne_lidar_device_status == E_BUSY)
  251. {
  252. m_velodyne_lidar_device_status = E_READY;
  253. }
  254. //else 状态不变
  255. //在结束任务单时,将雷达任务状态改为 TASK_OVER 已结束
  256. if (mp_velodyne_lidar_scan_task != NULL)
  257. {
  258. //判断任务单的错误等级,
  259. if (mp_velodyne_lidar_scan_task->get_task_error_manager().get_error_level() < Error_level::MINOR_ERROR)
  260. {
  261. //强制改为TASK_OVER,不管它当前在做什么。
  262. mp_velodyne_lidar_scan_task->set_task_statu(TASK_OVER);
  263. }
  264. else
  265. {
  266. //强制改为 TASK_ERROR,不管它当前在做什么。
  267. mp_velodyne_lidar_scan_task->set_task_statu(TASK_ERROR);
  268. }
  269. }
  270. return Error_code::SUCCESS;
  271. }
  272. //取消任务单,由发送方提前取消任务单
  273. Error_manager Velodyne_lidar_device::cancel_task(Task_Base *p_wanji_lidar_scan_task)
  274. {
  275. if (p_wanji_lidar_scan_task == mp_velodyne_lidar_scan_task)
  276. {
  277. m_execute_condition.notify_all(false);
  278. if (m_velodyne_lidar_device_status == E_BUSY)
  279. {
  280. m_velodyne_lidar_device_status = E_READY;
  281. }
  282. //else 状态不变
  283. //强制改为 TASK_DEAD,不管它当前在做什么。
  284. mp_velodyne_lidar_scan_task->set_task_statu(TASK_DEAD);
  285. return Error_code::SUCCESS;
  286. }
  287. else
  288. {
  289. return Error_manager(Error_code::PARAMETER_ERROR, Error_level::MINOR_ERROR,
  290. " Velodyne_lidar_device::cancel_task PARAMRTER ERROR ");
  291. }
  292. }
  293. //判断是否为待机,如果已经准备好,则可以执行任务。
  294. bool Velodyne_lidar_device::is_ready()
  295. {
  296. updata_status();
  297. return m_velodyne_lidar_device_status == E_READY;
  298. }
  299. //外部调用获取新的点云, 获取指令时间之后的点云, 如果没有就会等待点云刷新, 直到超时, (内置while)
  300. Error_manager Velodyne_lidar_device::get_new_cloud_and_wait(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  301. std::chrono::steady_clock::time_point command_time, int timeout_ms)
  302. {
  303. if (p_mutex == NULL || p_cloud.get() == NULL)
  304. {
  305. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  306. " POINTER IS NULL ");
  307. }
  308. //判断是否超时
  309. while (std::chrono::steady_clock::now() - command_time < std::chrono::milliseconds(timeout_ms))
  310. {
  311. //获取指令时间之后的点云, 如果没有就会循环
  312. if (m_parse_ring_time > command_time)
  313. {
  314. std::unique_lock<std::mutex> lck(*p_mutex);
  315. {
  316. std::lock_guard<std::mutex> lck(m_cloud_mutex);
  317. if (m_ring_cloud.size() <= 0)
  318. return VELODYNE_LIDAR_DEVICE_NO_CLOUD;
  319. for (size_t i = 0; i < m_ring_cloud.size(); i++)
  320. {
  321. p_cloud->push_back(pcl::PointXYZ(m_ring_cloud[i].x, m_ring_cloud[i].y, m_ring_cloud[i].z));
  322. }
  323. }
  324. return SUCCESS;
  325. }
  326. //else 等待下一次数据更新
  327. //等1ms
  328. std::this_thread::sleep_for(std::chrono::milliseconds(1));
  329. }
  330. //超时退出就报错
  331. return Error_manager(Error_code::WJ_LIDAR_GET_CLOUD_TIMEOUT, Error_level::MINOR_ERROR,
  332. " Velodyne_lidar_device::get_new_cloud_and_wait error ");
  333. }
  334. //外部调用获取当前点云, 获取指令时间之后的点云, 如果没有就会报错, 不会等待
  335. Error_manager Velodyne_lidar_device::get_current_cloud(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  336. std::chrono::steady_clock::time_point command_time)
  337. {
  338. if (p_mutex == NULL || p_cloud.get() == NULL)
  339. {
  340. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  341. " POINTER IS NULL ");
  342. }
  343. //获取指令时间之后的点云, 如果没有就会报错, 不会等待
  344. if (m_parse_time > command_time)
  345. {
  346. std::unique_lock<std::mutex> lck(*p_mutex);
  347. {
  348. std::lock_guard<std::mutex> lck(m_cloud_mutex);
  349. if (m_cloud_buf.size() <= 0)
  350. return VELODYNE_LIDAR_DEVICE_NO_CLOUD;
  351. for (size_t i = 0; i < m_cloud_buf.size(); i++)
  352. {
  353. p_cloud->push_back(pcl::PointXYZ(m_cloud_buf[i].x, m_cloud_buf[i].y, m_cloud_buf[i].z));
  354. }
  355. }
  356. return SUCCESS;
  357. }
  358. else
  359. {
  360. return Error_manager(Error_code::VELODYNE_LIDAR_DEVICE_NO_CLOUD, Error_level::MINOR_ERROR,
  361. " Velodyne_lidar_device::get_current_cloud error ");
  362. }
  363. }
  364. //外部调用获取最新的点云, 如果没有就会报错, 不会等待
  365. Error_manager Velodyne_lidar_device::get_last_cloud(std::mutex *p_mutex, pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  366. std::chrono::steady_clock::time_point command_time)
  367. {
  368. if (p_mutex == NULL || p_cloud.get() == NULL)
  369. {
  370. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  371. " POINTER IS NULL ");
  372. }
  373. if (m_parse_ring_time > command_time)
  374. {
  375. std::unique_lock<std::mutex> lck(*p_mutex);
  376. {
  377. std::lock_guard<std::mutex> lck(m_cloud_mutex);
  378. if (m_ring_cloud.size() <= 0)
  379. return VELODYNE_LIDAR_DEVICE_NO_CLOUD;
  380. for (size_t i = 0; i < m_ring_cloud.size(); i++)
  381. {
  382. p_cloud->push_back(pcl::PointXYZ(m_ring_cloud[i].x, m_ring_cloud[i].y, m_ring_cloud[i].z));
  383. }
  384. }
  385. return SUCCESS;
  386. }
  387. else
  388. {
  389. return Error_manager(Error_code::VELODYNE_LIDAR_DEVICE_NO_CLOUD, Error_level::MINOR_ERROR,
  390. " Velodyne_lidar_device::get_current_cloud error ");
  391. }
  392. }
  393. //外部调用获取最新的点云, 获取指令时间往前一个周期内的点云, 如果没有就会报错, 不会等待
  394. //注:函数内部不加锁, 由外部统一加锁.
  395. Error_manager Velodyne_lidar_device::get_last_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr p_cloud,
  396. std::chrono::steady_clock::time_point command_time)
  397. {
  398. if (p_cloud.get() == NULL)
  399. {
  400. return Error_manager(Error_code::POINTER_IS_NULL, Error_level::MINOR_ERROR,
  401. " POINTER IS NULL ");
  402. }
  403. if (m_parse_ring_time > command_time)
  404. {
  405. std::lock_guard<std::mutex> lck(m_cloud_mutex);
  406. if (m_ring_cloud.size() <= 0)
  407. return VELODYNE_LIDAR_DEVICE_NO_CLOUD;
  408. for (size_t i = 0; i < m_ring_cloud.size(); i++)
  409. {
  410. p_cloud->push_back(pcl::PointXYZ(m_ring_cloud[i].x, m_ring_cloud[i].y, m_ring_cloud[i].z));
  411. }
  412. return SUCCESS;
  413. }
  414. else
  415. {
  416. return Error_manager(Error_code::VELODYNE_LIDAR_DEVICE_NO_CLOUD, Error_level::MINOR_ERROR,
  417. " Velodyne_lidar_device::get_current_cloud error ");
  418. }
  419. }
  420. Velodyne_lidar_device::Velodyne_lidar_device_status Velodyne_lidar_device::get_status()
  421. {
  422. updata_status();
  423. return m_velodyne_lidar_device_status;
  424. }
  425. void Velodyne_lidar_device::updata_status()
  426. {
  427. if (m_velodyne_socket_status == E_FAULT || m_velodyne_protocol_status == E_FAULT)
  428. {
  429. m_velodyne_lidar_device_status = E_FAULT;
  430. }
  431. if (m_velodyne_socket_status == E_DISCONNECT)
  432. {
  433. m_velodyne_lidar_device_status = E_DISCONNECT;
  434. }
  435. else if (m_velodyne_socket_status == E_READY && m_velodyne_protocol_status == E_READY)
  436. {
  437. if (m_execute_condition.get_pass_ever())
  438. {
  439. m_velodyne_lidar_device_status = E_BUSY;
  440. }
  441. else
  442. {
  443. m_velodyne_lidar_device_status = E_READY;
  444. }
  445. }
  446. else
  447. {
  448. m_velodyne_lidar_device_status = E_UNKNOWN;
  449. }
  450. }
  451. void Velodyne_lidar_device::capture_thread_fun()
  452. {
  453. LOG(INFO) << " Velodyne_lidar_device::capture_thread_fun() start " << this;
  454. Error_manager t_error;
  455. while (m_capture_condition.is_alive())
  456. {
  457. m_capture_condition.wait_for_millisecond(1);
  458. if (m_capture_condition.is_alive())
  459. {
  460. // socket状态正常才更新状态
  461. if (m_velodyne_socket_status == E_READY)
  462. m_velodyne_socket_status = E_BUSY;
  463. if (m_input_socket.getPacket(m_buf) == 0)
  464. {
  465. Binary_buf *tp_binary_buf = new Binary_buf(reinterpret_cast<char *>(m_buf), PACKET_SIZE);
  466. //将数据添加到队列中, 然后内存权限转交给队列.
  467. m_communication_data_queue.push(tp_binary_buf);
  468. m_capture_time = std::chrono::steady_clock::now();
  469. m_velodyne_socket_status = E_READY;
  470. }
  471. else
  472. {
  473. m_velodyne_socket_status = E_DISCONNECT;
  474. }
  475. // 队列有数据,激活解析线程
  476. if (m_communication_data_queue.size() > 0)
  477. m_parse_condition.notify_one(false, true);
  478. }
  479. }
  480. LOG(INFO) << " Velodyne_lidar_device::capture_thread_fun() end :" << this;
  481. return;
  482. }
  483. void Velodyne_lidar_device::parse_thread_fun()
  484. {
  485. LOG(INFO) << " Velodyne_lidar_device::parse_thread_fun() start " << this;
  486. Error_manager t_error;
  487. while (m_parse_condition.is_alive())
  488. {
  489. m_parse_condition.wait();
  490. if (m_parse_condition.is_alive())
  491. {
  492. if (m_velodyne_protocol_status == E_READY)
  493. m_velodyne_protocol_status = E_BUSY;
  494. if (m_protocol.isInitialized())
  495. {
  496. Binary_buf *buf = *m_communication_data_queue.wait_and_pop();
  497. if (buf != nullptr)
  498. {
  499. std::lock_guard<std::mutex> lck(m_cloud_mutex);
  500. m_protocol.unpack(reinterpret_cast<unsigned char *>(buf->get_buf()), m_cloud_buf);
  501. m_num_packet_inside++;
  502. m_parse_time = std::chrono::steady_clock::now();
  503. // 雷达掉线,清除不完整数据,不更新时间戳
  504. if (m_velodyne_socket_status != E_READY && m_velodyne_socket_status != E_BUSY)
  505. {
  506. m_num_packet_inside = 0;
  507. m_cloud_buf.clear();
  508. m_ring_cloud.clear();
  509. }
  510. else if (m_num_packet_inside >= m_num_packet_per_scan) // 一环数据填满,同时更新时间戳
  511. {
  512. m_num_packet_inside = 0;
  513. m_ring_cloud.clear();
  514. m_ring_cloud = m_cloud_buf;
  515. m_cloud_buf.clear();
  516. // 对环点云进行内参变换
  517. for (size_t i = 0; i < m_ring_cloud.size(); i++)
  518. {
  519. m_ring_cloud[i].transform(m_calib_matrix);
  520. }
  521. m_parse_ring_time = std::chrono::steady_clock::now();
  522. }
  523. }
  524. m_velodyne_protocol_status = E_READY;
  525. }
  526. else
  527. {
  528. m_velodyne_protocol_status = E_FAULT;
  529. }
  530. }
  531. }
  532. LOG(INFO) << " Velodyne_lidar_device::parse_thread_fun() end " << this;
  533. return;
  534. }
  535. //mp_laser_manager_thread 线程执行函数,
  536. //thread_work 内部线程负责获取点云结果
  537. void Velodyne_lidar_device::execute_thread_fun()
  538. {
  539. LOG(INFO) << " Velodyne_lidar_device::execute_thread_fun() start " << this;
  540. Error_manager t_error;
  541. //雷达管理的独立线程,负责控制管理所有的雷达。
  542. while (m_execute_condition.is_alive())
  543. {
  544. m_execute_condition.wait();
  545. if (m_execute_condition.is_alive())
  546. {
  547. std::this_thread::yield();
  548. if (mp_velodyne_lidar_scan_task == NULL)
  549. {
  550. //没有任务就忽略, 直接关闭线程
  551. m_velodyne_lidar_device_status = E_READY;
  552. m_execute_condition.notify_all(false);
  553. }
  554. else
  555. {
  556. if (mp_velodyne_lidar_scan_task->is_over_time())
  557. {
  558. t_error.error_manager_reset(TASK_TIMEOVER, MINOR_ERROR, "Velodyne_lidar_device::get_cloud_thread() TASK_TIMEOVER");
  559. mp_velodyne_lidar_scan_task->compare_and_cover_task_error_manager(t_error);
  560. //故障结束任务
  561. end_task();
  562. }
  563. else
  564. {
  565. //获取这个时间后面的点云.
  566. if (m_parse_ring_time > mp_velodyne_lidar_scan_task->get_command_time())
  567. {
  568. std::mutex *tp_mutex = mp_velodyne_lidar_scan_task->get_task_cloud_lock();
  569. pcl::PointCloud<pcl::PointXYZ>::Ptr tp_cloud = mp_velodyne_lidar_scan_task->get_task_point_cloud();
  570. {
  571. std::unique_lock<std::mutex> lck(*tp_mutex);
  572. {
  573. std::lock_guard<std::mutex> lck(m_cloud_mutex);
  574. for (size_t i = 0; i < m_ring_cloud.size(); i++)
  575. {
  576. tp_cloud->push_back(pcl::PointXYZ(m_ring_cloud[i].x, m_ring_cloud[i].y, m_ring_cloud[i].z));
  577. }
  578. }
  579. }
  580. mp_velodyne_lidar_scan_task->compare_and_cover_task_error_manager(t_error);
  581. //正常结束任务
  582. end_task();
  583. }
  584. else
  585. {
  586. //等1ms
  587. std::this_thread::sleep_for(std::chrono::milliseconds(1));
  588. }
  589. }
  590. }
  591. }
  592. }
  593. LOG(INFO) << " Velodyne_lidar_device::execute_thread_fun() end :" << this;
  594. return;
  595. }