Note: This tutorial assumes you have completed the writing a tf broadcaster 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.

Writing a tf listener (Python)

Description: This tutorial teaches you how to use tf to get access to frame transformations.

Tutorial Level: BEGINNER

Next Tutorial: Adding a frame (Python)

  Show EOL distros: 

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 created a tf broadcaster to publish the pose of a turtle to tf. In this tutorial we'll create a tf listener to start using tf.

How to create a tf listener

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

 $ roscd learning_tf

The Code

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

   1 #!/usr/bin/env python  
   2 import roslib
   3 roslib.load_manifest('learning_tf')
   4 import rospy
   5 import math
   6 import tf
   7 import turtlesim.msg
   8 import turtlesim.srv
   9 
  10 if __name__ == '__main__':
  11     rospy.init_node('turtle_tf_listener')
  12 
  13     listener = tf.TransformListener()
  14 
  15     rospy.wait_for_service('spawn')
  16     spawner = rospy.ServiceProxy('spawn', turtlesim.srv.Spawn)
  17     spawner(4, 2, 0, 'turtle2')
  18 
  19     turtle_vel = rospy.Publisher('turtle2/command_velocity', turtlesim.msg.Velocity, queue_size=1)
  20     # Groovy no queue_size
  21     # turtle_vel = rospy.Publisher('turtle2/command_velocity', turtlesim.msg.Velocity)
  22 
  23     rate = rospy.Rate(10.0)
  24     while not rospy.is_shutdown():
  25         try:
  26             (trans,rot) = listener.lookupTransform('/turtle2', '/turtle1', rospy.Time(0))
  27         except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):
  28             continue
  29 
  30         angular = 4 * math.atan2(trans[1], trans[0])
  31         linear = 0.5 * math.sqrt(trans[0] ** 2 + trans[1] ** 2)
  32         turtle_vel.publish(turtlesim.msg.Velocity(linear, angular))
  33 
  34         rate.sleep()

   1 #!/usr/bin/env python  
   2 import roslib
   3 roslib.load_manifest('learning_tf')
   4 import rospy
   5 import math
   6 import tf
   7 import geometry_msgs.msg
   8 import turtlesim.srv
   9 
  10 if __name__ == '__main__':
  11     rospy.init_node('turtle_tf_listener')
  12 
  13     listener = tf.TransformListener()
  14 
  15     rospy.wait_for_service('spawn')
  16     spawner = rospy.ServiceProxy('spawn', turtlesim.srv.Spawn)
  17     spawner(4, 2, 0, 'turtle2')
  18 
  19     turtle_vel = rospy.Publisher('turtle2/cmd_vel', geometry_msgs.msg.Twist,queue_size=1)
  20 
  21     rate = rospy.Rate(10.0)
  22     while not rospy.is_shutdown():
  23         try:
  24             (trans,rot) = listener.lookupTransform('/turtle2', '/turtle1', rospy.Time(0))
  25         except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):
  26             continue
  27 
  28         angular = 4 * math.atan2(trans[1], trans[0])
  29         linear = 0.5 * math.sqrt(trans[0] ** 2 + trans[1] ** 2)
  30         cmd = geometry_msgs.msg.Twist()
  31         cmd.linear.x = linear
  32         cmd.angular.z = angular
  33         turtle_vel.publish(cmd)
  34 
  35         rate.sleep()

Don't forget to make the node executable:

  • chmod +x nodes/turtle_tf_listener.py

The Code Explained

Now, let's take a look at the code that is relevant to publishing the turtle pose to tf.

   6 import tf

The tf package provides an implementation of a tf.TransformListener to help make the task of receiving transforms easier.

  13     listener = tf.TransformListener()

Here, we create a tf.TransformListener object. Once the listener is created, it starts receiving tf transformations over the wire, and buffers them for up to 10 seconds.

  23     rate = rospy.Rate(10.0)
  24     while not rospy.is_shutdown():
  25         try:
  26             (trans,rot) = listener.lookupTransform('/turtle2', '/turtle1', rospy.Time(0))
  27         except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):
  28             continue

Here, the real work is done, we query the listener for a specific transformation by lookupTransform. Let's take a look at the arguments:

  1. We want the transform from the '/turtle1' frame ...
  2. ... to the '/turtle2' frame.
  3. The time at which we want to transform. Providing rospy.Time(0) will just get us the latest available transform.

This function returns two lists. The first is the (x, y, z) linear transformation of the child frame relative to the parent, and the second is the (x, y, z, w) quaternion required to rotate from the parent orientation to the child orientation.

All this is wrapped in a try-except block to catch possible exceptions.

Running the listener

With your text editor, open the launch file called start_demo.launch, and add the following lines:

  <launch>
    ...
    <node pkg="learning_tf" type="turtle_tf_listener.py" 
          name="listener" />
  </launch>

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

 $ roslaunch learning_tf start_demo.launch

You should see the turtlesim with two turtles.

Checking the results

To see if things work, simply drive around the first turtle using the arrow keys (make sure your terminal window is active, not your simulator window), and you'll see the second turtle following the first one!

When the turtlesim starts up you may see:

  • [ERROR] 1253915565.300572000: Frame id /turtle2 does not exist! When trying to transform between /turtle1 and /turtle2.
    [ERROR] 1253915565.401172000: Frame id /turtle2 does not exist! When trying to transform between /turtle1 and /turtle2.

This happens because our listener is trying to compute the transform before messages about turtle 2 have been received because it takes a little time to spawn in turtlesim and start broadcasting a tf frame.

Now you're ready to move on to the next tutorial, where you'll learn how to add a frame (Python) (C++)

Wiki: tf/Tutorials/Writing a tf listener (Python) (last edited 2021-04-01 04:41:18 by FelixvonDrigalski)