From d304b8953339aedbf67f75dca0f41025ead2a4d7 Mon Sep 17 00:00:00 2001 From: Fangcheng Zhu <50921331+zfc-zfc@users.noreply.github.com> Date: Sat, 17 Dec 2022 19:15:43 +0800 Subject: [PATCH] Fix a bug of time_sync_en. --- src/laserMapping.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/laserMapping.cpp b/src/laserMapping.cpp index 15935fb..44bc280 100644 --- a/src/laserMapping.cpp +++ b/src/laserMapping.cpp @@ -338,14 +338,13 @@ void imu_cbk(const sensor_msgs::Imu::ConstPtr &msg_in) // cout<<"IMU got at: "<header.stamp.toSec()<header.stamp = ros::Time().fromSec(msg_in->header.stamp.toSec() - time_diff_lidar_to_imu); if (abs(timediff_lidar_wrt_imu) > 0.1 && time_sync_en) { msg->header.stamp = \ ros::Time().fromSec(timediff_lidar_wrt_imu + msg_in->header.stamp.toSec()); } - msg->header.stamp = ros::Time().fromSec(msg_in->header.stamp.toSec() - time_diff_lidar_to_imu); - double timestamp = msg->header.stamp.toSec(); mtx_buffer.lock();