Follow googlecartographer/cartographer#616. (#569)
parent
e2f018d311
commit
b665fbd6d2
|
@ -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
|
// published poses to advance. If we already know a newer pose, we use its
|
||||||
// time instead. Since tf knows how to interpolate, providing newer
|
// time instead. Since tf knows how to interpolate, providing newer
|
||||||
// information is better.
|
// information is better.
|
||||||
const ::cartographer::common::Time now =
|
const ::cartographer::common::Time now = std::max(
|
||||||
std::max(FromRos(ros::Time::now()), extrapolator.GetLastPoseTime());
|
FromRos(ros::Time::now()), extrapolator.GetLastExtrapolatedTime());
|
||||||
stamped_transform.header.stamp = ToRos(now);
|
stamped_transform.header.stamp = ToRos(now);
|
||||||
const Rigid3d tracking_to_local = extrapolator.ExtrapolatePose(now);
|
const Rigid3d tracking_to_local = extrapolator.ExtrapolatePose(now);
|
||||||
const Rigid3d tracking_to_map =
|
const Rigid3d tracking_to_map =
|
||||||
|
|
Loading…
Reference in New Issue