Follow googlecartographer/cartographer#616. (#569)

master
gaschler 2017-11-03 13:34:53 +01:00 committed by Wolfgang Hess
parent e2f018d311
commit b665fbd6d2
1 changed files with 2 additions and 2 deletions

View File

@ -194,8 +194,8 @@ void Node::PublishTrajectoryStates(const ::ros::WallTimerEvent& timer_event) {
// published poses to advance. If we already know a newer pose, we use its
// time instead. Since tf knows how to interpolate, providing newer
// information is better.
const ::cartographer::common::Time now =
std::max(FromRos(ros::Time::now()), extrapolator.GetLastPoseTime());
const ::cartographer::common::Time now = std::max(
FromRos(ros::Time::now()), extrapolator.GetLastExtrapolatedTime());
stamped_transform.header.stamp = ToRos(now);
const Rigid3d tracking_to_local = extrapolator.ExtrapolatePose(now);
const Rigid3d tracking_to_map =