| Note: This tutorial assumes you have completed the writing a tf broadcaster tutorial (Python) (C++). |
Writing a tf listener (C++)
Description: This tutorial teaches you how to use tf to get access to frame transformations.Tutorial Level: BEGINNER
Next Tutorial: Adding a frame (Python) (C++)
Contents
In the previous tutorias 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 src/turtle_tf_listener.cpp.
1 #include <ros/ros.h>
2 #include <tf/transform_listener.h>
3 #include <turtlesim/Velocity.h>
4 #include <turtlesim/Spawn.h>
5
6 int main(int argc, char** argv){
7 ros::init(argc, argv, "my_tf_listener");
8
9 ros::NodeHandle node;
10
11 ros::service::waitForService("spawn");
12 ros::ServiceClient add_turtle =
13 node.serviceClient<turtlesim::Spawn>("spawn");
14 turtlesim::Spawn srv;
15 add_turtle.call(srv);
16
17 ros::Publisher turtle_vel =
18 node.advertise<turtlesim::Velocity>("turtle2/command_velocity", 10);
19
20 tf::TransformListener listener;
21
22 ros::Rate rate(10.0);
23 while (node.ok()){
24 tf::StampedTransform transform;
25 try{
26 listener.lookupTransform("/turtle2", "/turtle1",
27 ros::Time(0), transform);
28 }
29 catch (tf::TransformException ex){
30 ROS_ERROR("%s",ex.what());
31 }
32
33 turtlesim::Velocity vel_msg;
34 vel_msg.angular = 4 * atan2(transform.getOrigin().y(),
35 transform.getOrigin().x());
36 vel_msg.linear = 0.5 * sqrt(pow(transform.getOrigin().x(), 2) +
37 pow(transform.getOrigin().y(), 2));
38 turtle_vel.publish(vel_msg);
39
40 rate.sleep();
41 }
42 return 0;
43 };
The Code Explained
Now, let's take a look at the code that is relevant to publishing the turtle pose to tf.
The tf package provides an implementation of a TransformListener to help make the task of receiving transforms easier. To use the TransformListener, we need to include the tf/transform_listener.h header file.
20 tf::TransformListener listener;
Here, we create a TransformListener object. Once the listener is created, it starts receiving tf transformations over the wire, and buffers them for up to 10 seconds. The TransformListener object should be scoped to persist otherwise it's cache will be unable to fill and almost every query will fail. A common method is to make the TransformListener object a member variable of a class.
Here, the real work is done, we query the listener for a specific transformation. Let's take a look at the four arguments:
- We want the transform from this frame ...
- ... to this frame.
The time at which we want to transform. Providing ros::Time(0) will just get us the latest available transform.
- The object in which we store the resulting transform.
All this is wrapped in a try-catch block to catch possible exceptions.
Here, the transform is used to calculate new linear and angular velocities for turtle2, based on its distance and angle from turtle1. The new velocity is published in the topic "turtle2/command_velocity" and the sim will use that to update turtle2's movement.
Running the listener
Now that we created the code, lets compile it first. Open the CMakeLists.txt file, and add the following line on the bottom:
rosbuild_add_executable(turtle_tf_listener src/turtle_tf_listener.cpp)
and, try to build your package:
$ make
If everything went well, you should have a binary file called turtle_tf_listener in your bin folder. If so, we're ready add it the launch file for this demo. With your text editor, open the launch file called start_demo.launch, and merge the node block below inside the <launch> block:
<launch>
...
<node pkg="learning_tf" type="turtle_tf_listener"
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 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] 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 recieved 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++)






