Note: This tutorial assumes you have a working knowledge of compiling programs in ROS and you have completed the Introduction to tf tutorial.
(!) 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 broadcaster (Python)

Description: This tutorial teaches you how to broadcast the state of a robot to tf.

Tutorial Level: BEGINNER

Next Tutorial: Writing a tf listener (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.

Create package

NOTE: Work on this section ONLY IF you haven't done Writing a tf broadcaster (C++) tutorial.

In the next two tutorials we will write the code to reproduce the demo from the tf introduction tutorial. After that, the following tutorials focus on extending the demo with more advanced tf features.

Before we get started, you need to create a new ros package for this project. In the sandbox folder, create a package called learning_tf that depends on tf, roscpp, rospy and turtlesim:

 $ cd %YOUR_CATKIN_WORKSPACE_HOME%/src
 $ catkin_create_pkg learning_tf tf roscpp rospy turtlesim

Build your new package before you can roscd:

 $ cd %YOUR_CATKIN_WORKSPACE_HOME%/
 $ catkin_make
 $ source ./devel/setup.bash

 $ roscd tutorials
 $ roscreate-pkg learning_tf tf roscpp rospy turtlesim
 $ rosmake learning_tf

How to broadcast transforms

This tutorial teaches you how to broadcast coordinate frames to tf. In this case, we want to broadcast the changing coordinate frames of the turtles, as they move around.

Let's first create the source files. Go to the package we just created:

 $ roscd learning_tf

The Code

Let's start by making a new directory called nodes in our learning_tf package.

$ mkdir nodes

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

   1 #!/usr/bin/env python  
   2 import roslib
   3 roslib.load_manifest('learning_tf')
   4 import rospy
   5 
   6 import tf
   7 import turtlesim.msg
   8 
   9 def handle_turtle_pose(msg, turtlename):
  10     br = tf.TransformBroadcaster()
  11     br.sendTransform((msg.x, msg.y, 0),
  12                      tf.transformations.quaternion_from_euler(0, 0, msg.theta),
  13                      rospy.Time.now(),
  14                      turtlename,
  15                      "world")
  16 
  17 if __name__ == '__main__':
  18     rospy.init_node('turtle_tf_broadcaster')
  19     turtlename = rospy.get_param('~turtle')
  20     rospy.Subscriber('/%s/pose' % turtlename,
  21                      turtlesim.msg.Pose,
  22                      handle_turtle_pose,
  23                      turtlename)
  24     rospy.spin()

Don't forget to make the node executable:

  • chmod +x nodes/turtle_tf_broadcaster.py

The Code Explained

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

  19     turtlename = rospy.get_param('~turtle')

This node takes a single parameter "turtle", which specifies a turtle name, e.g. "turtle1" or "turtle2".

  20     rospy.Subscriber('/%s/pose' % turtlename,
  21                      turtlesim.msg.Pose,
  22                      handle_turtle_pose,
  23                      turtlename)

The node subscribes to topic "turtleX/pose" and runs function handle_turtle_pose on every incoming message.

  10     br = tf.TransformBroadcaster()
  11     br.sendTransform((msg.x, msg.y, 0),
  12                      tf.transformations.quaternion_from_euler(0, 0, msg.theta),
  13                      rospy.Time.now(),
  14                      turtlename,
  15                      "world")

The handler function for the turtle pose message broadcasts this turtle's translation and rotation, and publishes it as a transform from frame "world" to frame "turtleX".

Running the broadcaster

Now create a launch file for this demo. With your text editor, create a new file called launch/start_demo.launch, and add the following lines:

  <launch>
    <!-- Turtlesim Node-->
    <node pkg="turtlesim" type="turtlesim_node" name="sim"/>
    <node pkg="turtlesim" type="turtle_teleop_key" name="teleop" output="screen"/>

    <node name="turtle1_tf_broadcaster" pkg="learning_tf" type="turtle_tf_broadcaster.py" respawn="false" output="screen" >
      <param name="turtle" type="string" value="turtle1" />
    </node>
    <node name="turtle2_tf_broadcaster" pkg="learning_tf" type="turtle_tf_broadcaster.py" respawn="false" output="screen" >
      <param name="turtle" type="string" value="turtle2" /> 
    </node>

  </launch>

Now you're ready to start your own turtle broadcaster demo:

 $ roslaunch learning_tf start_demo.launch

You should see the turtlesim with one turtle.

Checking the results

Now, use the tf_echo tool to check if the turtle pose is actually getting broadcast to tf:

 $ rosrun tf tf_echo /world /turtle1

This should show you the pose of the first turtle. Drive around the turtle using the arrow keys (make sure your terminal window is active, not your simulator window). If you run tf_echo for the transform between the world and turtle 2, you should not see a transform, because the second turtle is not there yet. However, as soon as we add the second turtle in the next tutorial, the pose of turtle 2 will be broadcast to tf.

To actually use the transforms broadcast to tf, you should move on to the next tutorial about creating a tf listener (Python) (C++)

Wiki: tf/Tutorials/Writing a tf broadcaster (Python) (last edited 2021-04-01 04:38:16 by FelixvonDrigalski)