From ec2d54ef847356b7371c2657108e9fd05d10e610 Mon Sep 17 00:00:00 2001 From: Stefan Kohlbrecher Date: Wed, 26 Oct 2016 12:40:19 +0200 Subject: [PATCH] Sets stamped_transform timestamp to ros::Time::now() (#143) --- cartographer_ros/cartographer_ros/node_main.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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);