From 7f546a57d097bab7768a7f4788bae012526d1584 Mon Sep 17 00:00:00 2001 From: livox Date: Tue, 13 Aug 2019 17:15:00 +0800 Subject: [PATCH] resolve the timestamp error in pointcloud2 msg The timestamp unit in pcl::PointCloud is us, not ns! --- livox_ros_driver/livox_lidar.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/livox_ros_driver/livox_lidar.cpp b/livox_ros_driver/livox_lidar.cpp index d635717..d915c69 100755 --- a/livox_ros_driver/livox_lidar.cpp +++ b/livox_ros_driver/livox_lidar.cpp @@ -425,7 +425,7 @@ static uint32_t PublishPointcloud2(StoragePacketQueue* queue, uint32_t packet_nu if (!cloud->width) { //cloud->header.stamp = ros::Time(timestamp/1000000000.0); // to ros time stamp - cloud->header.stamp = timestamp/1000000000.0; // to ros time stamp + cloud->header.stamp = timestamp/1000.0; // to ros time stamp ROS_DEBUG("[%d]:%ld us", handle, timestamp); } cloud->width += storage_packet.point_num;