Note: This tutorial assumes you have completed the adding a fixed frame 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 dynamic frame (Python)

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

Tutorial Level:

Next Tutorial: Tf and time (Python) (C++)

In the previous tutorial we added a fixed frame to the turtle. In this tutorial we'll add a dynamic frame to the turtle.

How to add a dynamic frame

Adding a fixed frame is just a small step from adding a fixed frame. Go to the package we created for the previous tutorials:

 $ roscd learning_tf

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

   1 import roslib
   2 roslib.load_manifest('turtle_tf')
   3 
   4 import rospy
   5 import tf
   6 import turtlesim.msg
   7 import tf.msg
   8 import geometry_msgs.msg
   9 import math
  10 
  11 class DynamicTFBroadcaster:
  12 
  13     def __init__(self):
  14         self.pub_tf = rospy.Publisher("/tf", tf.msg.tfMessage)
  15 
  16         change = 0.0
  17         while not rospy.is_shutdown():
  18             # Run this loop at about 10Hz
  19             rospy.sleep(0.1)
  20 
  21             t = geometry_msgs.msg.TransformStamped()
  22             t.header.frame_id = "turtle1"
  23             t.header.stamp = rospy.Time.now()
  24             t.child_frame_id = "carrot2"
  25             t.transform.translation.x = 2.0 * math.sin(change)
  26             t.transform.translation.y = 2.0 * math.cos(change)
  27             t.transform.translation.z = 0.0
  28 
  29             t.transform.rotation.x = 0.0
  30             t.transform.rotation.y = 0.0
  31             t.transform.rotation.z = 0.0
  32             t.transform.rotation.w = 1.0
  33 
  34             tfm = tf.msg.tfMessage([t])
  35             self.pub_tf.publish(tfm)
  36 
  37             change += 0.1
  38 
  39 if __name__ == '__main__':
  40     rospy.init_node('my_tf_broadcaster')
  41     tfb = DynamicTFBroadcaster()
  42     rospy.spin()

The code is very similar to the example in the adding a fixed frame tutorial. Only here the transform does change over time.

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

Error: No code_block found Here we create a new transform, from the parent "turtle1" to the new child "carrot2". The carrot2 frame is 1 meter offset from the turtle1 frame.

Running the fixed frame broadcaster

Edit the start_demo.launchlaunch file. Add the following line:

  <launch>
    ...
    <node pkg="tf_tutorial_demo" type="dynamic_tf_broadcaster"
          name="broadcaster_fixed" />
  </launch>

Now you're ready to start the turtle broadcaster demo:

 $ roslaunch learning_tf start_demo.launch

You should see the turtle sim with two turtles.

Checking the results

Pretty much like in the last tutorial, we first need to change the listener to use the new dynamic frame we just added. Open the node/turtle_tf_listener.py file, and replace "/carrot1" with "/carrot2":

   1 (trans,rot) = self.tf.lookupTransform("/turtle2", "/carrot2", 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! And even if you're not moving the first turtle around, the carrot should still move!

 $ roslaunch tf_tutorial_demo start_demo.launch

Wiki: tf/Tutorials/Adding a dynamic frame (Python) (last edited 2009-09-23 19:49:34 by wim)