34 #include <sensor_msgs/Imu.h> 35 #include <sensor_msgs/PointCloud2.h> 37 #include <livox_ros_driver/CustomMsg.h> 38 #include <livox_ros_driver/CustomPoint.h> 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),
50 output_type_(output_type),
53 enable_lidar_bag_(lidar_bag),
54 enable_imu_bag_(imu_bag) {
102 *start_time = timestamp - remaining_time;
104 }
else if (diff_time <= lidar->packet_interval_max) {
105 *start_time = timestamp;
116 uint32_t last_remaning_time = remaining_time;
120 if (last_remaning_time > remaining_time) {
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;
177 sensor_msgs::PointCloud2 cloud;
183 uint8_t *point_base = cloud.data.data();
188 while ((published_packet < packet_num) && !
QueueIsEmpty(queue)) {
190 LivoxEthPacket *raw_packet =
191 reinterpret_cast<LivoxEthPacket *
>(storage_packet.
raw_data);
193 int64_t packet_gap = timestamp - last_timestamp;
205 if (!published_packet) {
206 cloud.header.stamp =
ros::Time(timestamp / 1000000000.0);
213 if (pf_point_convert) {
214 point_base = pf_point_convert(point_base, raw_packet,
218 ROS_INFO(
"Lidar[%d] unkown packet type[%d]", handle,
219 raw_packet->data_type);
227 if (!is_zero_packet) {
232 cloud.width += single_point_num;
234 last_timestamp = timestamp;
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);
252 return published_packet;
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;
265 pcl_msg->points.push_back(point);
284 cloud->header.frame_id.assign(
frame_id_);
293 while ((published_packet < packet_num) && !
QueueIsEmpty(queue)) {
295 LivoxEthPacket *raw_packet =
296 reinterpret_cast<LivoxEthPacket *
>(storage_packet.
raw_data);
298 int64_t packet_gap = timestamp - last_timestamp;
308 if (!published_packet) {
309 cloud->header.stamp = timestamp / 1000.0;
316 if (pf_point_convert) {
321 ROS_INFO(
"Lidar[%d] unkown packet type[%d]", handle,
322 raw_packet->data_type);
331 if (!is_zero_packet) {
336 cloud->width += single_point_num;
338 last_timestamp = timestamp;
353 return published_packet;
360 for (
uint32_t i = 0; i < num; i++) {
361 livox_ros_driver::CustomPoint point;
363 point.offset_time = offset_time + (i / echo_num) * point_interval;
365 point.offset_time = offset_time + i * point_interval;
367 point.
x = point_xyzrtl->
x;
368 point.y = point_xyzrtl->
y;
369 point.z = point_xyzrtl->
z;
371 point.tag = point_xyzrtl->
tag;
372 point.line = point_xyzrtl->
line;
374 livox_msg.points.push_back(point);
391 livox_ros_driver::CustomMsg livox_msg;
392 livox_msg.header.frame_id.assign(
frame_id_);
393 livox_msg.header.seq = msg_seq;
395 livox_msg.timebase = 0;
396 livox_msg.point_num = 0;
397 livox_msg.lidar_id = handle;
407 while (published_packet < packet_num) {
409 LivoxEthPacket *raw_packet =
410 reinterpret_cast<LivoxEthPacket *
>(storage_packet.
raw_data);
412 int64_t packet_gap = timestamp - last_timestamp;
424 if (!published_packet) {
425 livox_msg.timebase = timestamp;
426 packet_offset_time = 0;
428 livox_msg.header.stamp =
ros::Time(timestamp / 1000000000.0);
430 packet_offset_time = (
uint32_t)(timestamp - livox_msg.timebase);
437 if (pf_point_convert) {
442 ROS_INFO(
"Lidar[%d] unkown packet type[%d]", handle,
452 packet_offset_time, point_interval, echo_num);
454 if (!is_zero_packet) {
460 livox_msg.point_num += single_point_num;
461 last_timestamp = timestamp;
467 p_publisher->
publish(livox_msg);
478 return published_packet;
486 sensor_msgs::Imu imu_data;
487 imu_data.header.frame_id =
"livox_frame";
492 LivoxEthPacket *raw_packet =
493 reinterpret_cast<LivoxEthPacket *
>(storage_packet.
raw_data);
495 if (timestamp >= 0) {
496 imu_data.header.stamp =
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;
516 p_publisher->
publish(imu_data);
523 return published_packet;
527 if (
lds_ ==
nullptr) {
544 if (used_size < onetime_publish_packets) {
570 if (
lds_ ==
nullptr) {
579 (p_queue ==
nullptr)) {
597 queue_size = queue_size * 2;
600 queue_size = queue_size * 8;
603 if (*pub ==
nullptr) {
605 memset(name_str, 0,
sizeof(name_str));
607 snprintf(name_str,
sizeof(name_str),
"livox/lidar_%s",
611 ROS_INFO(
"Support only one topic.");
612 snprintf(name_str,
sizeof(name_str),
"livox/lidar");
620 "%s publish use PointCloud2 format, set ROS publisher queue size %d",
621 name_str, queue_size);
626 "%s publish use livox custom format, set ROS publisher queue size %d",
627 name_str, queue_size);
631 "%s publish use pcl PointXYZI format, set ROS publisher queue " 633 name_str, queue_size);
646 queue_size = queue_size * 2;
649 queue_size = queue_size * 8;
652 if (*pub ==
nullptr) {
654 memset(name_str, 0,
sizeof(name_str));
657 snprintf(name_str,
sizeof(name_str),
"livox/imu_%s",
660 ROS_INFO(
"Support only one topic.");
661 snprintf(name_str,
sizeof(name_str),
"livox/imu");
666 ROS_INFO(
"%s publish imu data, set ROS publisher queue size %d", name_str,
677 ROS_INFO(
"Create bag file :%s!", file_name.c_str());
683 ROS_INFO(
"Waiting to save the bag file!");
685 ROS_INFO(
"Save the bag file successfully!");
uint32_t GetPointInterval(uint32_t product_type)
const uint32_t kMaxSourceLidar
uint32_t PublishPointcloudData(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
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_
ros::Publisher * GetCurrentPublisher(uint8_t handle)
void QueuePrePop(LidarDataQueue *queue, StoragePacket *storage_packet)
uint8_t raw_data[KEthPacketMaxLength]
ExtrinsicParameter extrinsic_parameter
uint32_t GetEchoNumPerPoint(uint32_t data_type)
uint32_t GetLaserLineNumber(uint32_t product_type)
uint32_t PublishPointcloud2(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
void InitPointcloud2MsgHeader(sensor_msgs::PointCloud2 &cloud)
uint8_t * LivoxImuDataProcess(uint8_t *point_buf, LivoxEthPacket *eth_packet)
void CreateBagFile(const std::string &file_name)
void PollingLidarPointCloudData(uint8_t handle, LidarDevice *lidar)
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)
uint8_t *(* PointConvertHandler)(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
void ZeroPointDataOfStoragePacket(StoragePacket *storage_packet)
ros::Publisher * private_pub_[kMaxSourceLidar]
pcl::PointCloud< pcl::PointXYZI > PointCloud
const uint32_t kMaxPointPerEthPacket
uint64_t GetStoragePacketTimestamp(StoragePacket *packet, uint8_t data_src)
unsigned __int64 uint64_t
virtual void PrepareExit(void)
ros::Publisher * global_pub_
uint32_t QueueUsedSize(LidarDataQueue *queue)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
volatile uint32_t packet_interval
StoragePacket * storage_packet
uint32_t QueueIsEmpty(LidarDataQueue *queue)
void PollingLidarImuData(uint8_t handle, LidarDevice *lidar)
ros::NodeHandle * cur_node_
uint32_t PublishImuData(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
void QueuePopUpdate(LidarDataQueue *queue)
int RegisterLds(Lds *lds)
uint32_t publish_period_ns_
std::string getTopic() const
const uint32_t kMinEthPacketQueueSize
ros::Publisher * GetCurrentImuPublisher(uint8_t handle)
uint32_t PublishCustomPointcloud(LidarDataQueue *queue, uint32_t packet_num, uint8_t handle)
ros::Publisher * private_imu_pub_[kMaxSourceLidar]
uint8_t * LivoxPointToPxyzrtl(uint8_t *point_buf, LivoxEthPacket *eth_packet, ExtrinsicParameter &extrinsic, uint32_t line_num)
LidarDevice lidars_[kMaxSourceLidar]
volatile uint32_t onetime_publish_packets
void DistributeLidarData(void)
PointConvertHandler GetConvertHandler(uint8_t data_type)
void write(std::string const &topic, ros::MessageEvent< T > const &event)
int32_t GetPublishStartTime(LidarDevice *lidar, LidarDataQueue *queue, uint64_t *start_time, StoragePacket *storage_packet)
volatile LidarConnectState connect_state
Lddc(int format, int multi_topic, int data_src, int output_type, double frq, std::string &frame_id, bool lidar_bag, bool imu_bag)
volatile uint32_t packet_interval_max
void FillPointsToPclMsg(PointCloud::Ptr &pcl_msg, LivoxPointXyzrtl *src_point, uint32_t num)
const int64_t kNsPerSecond