Using ROS 2? Check out the ROS 2 tf2 tutorials.

Note: This tutorial assumes you have completed the writing a tf2 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 tf2 listener (Python)

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

Tutorial Level: BEGINNER

Next Tutorial: Adding a frame (Python)

In the previous tutorials we created a tf2 broadcaster to publish the pose of a turtle to tf2. In this tutorial we'll create a tf2 listener to start using tf2.

How to create a tf2 listener

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

 $ roscd learning_tf2

The Code

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

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

Don't forget to make the node executable:

  • chmod +x nodes/turtle_tf2_listener.py

The Code Explained

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

   5 import tf2_ros

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

  13     listener = tf2_ros.TransformListener(tfBuffer)

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

  24         try:
  25             trans = tfBuffer.lookup_transform(turtle_name, 'turtle1', rospy.Time())
  26         except (tf2_ros.LookupException, tf2_ros.ConnectivityException, tf2_ros.ExtrapolationException):
  27             rate.sleep()
  28             continue
  29 
  30         msg = geometry_msgs.msg.Twist()

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

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

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_tf2" type="turtle_tf2_listener.py" 
          name="listener" output="screen"/>
  </launch>

Don't forget to add the script to the CMakeLists.txt install rule, reinvoke catkin_make_isolated and use your terminal with the devel_isolated/setup.bash sourced.

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_tf2 start_demo.launch

You should see the turtle sim 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] [1418082761.220546623]: "turtle2" passed to lookupTransform argument target_frame does not exist.
    [ERROR] [1418082761.320422000]: "turtle2" passed to lookupTransform argument target_frame does not exist.

This happens because our listener is trying to compute the transform before turtle 2 is spawned in turtlesim and broadcasting a tf2 frame.

Transforming poses, points, etc. from frame to frame

Now that you know the transform from frame "turtle1" to frame "turtle2", you can transform vectors from one to the other. See (Using Stamped datatypes with tf2_ros::MessageFilter)

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

Wiki: tf2/Tutorials/Writing a tf2 listener (Python) (last edited 2022-10-06 16:55:39 by ShaneLoretz)