lddc.cpp
Go to the documentation of this file.
1 //
2 // The MIT License (MIT)
3 //
4 // Copyright (c) 2019 Livox. All rights reserved.
5 //
6 // Permission is hereby granted, free of charge, to any person obtaining a copy
7 // of this software and associated documentation files (the "Software"), to deal
8 // in the Software without restriction, including without limitation the rights
9 // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
10 // copies of the Software, and to permit persons to whom the Software is
11 // furnished to do so, subject to the following conditions:
12 //
13 // The above copyright notice and this permission notice shall be included in
14 // all copies or substantial portions of the Software.
15 //
16 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
17 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
18 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
19 // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
20 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
21 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
22 // SOFTWARE.
23 //
24 
25 #include "lddc.h"
26 
27 #include <inttypes.h>
28 #include <math.h>
29 #include <stdint.h>
30 
31 #include <pcl_ros/point_cloud.h>
32 #include <ros/ros.h>
33 #include <rosbag/bag.h>
34 #include <sensor_msgs/Imu.h>
35 #include <sensor_msgs/PointCloud2.h>
36 
37 #include <livox_ros_driver/CustomMsg.h>
38 #include <livox_ros_driver/CustomPoint.h>
39 #include "lds_lidar.h"
40 #include "lds_lvx.h"
41 
42 namespace livox_ros {
43 
45 Lddc::Lddc(int format, int multi_topic, int data_src, int output_type,
46  double frq, std::string &frame_id, bool lidar_bag, bool imu_bag)
47  : transfer_format_(format),
48  use_multi_topic_(multi_topic),
49  data_src_(data_src),
50  output_type_(output_type),
51  publish_frq_(frq),
52  frame_id_(frame_id),
53  enable_lidar_bag_(lidar_bag),
54  enable_imu_bag_(imu_bag) {
56  lds_ = nullptr;
57  memset(private_pub_, 0, sizeof(private_pub_));
58  memset(private_imu_pub_, 0, sizeof(private_imu_pub_));
59  global_pub_ = nullptr;
60  global_imu_pub_ = nullptr;
61  cur_node_ = nullptr;
62  bag_ = nullptr;
63 };
64 
66  if (global_pub_) {
67  delete global_pub_;
68  }
69 
70  if (global_imu_pub_) {
71  delete global_imu_pub_;
72  }
73 
74  if (lds_) {
75  lds_->PrepareExit();
76  }
77 
78  for (uint32_t i = 0; i < kMaxSourceLidar; i++) {
79  if (private_pub_[i]) {
80  delete private_pub_[i];
81  }
82  }
83 
84  for (uint32_t i = 0; i < kMaxSourceLidar; i++) {
85  if (private_imu_pub_[i]) {
86  delete private_imu_pub_[i];
87  }
88  }
89 }
90 
92  uint64_t *start_time,
93  StoragePacket *storage_packet) {
94  QueuePrePop(queue, storage_packet);
95  uint64_t timestamp =
96  GetStoragePacketTimestamp(storage_packet, lidar->data_src);
97  uint32_t remaining_time = timestamp % publish_period_ns_;
98  uint32_t diff_time = publish_period_ns_ - remaining_time;
100  if (diff_time > (publish_period_ns_ / 4)) {
101  // ROS_INFO("0 : %u", diff_time);
102  *start_time = timestamp - remaining_time;
103  return 0;
104  } else if (diff_time <= lidar->packet_interval_max) {
105  *start_time = timestamp;
106  return 0;
107  } else {
109  // ROS_INFO("2 : %u", diff_time);
110  do {
111  if (QueueIsEmpty(queue)) {
112  break;
113  }
114  QueuePopUpdate(queue); /* skip packet */
115  QueuePrePop(queue, storage_packet);
116  uint32_t last_remaning_time = remaining_time;
117  timestamp = GetStoragePacketTimestamp(storage_packet, lidar->data_src);
118  remaining_time = timestamp % publish_period_ns_;
120  if (last_remaning_time > remaining_time) {
121  // ROS_INFO("Flip to another period, exit");
122  break;
123  }
124  diff_time = publish_period_ns_ - remaining_time;
125  } while (diff_time > lidar->packet_interval);
126 
127  /* the remaning packets in queue maybe not enough after skip */
128  return -1;
129  }
130 }
131 
132 void Lddc::InitPointcloud2MsgHeader(sensor_msgs::PointCloud2& cloud) {
133  cloud.header.frame_id.assign(frame_id_);
134  cloud.height = 1;
135  cloud.width = 0;
136  cloud.fields.resize(6);
137  cloud.fields[0].offset = 0;
138  cloud.fields[0].name = "x";
139  cloud.fields[0].count = 1;
140  cloud.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
141  cloud.fields[1].offset = 4;
142  cloud.fields[1].name = "y";
143  cloud.fields[1].count = 1;
144  cloud.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
145  cloud.fields[2].offset = 8;
146  cloud.fields[2].name = "z";
147  cloud.fields[2].count = 1;
148  cloud.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
149  cloud.fields[3].offset = 12;
150  cloud.fields[3].name = "intensity";
151  cloud.fields[3].count = 1;
152  cloud.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
153  cloud.fields[4].offset = 16;
154  cloud.fields[4].name = "tag";
155  cloud.fields[4].count = 1;
156  cloud.fields[4].datatype = sensor_msgs::PointField::UINT8;
157  cloud.fields[5].offset = 17;
158  cloud.fields[5].name = "line";
159  cloud.fields[5].count = 1;
160  cloud.fields[5].datatype = sensor_msgs::PointField::UINT8;
161  cloud.point_step = sizeof(LivoxPointXyzrtl);
162 }
163 
165  uint8_t handle) {
166  uint64_t timestamp = 0;
167  uint64_t last_timestamp = 0;
168  uint32_t published_packet = 0;
169 
170  StoragePacket storage_packet;
171  LidarDevice *lidar = &lds_->lidars_[handle];
172  if (GetPublishStartTime(lidar, queue, &last_timestamp, &storage_packet)) {
173  /* the remaning packets in queue maybe not enough after skip */
174  return 0;
175  }
176 
177  sensor_msgs::PointCloud2 cloud;
179  cloud.data.resize(packet_num * kMaxPointPerEthPacket *
180  sizeof(LivoxPointXyzrtl));
181  cloud.point_step = sizeof(LivoxPointXyzrtl);
182 
183  uint8_t *point_base = cloud.data.data();
184  uint8_t data_source = lidar->data_src;
185  uint32_t line_num = GetLaserLineNumber(lidar->info.type);
186  uint32_t echo_num = GetEchoNumPerPoint(lidar->raw_data_type);
187  uint32_t is_zero_packet = 0;
188  while ((published_packet < packet_num) && !QueueIsEmpty(queue)) {
189  QueuePrePop(queue, &storage_packet);
190  LivoxEthPacket *raw_packet =
191  reinterpret_cast<LivoxEthPacket *>(storage_packet.raw_data);
192  timestamp = GetStoragePacketTimestamp(&storage_packet, data_source);
193  int64_t packet_gap = timestamp - last_timestamp;
194  if ((packet_gap > lidar->packet_interval_max) &&
195  lidar->data_is_pubulished) {
196  // ROS_INFO("Lidar[%d] packet time interval is %ldns", handle,
197  // packet_gap);
198  if (kSourceLvxFile != data_source) {
199  timestamp = last_timestamp + lidar->packet_interval;
200  ZeroPointDataOfStoragePacket(&storage_packet);
201  is_zero_packet = 1;
202  }
203  }
205  if (!published_packet) {
206  cloud.header.stamp = ros::Time(timestamp / 1000000000.0);
207  }
208  uint32_t single_point_num = storage_packet.point_num * echo_num;
209 
210  if (kSourceLvxFile != data_source) {
211  PointConvertHandler pf_point_convert =
213  if (pf_point_convert) {
214  point_base = pf_point_convert(point_base, raw_packet,
215  lidar->extrinsic_parameter, line_num);
216  } else {
218  ROS_INFO("Lidar[%d] unkown packet type[%d]", handle,
219  raw_packet->data_type);
220  break;
221  }
222  } else {
223  point_base = LivoxPointToPxyzrtl(point_base, raw_packet,
224  lidar->extrinsic_parameter, line_num);
225  }
226 
227  if (!is_zero_packet) {
228  QueuePopUpdate(queue);
229  } else {
230  is_zero_packet = 0;
231  }
232  cloud.width += single_point_num;
233  ++published_packet;
234  last_timestamp = timestamp;
235  }
236  cloud.row_step = cloud.width * cloud.point_step;
237  cloud.is_bigendian = false;
238  cloud.is_dense = true;
239  cloud.data.resize(cloud.row_step);
240  ros::Publisher *p_publisher = Lddc::GetCurrentPublisher(handle);
241  if (kOutputToRos == output_type_) {
242  p_publisher->publish(cloud);
243  } else {
244  if (bag_ && enable_lidar_bag_) {
245  bag_->write(p_publisher->getTopic(), ros::Time(timestamp / 1000000000.0),
246  cloud);
247  }
248  }
249  if (!lidar->data_is_pubulished) {
250  lidar->data_is_pubulished = true;
251  }
252  return published_packet;
253 }
254 
255 void Lddc::FillPointsToPclMsg(PointCloud::Ptr& pcl_msg, \
256  LivoxPointXyzrtl* src_point, uint32_t num) {
257  LivoxPointXyzrtl* point_xyzrtl = (LivoxPointXyzrtl*)src_point;
258  for (uint32_t i = 0; i < num; i++) {
259  pcl::PointXYZI point;
260  point.x = point_xyzrtl->x;
261  point.y = point_xyzrtl->y;
262  point.z = point_xyzrtl->z;
263  point.intensity = point_xyzrtl->reflectivity;
264  ++point_xyzrtl;
265  pcl_msg->points.push_back(point);
266  }
267 }
268 
269 /* for pcl::pxyzi */
271  uint8_t handle) {
272  uint64_t timestamp = 0;
273  uint64_t last_timestamp = 0;
274  uint32_t published_packet = 0;
275 
276  StoragePacket storage_packet;
277  LidarDevice *lidar = &lds_->lidars_[handle];
278  if (GetPublishStartTime(lidar, queue, &last_timestamp, &storage_packet)) {
279  /* the remaning packets in queue maybe not enough after skip */
280  return 0;
281  }
282 
283  PointCloud::Ptr cloud(new PointCloud);
284  cloud->header.frame_id.assign(frame_id_);
285  cloud->height = 1;
286  cloud->width = 0;
287 
288  uint8_t point_buf[2048];
289  uint32_t is_zero_packet = 0;
290  uint8_t data_source = lidar->data_src;
291  uint32_t line_num = GetLaserLineNumber(lidar->info.type);
292  uint32_t echo_num = GetEchoNumPerPoint(lidar->raw_data_type);
293  while ((published_packet < packet_num) && !QueueIsEmpty(queue)) {
294  QueuePrePop(queue, &storage_packet);
295  LivoxEthPacket *raw_packet =
296  reinterpret_cast<LivoxEthPacket *>(storage_packet.raw_data);
297  timestamp = GetStoragePacketTimestamp(&storage_packet, data_source);
298  int64_t packet_gap = timestamp - last_timestamp;
299  if ((packet_gap > lidar->packet_interval_max) &&
300  lidar->data_is_pubulished) {
301  //ROS_INFO("Lidar[%d] packet time interval is %ldns", handle, packet_gap);
302  if (kSourceLvxFile != data_source) {
303  timestamp = last_timestamp + lidar->packet_interval;
304  ZeroPointDataOfStoragePacket(&storage_packet);
305  is_zero_packet = 1;
306  }
307  }
308  if (!published_packet) {
309  cloud->header.stamp = timestamp / 1000.0; // to pcl ros time stamp
310  }
311  uint32_t single_point_num = storage_packet.point_num * echo_num;
312 
313  if (kSourceLvxFile != data_source) {
314  PointConvertHandler pf_point_convert =
316  if (pf_point_convert) {
317  pf_point_convert(point_buf, raw_packet, lidar->extrinsic_parameter, \
318  line_num);
319  } else {
320  /* Skip the packet */
321  ROS_INFO("Lidar[%d] unkown packet type[%d]", handle,
322  raw_packet->data_type);
323  break;
324  }
325  } else {
326  LivoxPointToPxyzrtl(point_buf, raw_packet, lidar->extrinsic_parameter, \
327  line_num);
328  }
329  LivoxPointXyzrtl *dst_point = (LivoxPointXyzrtl *)point_buf;
330  FillPointsToPclMsg(cloud, dst_point, single_point_num);
331  if (!is_zero_packet) {
332  QueuePopUpdate(queue);
333  } else {
334  is_zero_packet = 0;
335  }
336  cloud->width += single_point_num;
337  ++published_packet;
338  last_timestamp = timestamp;
339  }
340 
341  ros::Publisher *p_publisher = Lddc::GetCurrentPublisher(handle);
342  if (kOutputToRos == output_type_) {
343  p_publisher->publish(cloud);
344  } else {
345  if (bag_ && enable_lidar_bag_) {
346  bag_->write(p_publisher->getTopic(), ros::Time(timestamp / 1000000000.0),
347  cloud);
348  }
349  }
350  if (!lidar->data_is_pubulished) {
351  lidar->data_is_pubulished = true;
352  }
353  return published_packet;
354 }
355 
356 void Lddc::FillPointsToCustomMsg(livox_ros_driver::CustomMsg& livox_msg, \
357  LivoxPointXyzrtl* src_point, uint32_t num, uint32_t offset_time, \
358  uint32_t point_interval, uint32_t echo_num) {
359  LivoxPointXyzrtl* point_xyzrtl = (LivoxPointXyzrtl*)src_point;
360  for (uint32_t i = 0; i < num; i++) {
361  livox_ros_driver::CustomPoint point;
362  if (echo_num > 1) {
363  point.offset_time = offset_time + (i / echo_num) * point_interval;
364  } else {
365  point.offset_time = offset_time + i * point_interval;
366  }
367  point.x = point_xyzrtl->x;
368  point.y = point_xyzrtl->y;
369  point.z = point_xyzrtl->z;
370  point.reflectivity = point_xyzrtl->reflectivity;
371  point.tag = point_xyzrtl->tag;
372  point.line = point_xyzrtl->line;
373  ++point_xyzrtl;
374  livox_msg.points.push_back(point);
375  }
376 }
377 
379  uint32_t packet_num, uint8_t handle) {
380  static uint32_t msg_seq = 0;
381  uint64_t timestamp = 0;
382  uint64_t last_timestamp = 0;
383 
384  StoragePacket storage_packet;
385  LidarDevice *lidar = &lds_->lidars_[handle];
386  if (GetPublishStartTime(lidar, queue, &last_timestamp, &storage_packet)) {
387  /* the remaning packets in queue maybe not enough after skip */
388  return 0;
389  }
390 
391  livox_ros_driver::CustomMsg livox_msg;
392  livox_msg.header.frame_id.assign(frame_id_);
393  livox_msg.header.seq = msg_seq;
394  ++msg_seq;
395  livox_msg.timebase = 0;
396  livox_msg.point_num = 0;
397  livox_msg.lidar_id = handle;
398 
399  uint8_t point_buf[2048];
400  uint8_t data_source = lds_->lidars_[handle].data_src;
401  uint32_t line_num = GetLaserLineNumber(lidar->info.type);
402  uint32_t echo_num = GetEchoNumPerPoint(lidar->raw_data_type);
403  uint32_t point_interval = GetPointInterval(lidar->info.type);
404  uint32_t published_packet = 0;
405  uint32_t packet_offset_time = 0;
406  uint32_t is_zero_packet = 0;
407  while (published_packet < packet_num) {
408  QueuePrePop(queue, &storage_packet);
409  LivoxEthPacket *raw_packet =
410  reinterpret_cast<LivoxEthPacket *>(storage_packet.raw_data);
411  timestamp = GetStoragePacketTimestamp(&storage_packet, data_source);
412  int64_t packet_gap = timestamp - last_timestamp;
413  if ((packet_gap > lidar->packet_interval_max) &&
414  lidar->data_is_pubulished) {
415  // ROS_INFO("Lidar[%d] packet time interval is %ldns", handle,
416  // packet_gap);
417  if (kSourceLvxFile != data_source) {
418  timestamp = last_timestamp + lidar->packet_interval;
419  ZeroPointDataOfStoragePacket(&storage_packet);
420  is_zero_packet = 1;
421  }
422  }
424  if (!published_packet) {
425  livox_msg.timebase = timestamp;
426  packet_offset_time = 0;
428  livox_msg.header.stamp = ros::Time(timestamp / 1000000000.0);
429  } else {
430  packet_offset_time = (uint32_t)(timestamp - livox_msg.timebase);
431  }
432  uint32_t single_point_num = storage_packet.point_num * echo_num;
433 
434  if (kSourceLvxFile != data_source) {
435  PointConvertHandler pf_point_convert =
437  if (pf_point_convert) {
438  pf_point_convert(point_buf, raw_packet, lidar->extrinsic_parameter, \
439  line_num);
440  } else {
441  /* Skip the packet */
442  ROS_INFO("Lidar[%d] unkown packet type[%d]", handle,
443  lidar->raw_data_type);
444  break;
445  }
446  } else {
447  LivoxPointToPxyzrtl(point_buf, raw_packet, lidar->extrinsic_parameter, \
448  line_num);
449  }
450  LivoxPointXyzrtl *dst_point = (LivoxPointXyzrtl *)point_buf;
451  FillPointsToCustomMsg(livox_msg, dst_point, single_point_num, \
452  packet_offset_time, point_interval, echo_num);
453 
454  if (!is_zero_packet) {
455  QueuePopUpdate(queue);
456  } else {
457  is_zero_packet = 0;
458  }
459 
460  livox_msg.point_num += single_point_num;
461  last_timestamp = timestamp;
462  ++published_packet;
463  }
464 
465  ros::Publisher *p_publisher = Lddc::GetCurrentPublisher(handle);
466  if (kOutputToRos == output_type_) {
467  p_publisher->publish(livox_msg);
468  } else {
469  if (bag_ && enable_lidar_bag_) {
470  bag_->write(p_publisher->getTopic(), ros::Time(timestamp / 1000000000.0),
471  livox_msg);
472  }
473  }
474 
475  if (!lidar->data_is_pubulished) {
476  lidar->data_is_pubulished = true;
477  }
478  return published_packet;
479 }
480 
482  uint8_t handle) {
483  uint64_t timestamp = 0;
484  uint32_t published_packet = 0;
485 
486  sensor_msgs::Imu imu_data;
487  imu_data.header.frame_id = "livox_frame";
488 
489  uint8_t data_source = lds_->lidars_[handle].data_src;
490  StoragePacket storage_packet;
491  QueuePrePop(queue, &storage_packet);
492  LivoxEthPacket *raw_packet =
493  reinterpret_cast<LivoxEthPacket *>(storage_packet.raw_data);
494  timestamp = GetStoragePacketTimestamp(&storage_packet, data_source);
495  if (timestamp >= 0) {
496  imu_data.header.stamp =
497  ros::Time(timestamp / 1000000000.0); // to ros time stamp
498  }
499 
500  uint8_t point_buf[2048];
501  LivoxImuDataProcess(point_buf, raw_packet);
502 
503  LivoxImuPoint *imu = (LivoxImuPoint *)point_buf;
504  imu_data.angular_velocity.x = imu->gyro_x;
505  imu_data.angular_velocity.y = imu->gyro_y;
506  imu_data.angular_velocity.z = imu->gyro_z;
507  imu_data.linear_acceleration.x = imu->acc_x;
508  imu_data.linear_acceleration.y = imu->acc_y;
509  imu_data.linear_acceleration.z = imu->acc_z;
510 
511  QueuePopUpdate(queue);
512  ++published_packet;
513 
514  ros::Publisher *p_publisher = Lddc::GetCurrentImuPublisher(handle);
515  if (kOutputToRos == output_type_) {
516  p_publisher->publish(imu_data);
517  } else {
518  if (bag_ && enable_imu_bag_) {
519  bag_->write(p_publisher->getTopic(), ros::Time(timestamp / 1000000000.0),
520  imu_data);
521  }
522  }
523  return published_packet;
524 }
525 
527  if (lds_ == nullptr) {
528  lds_ = lds;
529  return 0;
530  } else {
531  return -1;
532  }
533 }
534 
536  LidarDataQueue *p_queue = &lidar->data;
537  if (p_queue->storage_packet == nullptr) {
538  return;
539  }
540 
541  while (!QueueIsEmpty(p_queue)) {
542  uint32_t used_size = QueueUsedSize(p_queue);
543  uint32_t onetime_publish_packets = lidar->onetime_publish_packets;
544  if (used_size < onetime_publish_packets) {
545  break;
546  }
547 
549  PublishPointcloud2(p_queue, onetime_publish_packets, handle);
550  } else if (kLivoxCustomMsg == transfer_format_) {
551  PublishCustomPointcloud(p_queue, onetime_publish_packets, handle);
552  } else if (kPclPxyziMsg == transfer_format_) {
553  PublishPointcloudData(p_queue, onetime_publish_packets, handle);
554  }
555  }
556 }
557 
559  LidarDataQueue *p_queue = &lidar->imu_data;
560  if (p_queue->storage_packet == nullptr) {
561  return;
562  }
563 
564  while (!QueueIsEmpty(p_queue)) {
565  PublishImuData(p_queue, 1, handle);
566  }
567 }
568 
570  if (lds_ == nullptr) {
571  return;
572  }
573  lds_->semaphore_.Wait();
574  for (uint32_t i = 0; i < lds_->lidar_count_; i++) {
575  uint32_t lidar_id = i;
576  LidarDevice *lidar = &lds_->lidars_[lidar_id];
577  LidarDataQueue *p_queue = &lidar->data;
578  if ((kConnectStateSampling != lidar->connect_state) ||
579  (p_queue == nullptr)) {
580  continue;
581  }
582  PollingLidarPointCloudData(lidar_id, lidar);
583  PollingLidarImuData(lidar_id, lidar);
584  }
585 
586  if (lds_->IsRequestExit()) {
587  PrepareExit();
588  }
589 }
590 
592  ros::Publisher **pub = nullptr;
593  uint32_t queue_size = kMinEthPacketQueueSize;
594 
595  if (use_multi_topic_) {
596  pub = &private_pub_[handle];
597  queue_size = queue_size * 2; // queue size is 64 for only one lidar
598  } else {
599  pub = &global_pub_;
600  queue_size = queue_size * 8; // shared queue size is 256, for all lidars
601  }
602 
603  if (*pub == nullptr) {
604  char name_str[48];
605  memset(name_str, 0, sizeof(name_str));
606  if (use_multi_topic_) {
607  snprintf(name_str, sizeof(name_str), "livox/lidar_%s",
608  lds_->lidars_[handle].info.broadcast_code);
609  ROS_INFO("Support multi topics.");
610  } else {
611  ROS_INFO("Support only one topic.");
612  snprintf(name_str, sizeof(name_str), "livox/lidar");
613  }
614 
615  *pub = new ros::Publisher;
617  **pub =
618  cur_node_->advertise<sensor_msgs::PointCloud2>(name_str, queue_size);
619  ROS_INFO(
620  "%s publish use PointCloud2 format, set ROS publisher queue size %d",
621  name_str, queue_size);
622  } else if (kLivoxCustomMsg == transfer_format_) {
623  **pub = cur_node_->advertise<livox_ros_driver::CustomMsg>(name_str,
624  queue_size);
625  ROS_INFO(
626  "%s publish use livox custom format, set ROS publisher queue size %d",
627  name_str, queue_size);
628  } else if (kPclPxyziMsg == transfer_format_) {
629  **pub = cur_node_->advertise<PointCloud>(name_str, queue_size);
630  ROS_INFO(
631  "%s publish use pcl PointXYZI format, set ROS publisher queue "
632  "size %d",
633  name_str, queue_size);
634  }
635  }
636 
637  return *pub;
638 }
639 
641  ros::Publisher **pub = nullptr;
642  uint32_t queue_size = kMinEthPacketQueueSize;
643 
644  if (use_multi_topic_) {
645  pub = &private_imu_pub_[handle];
646  queue_size = queue_size * 2; // queue size is 64 for only one lidar
647  } else {
648  pub = &global_imu_pub_;
649  queue_size = queue_size * 8; // shared queue size is 256, for all lidars
650  }
651 
652  if (*pub == nullptr) {
653  char name_str[48];
654  memset(name_str, 0, sizeof(name_str));
655  if (use_multi_topic_) {
656  ROS_INFO("Support multi topics.");
657  snprintf(name_str, sizeof(name_str), "livox/imu_%s",
658  lds_->lidars_[handle].info.broadcast_code);
659  } else {
660  ROS_INFO("Support only one topic.");
661  snprintf(name_str, sizeof(name_str), "livox/imu");
662  }
663 
664  *pub = new ros::Publisher;
665  **pub = cur_node_->advertise<sensor_msgs::Imu>(name_str, queue_size);
666  ROS_INFO("%s publish imu data, set ROS publisher queue size %d", name_str,
667  queue_size);
668  }
669 
670  return *pub;
671 }
672 
673 void Lddc::CreateBagFile(const std::string &file_name) {
674  if (!bag_) {
675  bag_ = new rosbag::Bag;
676  bag_->open(file_name, rosbag::bagmode::Write);
677  ROS_INFO("Create bag file :%s!", file_name.c_str());
678  }
679 }
680 
681 void Lddc::PrepareExit(void) {
682  if (bag_) {
683  ROS_INFO("Waiting to save the bag file!");
684  bag_->close();
685  ROS_INFO("Save the bag file successfully!");
686  bag_ = nullptr;
687  }
688  if (lds_) {
689  lds_->PrepareExit();
690  lds_ = nullptr;
691  }
692 }
693 
694 } // namespace livox_ros
DeviceInfo info
Definition: lds.h:185
uint32_t GetPointInterval(uint32_t product_type)
Definition: lds.h:281
const uint32_t kMaxSourceLidar
Definition: lds.h:46
uint8_t lidar_count_
Definition: lds.h:445
uint32_t PublishPointcloudData(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
Definition: lddc.cpp:270
void publish(const boost::shared_ptr< M > &message) const
void open(std::string const &filename, uint32_t mode=bagmode::Read)
ros::Publisher * global_imu_pub_
Definition: lddc.h:102
ros::Publisher * GetCurrentPublisher(uint8_t handle)
Definition: lddc.cpp:591
LidarDataQueue data
Definition: lds.h:187
void QueuePrePop(LidarDataQueue *queue, StoragePacket *storage_packet)
Definition: ldq.cpp:77
uint8_t raw_data[KEthPacketMaxLength]
Definition: ldq.h:41
ExtrinsicParameter extrinsic_parameter
Definition: lds.h:191
uint32_t GetEchoNumPerPoint(uint32_t data_type)
Definition: lds.h:316
uint32_t GetLaserLineNumber(uint32_t product_type)
Definition: lds.h:300
Semaphore semaphore_
Definition: lds.h:447
uint32_t PublishPointcloud2(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
Definition: lddc.cpp:164
void InitPointcloud2MsgHeader(sensor_msgs::PointCloud2 &cloud)
Definition: lddc.cpp:132
uint8_t * LivoxImuDataProcess(uint8_t *point_buf, LivoxEthPacket *eth_packet)
Definition: lds.cpp:509
unsigned char uint8_t
Definition: stdint.h:125
void CreateBagFile(const std::string &file_name)
Definition: lddc.cpp:673
void PollingLidarPointCloudData(uint8_t handle, LidarDevice *lidar)
Definition: lddc.cpp:535
void FillPointsToCustomMsg(livox_ros_driver::CustomMsg &livox_msg, LivoxPointXyzrtl *src_point, uint32_t num, uint32_t offset_time, uint32_t point_interval, uint32_t echo_num)
Definition: lddc.cpp:356
void close()
uint8_t *(* PointConvertHandler)(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
Definition: lds.h:233
void ZeroPointDataOfStoragePacket(StoragePacket *storage_packet)
Definition: lds.cpp:533
ros::Publisher * private_pub_[kMaxSourceLidar]
Definition: lddc.h:99
uint8_t output_type_
Definition: lddc.h:93
LidarDataQueue imu_data
Definition: lds.h:188
Lds * lds_
Definition: lddc.h:65
uint8_t transfer_format_
Definition: lddc.h:90
bool enable_lidar_bag_
Definition: lddc.h:97
pcl::PointCloud< pcl::PointXYZI > PointCloud
Definition: lddc.h:38
unsigned int uint32_t
Definition: stdint.h:127
rosbag::Bag * bag_
Definition: lddc.h:105
const uint32_t kMaxPointPerEthPacket
Definition: lds.h:49
#define ROS_INFO(...)
uint64_t GetStoragePacketTimestamp(StoragePacket *packet, uint8_t data_src)
Definition: lds.cpp:75
unsigned __int64 uint64_t
Definition: stdint.h:137
virtual void PrepareExit(void)
Definition: lds.cpp:713
bool enable_imu_bag_
Definition: lddc.h:98
ros::Publisher * global_pub_
Definition: lddc.h:100
uint32_t point_num
Definition: ldq.h:40
uint32_t QueueUsedSize(LidarDataQueue *queue)
Definition: ldq.cpp:93
uint8_t raw_data_type
Definition: lds.h:175
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint8_t data_src
Definition: lds.h:174
bool data_is_pubulished
Definition: lds.h:176
volatile uint32_t packet_interval
Definition: lds.h:178
StoragePacket * storage_packet
Definition: ldq.h:47
uint32_t QueueIsEmpty(LidarDataQueue *queue)
Definition: ldq.cpp:105
void PollingLidarImuData(uint8_t handle, LidarDevice *lidar)
Definition: lddc.cpp:558
ros::NodeHandle * cur_node_
Definition: lddc.h:104
uint32_t PublishImuData(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
Definition: lddc.cpp:481
void QueuePopUpdate(LidarDataQueue *queue)
Definition: ldq.cpp:84
signed __int64 int64_t
Definition: stdint.h:136
int RegisterLds(Lds *lds)
Definition: lddc.cpp:526
std::string frame_id_
Definition: lddc.h:96
uint32_t publish_period_ns_
Definition: lddc.h:95
double publish_frq_
Definition: lddc.h:94
std::string getTopic() const
void PrepareExit(void)
Definition: lddc.cpp:681
signed int int32_t
Definition: stdint.h:124
const uint32_t kMinEthPacketQueueSize
Definition: lds.h:50
ros::Publisher * GetCurrentImuPublisher(uint8_t handle)
Definition: lddc.cpp:640
uint32_t PublishCustomPointcloud(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
Definition: lddc.cpp:378
ros::Publisher * private_imu_pub_[kMaxSourceLidar]
Definition: lddc.h:101
uint8_t * LivoxPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
Definition: lds.cpp:208
LidarDevice lidars_[kMaxSourceLidar]
Definition: lds.h:446
bool IsRequestExit()
Definition: lds.h:441
volatile uint32_t onetime_publish_packets
Definition: lds.h:183
void DistributeLidarData(void)
Definition: lddc.cpp:569
PointConvertHandler GetConvertHandler(uint8_t data_type)
Definition: lds.cpp:526
void write(std::string const &topic, ros::MessageEvent< T > const &event)
uint8_t use_multi_topic_
Definition: lddc.h:91
int32_t GetPublishStartTime(LidarDevice *lidar, LidarDataQueue *queue, uint64_t *start_time, StoragePacket *storage_packet)
Definition: lddc.cpp:91
volatile LidarConnectState connect_state
Definition: lds.h:184
Lddc(int format, int multi_topic, int data_src, int output_type, double frq, std::string &frame_id, bool lidar_bag, bool imu_bag)
Definition: lddc.cpp:45
volatile uint32_t packet_interval_max
Definition: lds.h:180
void FillPointsToPclMsg(PointCloud::Ptr &pcl_msg, LivoxPointXyzrtl *src_point, uint32_t num)
Definition: lddc.cpp:255
const int64_t kNsPerSecond
Definition: lds.h:65


livox_ros_driver
Author(s): Livox Dev Team
autogenerated on Mon Mar 15 2021 02:40:46