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

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

Description: This tutorial teaches you how to add an extra fixed frame to tf2.

Tutorial Level: BEGINNER

Next Tutorial: tf2 and time (C++)

In the previous tutorials we recreated the turtle demo by adding a tf2 broadcaster and a tf2 listener. This tutorial will teach you how to add an extra frame to the tf2 tree. This is very similar to creating the tf2 broadcaster, and will show some of the power of tf2.

Why adding frames

For many tasks it is easier to think inside a local frame, e.g. it is easiest to reason about a laser scan in a frame at the center of the laser scanner. tf2 allows you to define a local frame for each sensor, link, etc in your system. And, tf2 will take care of all the extra frame transforms that are introduced.

Where to add frames

tf2 builds up a tree structure of frames; it does not allow a closed loop in the frame structure. This means that a frame only has one single parent, but it can have multiple children. Currently our tf2 tree contains three frames: world, turtle1 and turtle2. The two turtles are children of world. If we want to add a new frame to tf2, one of the three existing frames needs to be the parent frame, and the new frame will become a child frame.

  • tree.png

How to add a frame

In our turtle example, we'll add a new frame to the first turtle. This frame will be the "carrot" for the second turtle.

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

 $ roscd learning_tf2

The Code

Fire up your favorite editor and paste the following code into a new file called src/frame_tf2_broadcaster.cpp.

   1 #include <ros/ros.h>
   2 #include <tf2_ros/transform_broadcaster.h>
   3 #include <tf2/LinearMath/Quaternion.h>
   4 
   5 int main(int argc, char** argv){
   6   ros::init(argc, argv, "my_tf2_broadcaster");
   7   ros::NodeHandle node;
   8 
   9    tf2_ros::TransformBroadcaster tfb;
  10   geometry_msgs::TransformStamped transformStamped;
  11 
  12   
  13   transformStamped.header.frame_id = "turtle1";
  14   transformStamped.child_frame_id = "carrot1";
  15   transformStamped.transform.translation.x = 0.0;
  16   transformStamped.transform.translation.y = 2.0;
  17   transformStamped.transform.translation.z = 0.0;
  18   tf2::Quaternion q;
  19         q.setRPY(0, 0, 0);
  20   transformStamped.transform.rotation.x = q.x();
  21   transformStamped.transform.rotation.y = q.y();
  22   transformStamped.transform.rotation.z = q.z();
  23   transformStamped.transform.rotation.w = q.w();
  24 
  25   ros::Rate rate(10.0);
  26   while (node.ok()){
  27     transformStamped.header.stamp = ros::Time::now();
  28     tfb.sendTransform(transformStamped);
  29     rate.sleep();
  30     printf("sending\n");
  31   }
  32 
  33 };

The code is very similar to the example in the tf2 broadcaster tutorial.

The Code Explained

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

   9    tf2_ros::TransformBroadcaster tfb;
  10   geometry_msgs::TransformStamped transformStamped;
  11 
  12   
  13   transformStamped.header.frame_id = "turtle1";
  14   transformStamped.child_frame_id = "carrot1";
  15   transformStamped.transform.translation.x = 0.0;
  16   transformStamped.transform.translation.y = 2.0;
  17   transformStamped.transform.translation.z = 0.0;
  18   tf2::Quaternion q;
  19         q.setRPY(0, 0, 0);
  20   transformStamped.transform.rotation.x = q.x();
  21   transformStamped.transform.rotation.y = q.y();
  22   transformStamped.transform.rotation.z = q.z();
  23   transformStamped.transform.rotation.w = q.w();

Here we create a new transform, from the parent turtle1 to the new child carrot1. The carrot1 frame is 2 meters offset from the turtle1 frame.

Running the frame broadcaster

Now that we created the code, lets compile it first. Open the CMakeLists.txt file, and add the following line on the bottom:

add_executable(frame_tf2_broadcaster src/frame_tf2_broadcaster.cpp)
target_link_libraries(frame_tf2_broadcaster
 ${catkin_LIBRARIES}
)

and, try to build your package:

If everything went well, you should have a binary file called frame_tf2_broadcaster in your bin folder. If so, we're ready to edit the start_demo.launch launch file. Simply merge the node block below inside the launch block::

  <launch>
    ...
    <node pkg="learning_tf2" type="frame_tf2_broadcaster"
          name="broadcaster_frame" />
  </launch>

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

 $ roslaunch learning_tf2 start_demo.launch

Checking the results

So, if you drive the first turtle around, you notice that the behavior didn't change from the previous tutorial, even though we added a new frame. That's because adding an extra frame does not affect the other frames, and our listener is still using the previously defined frames. So, let's change the behavior of the listener.

Open the src/turtle_tf2_listener.cpp file, and simple replace "/turtle1" with "/carrot1" in lines 32-33:

   1   transformStamped = listener.lookupTransform("/turtle2", "/carrot1",
   2                            ros::Time(0));

And now the good part: just rebuild and restart the turtle demo, and you'll see the second turtle following the carrot instead of the first turtle!

 $ roslaunch learning_tf2 start_demo.launch

Broadcasting a moving frame

The extra frame we published in this tutorial is a fixed frame that doesn't change over time in relation to the parent frame. However, if you want to publish a moving frame you can change the broadcaster to change over time. Let's modify the /carrot1 frame to change relative to /turtle1 over time. Don't forget to put these lines within the while loop, so that the updated values get sent.

   1   transformStamped.transform.translation.x = 2.0*sin(ros::Time::now().toSec());
   2   transformStamped.transform.translation.y = 2.0*cos(ros::Time::now().toSec());

And now the good part: just rebuild and restart the turtle demo, and you'll see the second turtle following a moving carrot.

 $ roslaunch learning_tf2 start_demo.launch

You're now ready to move to the next tutorial about tf2 and time (Python) (C++)

Wiki: tf2/Tutorials/Adding a frame (C++) (last edited 2022-10-06 16:47:51 by ShaneLoretz)