diff --git a/cartographer_ros/cartographer_ros/node_main.cc b/cartographer_ros/cartographer_ros/node_main.cc index cb2a7ef..707118a 100644 --- a/cartographer_ros/cartographer_ros/node_main.cc +++ b/cartographer_ros/cartographer_ros/node_main.cc @@ -402,7 +402,7 @@ void Node::PublishPoseAndScanMatchedPointCloud( const Rigid3d tracking_to_map = local_to_map * tracking_to_local; geometry_msgs::TransformStamped stamped_transform; - stamped_transform.header.stamp = ToRos(last_pose_estimate.time); + stamped_transform.header.stamp = ros::Time::now(); const auto published_to_tracking = tf_bridge_.LookupToTracking( last_pose_estimate.time, options_.published_frame);