Note: This tutorial assumes you have completed the writing a tf listener tutorial (Python) (C++).
(!) 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.

Adding a frame (Python)

Description: This tutorial teaches you how to add an extra fixed frame to tf.

Tutorial Level: BEGINNER

Next Tutorial: tf and time (Python)

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 tutorials we recreated the turtle demo by adding a tf broadcaster and a tf listener. This tutorial will teach you how to add an extra frame to the tf tree. This is very similar to creating the tf broadcaster, and will show some of the power of tf.

Why adding frames

For many tasks it is easier to think inside a local frame, e.g. it is easier to reason about a laser scan in a frame at the center of the laser scanner. tf allows you to define a local frame for each sensor, link, etc in your system. And, tf will take care of all the extra frame transforms that are introduced.

Where to add frames

tf builds up a tree structure of frames; it does not allow a closed loop in the frame structure. This means that a frame only has one single parent, but it can have multiple children. Currently our tf tree contains three frames: world, turtle1 and turtle2. The two turtles are children of world. If we want to add a new frame to tf, one of the three existing frames needs to be the parent frame, and the new frame will become a child frame.

  • tree.png

How to add a frame

In our turtle example, we'll add a new frame to the first turtle. This frame will be the "carrot" for the second turtle.

Let's first create the source files. Go to the package we created for the previous tutorials:

 $ roscd learning_tf

The Code

Fire up your favorite editor and paste the following code into a new file called nodes/fixed_tf_broadcaster.py.

   1 #!/usr/bin/env python  
   2 import roslib
   3 roslib.load_manifest('learning_tf')
   4 
   5 import rospy
   6 import tf
   7 
   8 if __name__ == '__main__':
   9     rospy.init_node('fixed_tf_broadcaster')
  10     br = tf.TransformBroadcaster()
  11     rate = rospy.Rate(10.0)
  12     while not rospy.is_shutdown():
  13         br.sendTransform((0.0, 2.0, 0.0),
  14                          (0.0, 0.0, 0.0, 1.0),
  15                          rospy.Time.now(),
  16                          "carrot1",
  17                          "turtle1")
  18         rate.sleep()

Don't forget to make the node executable:

  • chmod +x nodes/fixed_tf_broadcaster.py

The code is very similar to the example in the tf broadcaster tutorial. Only here the transform does not change over time.

The Code Explained

Let's take a look at the key lines in this piece of code:

  13         br.sendTransform((0.0, 2.0, 0.0),
  14                          (0.0, 0.0, 0.0, 1.0),
  15                          rospy.Time.now(),
  16                          "carrot1",
  17                          "turtle1")

Here we create a new transform, from the parent "turtle1" to the new child "carrot1". The carrot1 frame is 2 meters offset from the turtle1 frame.

Running the frame broadcaster

Edit the start_demo.launch launch file. Simply add the following line:

  <launch>
    ...
    <node pkg="learning_tf" type="fixed_tf_broadcaster.py"
          name="broadcaster_fixed" />
  </launch>

First, make sure you stopped the launch file from the previous tutorial (use Ctrl-c). Now you're ready to start the turtle broadcaster demo:

 $ roslaunch learning_tf start_demo.launch

Checking the results

So, if you drive the first turtle around, you notice that the behavior didn't change from the previous tutorial, even though we added a new frame. That's because adding an extra frame does not affect the other frames, and our listener is still using the previously defined frames. So, let's change the behavior of the listener.

Open the nodes/turtle_tf_listener.py file, and simple replace "/turtle1" with "/carrot1":

   1 (trans,rot) = listener.lookupTransform("/turtle2", "/carrot1", rospy.Time(0))

And now the good part: just restart the turtle demo, and you'll see the second turtle following the carrot instead of the first turtle! Remember that the carrot is 2 meters to the left of turtle1. There is no visual representation for the carrot, but you should see the second turtle moving to that point.

 $ roslaunch learning_tf start_demo.launch

Broadcasting a moving frame

The extra frame we published in this tutorial is a fixed frame that doesn't change over time in relation to the parent frame. However, if you want to publish a moving frame you can code the broadcaster to change the frame over time. Let's change our carrot1 frame to change relative to turtle1 over time.

Create the file nodes/dynamic_tf_broadcaster.py containing the following (and make it executable with chmod +x as we did above):

   1 #!/usr/bin/env python  
   2 import roslib
   3 roslib.load_manifest('learning_tf')
   4 
   5 import rospy
   6 import tf
   7 import math
   8 
   9 if __name__ == '__main__':
  10     rospy.init_node('dynamic_tf_broadcaster')
  11     br = tf.TransformBroadcaster()
  12     rate = rospy.Rate(10.0)
  13     while not rospy.is_shutdown():
  14         t = rospy.Time.now().to_sec() * math.pi
  15         br.sendTransform((2.0 * math.sin(t), 2.0 * math.cos(t), 0.0),
  16                          (0.0, 0.0, 0.0, 1.0),
  17                          rospy.Time.now(),
  18                          "carrot1",
  19                          "turtle1")
  20         rate.sleep()

Note that instead of defining a fixed offset from turtle1, we are using a sin and cos function based on the current time to cause the definition of the frame's offset.

To test this code, remember to change the launch file to point to our new, dynamic broadcaster for the definition of carrot1 instead of the fixed broadcaster above:

  <launch>
    ...
    <node pkg="learning_tf" type="dynamic_tf_broadcaster.py"
          name="broadcaster_dynamic" />
  </launch>

You're now ready to move to the next tutorial about tf and time (Python) (C++)

Wiki: tf/Tutorials/Adding a frame (Python) (last edited 2021-04-01 07:41:44 by FelixvonDrigalski)