Fix a bug of time_sync_en.
parent
a56a0c544a
commit
d304b89533
|
@ -338,14 +338,13 @@ void imu_cbk(const sensor_msgs::Imu::ConstPtr &msg_in)
|
|||
// cout<<"IMU got at: "<<msg_in->header.stamp.toSec()<<endl;
|
||||
sensor_msgs::Imu::Ptr msg(new sensor_msgs::Imu(*msg_in));
|
||||
|
||||
msg->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();
|
||||
|
|
Loading…
Reference in New Issue