ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

Should I publish transforms with future stamps to keep them "valid"?

asked 2020-01-06 03:58:47 -0500

Rufus gravatar image

updated 2020-01-15 04:12:24 -0500

When writing a custom transform publisher and messing with the transform timestamps, a common problem I face is that other subsystems that end up using the transform sometimes encounter the extrapolation error

Extrapolation Error: Lookup would require extrapolation into the future.

One way I brush this problem under the rug is to just publish the transform with a stamp slightly in the future to keep them valid.

This obviously looks hacky. So what is the correct way of publishing transforms such that other nodes can properly look up transforms without facing the extrapolation error?

An example is base_local_planner throwing Extrapolation Error when looking up transform /map -> /odom, which is a transform that I'm manually publishing. I tried publishing at various different frequencies but only changing the stamp to be slightly in the future (e.g. now + ros::Duration(0.5)) fixes the issue.

edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
3

answered 2020-01-16 11:38:00 -0500

The correct way to do this is that the TF broadcaster publishes the transform with the correct time stamp (no future-dating), and the client nodes should wait for the transform to become available before looking it up:

http://wiki.ros.org/tf/Tutorials/tf%2...

For example, in Kinetic, base_local_planner does it like this:

https://github.com/ros-planning/navig...

In Melodic, base_local_planner has switched to TF2, and in TF2 it's possible to pass the timeout directly to lookupTransform:

https://github.com/ros-planning/navig...

So what both versions do is the same: They wait for up to 0.5 seconds for the TF transform with the proper time stamp and then look up the transform. If you get these errors, maybe you have more than 0.5 seconds latency? Another reason for this kind of error is when the TF broadcaster node runs on a different PC than the TF listener and the two clocks are not synchronized.

And by the way: one of the "default" nodes for publishing the map -> odom transform is AMCL, and it does indeed future-stamp the TFs that it broadcasts by transform_tolerance_ (by default 0.1 seconds):

https://github.com/ros-planning/navig...

The successor to AMCL, robot_localization, also provides this option (but it's off by default):

https://github.com/cra-ros-pkg/robot_...

I think the reason for doing this is that the map->odom transform usually doesn't change that fast (it's only a correction offset), and future-dating it reduces latency in all the waitForTransform calls in the client nodes. But I 100% agree with you, it's a hack and it has always bothered me a little.

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2020-01-06 03:58:47 -0500

Seen: 422 times

Last updated: Jan 16 '20