Note: This tutorial assumes you have completed the tf and time (Python) (C++) tutorials.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Time travel with tf (Python)

Description: This tutorial teaches you about advanced time travel features of tf

Tutorial Level: ADVANCED

tf is deprecated in favor of tf2. tf2 provides a superset of the functionality of tf and is actually now the implementation under the hood. If you're just learning now it's strongly recommended to use the tf2/Tutorials instead.

In the previous tutorial we discussed the basic concept of tf and time. This tutorial will take this one step further, and expose one of the most powerful tf tricks.

Time travel

So let's go back to where we ended in the previous tutorial. Go to your package for the tutorial:

  $ roscd learning_tf

Now, instead of making the second turtle go to where the first turtle is now, make the second turtle go to where the first turtle was 5 seconds ago. Edit nodes/turtle_tf_listener.py:

   1         try:
   2             now = rospy.Time.now() - rospy.Duration(5.0)
   3             listener.waitForTransform("/turtle2", "/turtle1", now, rospy.Duration(1.0))
   4             (trans, rot) = listener.lookupTransform("/turtle2", "/turtle1", now)
   5         except (tf.Exception, tf.LookupException, tf.ConnectivityException):

So now, if you would run this, what would you expect to see? Definitely during the first 5 seconds the second turtle would not know where to go, because we do not yet have a 5 second history of the first turtle. But what after these 5 seconds? Let's just give it a try:

  $ make  or  catkin_make
  $ roslaunch learning_tf start_demo.launch
  • random.png

Is your turtle driving around uncontrollably like in this screenshot? So what is happening?

  • We asked tf, "What was the pose of /turtle1 5 seconds ago, relative to /turtle2 5 seconds ago?". This means we are controlling the second turtle based on where it was 5 seconds ago as well as where the first turtle was 5 seconds ago.

  • What we really want to ask is, "What was the pose of /turtle1 5 seconds ago, relative to the current position of the /turtle2?".

Advanced API for lookupTransform

So how can we ask tf a question like that? This API gives us the power to say explicitly when each frame is transformed. This is what the code would look like:

   1         try:
   2             now = rospy.Time.now()
   3             past = now - rospy.Duration(5.0)
   4             listener.waitForTransformFull("/turtle2", now,
   5                                       "/turtle1", past,
   6                                       "/world", rospy.Duration(1.0))
   7             (trans, rot) = listener.lookupTransformFull("/turtle2", now,
   8                                       "/turtle1", past,
   9                                       "/world")

The advanced API for lookupTransform() takes six arguments:

  1. Give the transform from this frame,
  2. at this time ...
  3. ... to this frame,
  4. at this time.
  5. Specify the frame that does not change over time, in this case the "/world" frame, and
  6. the variable to store the result in.

Notice that waitForTransform() also has a basic and and advanced API, just like lookupTransform().

  • time_travel.png

This figure shows what tf is doing in the background. In the past it computes the transform from the first turtle to the world. In the world frame tf time travels from the past to now. And at time now tf computes the transform from the world to the second turtle.

Checking the results

Let's run the simulator again, this time with the advanced time-travel API:

  $ roslaunch learning_tf start_demo.launch

And yes, the second turtle is directed to where the first turtle was 5 seconds ago!

Wiki: tf/Tutorials/Time travel with tf (Python) (last edited 2021-04-01 07:42:59 by FelixvonDrigalski)