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

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

Description: This tutorial teaches you how to broadcast coordinate frames of a robot to tf2.

Tutorial Level: BEGINNER

Next Tutorial: Writing a tf2 listener (C++)

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

Create a learning_tf2 package

First we will create a catkin package that will be used for this tutorial and the following ones. This package called learning_tf2 will depend on tf2, tf2_ros, roscpp, rospy and turtlesim. Code for this tutorial is stored here.

 $ catkin_create_pkg learning_tf2 tf2 tf2_ros roscpp rospy turtlesim

How to broadcast transforms

This tutorial teaches you how to broadcast coordinate frames to tf2. 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_tf2

The Code

Create a folder called src/ and fire up your favorite editor to paste the following code into a new file called src/turtle_tf2_broadcaster.cpp.

   1 #include <ros/ros.h>
   2 #include <tf2/LinearMath/Quaternion.h>
   3 #include <tf2_ros/transform_broadcaster.h>
   4 #include <geometry_msgs/TransformStamped.h>
   5 #include <turtlesim/Pose.h>
   6 
   7 std::string turtle_name;
   8 
   9 void poseCallback(const turtlesim::PoseConstPtr& msg){
  10   static tf2_ros::TransformBroadcaster br;
  11   geometry_msgs::TransformStamped transformStamped;
  12   
  13   transformStamped.header.stamp = ros::Time::now();
  14   transformStamped.header.frame_id = "world";
  15   transformStamped.child_frame_id = turtle_name;
  16   transformStamped.transform.translation.x = msg->x;
  17   transformStamped.transform.translation.y = msg->y;
  18   transformStamped.transform.translation.z = 0.0;
  19   tf2::Quaternion q;
  20   q.setRPY(0, 0, msg->theta);
  21   transformStamped.transform.rotation.x = q.x();
  22   transformStamped.transform.rotation.y = q.y();
  23   transformStamped.transform.rotation.z = q.z();
  24   transformStamped.transform.rotation.w = q.w();
  25 
  26   br.sendTransform(transformStamped);
  27 }
  28 
  29 int main(int argc, char** argv){
  30   ros::init(argc, argv, "my_tf2_broadcaster");
  31 
  32   ros::NodeHandle private_node("~");
  33   if (! private_node.hasParam("turtle"))
  34   {
  35     if (argc != 2){ROS_ERROR("need turtle name as argument"); return -1;};
  36     turtle_name = argv[1];
  37   }
  38   else
  39   {
  40     private_node.getParam("turtle", turtle_name);
  41   }
  42     
  43   ros::NodeHandle node;
  44   ros::Subscriber sub = node.subscribe(turtle_name+"/pose", 10, &poseCallback);
  45 
  46   ros::spin();
  47   return 0;
  48 };

The Code Explained

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

   3 #include <tf2_ros/transform_broadcaster.h>
   4 

The tf2 package provides an implementation of a TransformBroadcaster to help make the task of publishing transforms easier. To use the TransformBroadcaster, we need to include the tf2_ros/transform_broadcaster.h header file.

  10   static tf2_ros::TransformBroadcaster br;

Here, we create a TransformBroadcaster object that we'll use later to send the transformations over the wire.

  11   geometry_msgs::TransformStamped transformStamped;
  12   
  13   transformStamped.header.stamp = ros::Time::now();
  14   transformStamped.header.frame_id = "world";
  15   transformStamped.child_frame_id = turtle_name;

Here we create a Transform object and give it the appropriate metadata.

  1. We need to give the transform being published a timestamp, we'll just stamp it with the current time, ros::Time::now().

  2. Then, we need to set the name of the parent frame of the link we're creating, in this case "world"

  3. Finally, we need to set the name of the child node of the link we're creating, in this case this is the name of the turtle itself.

  16   transformStamped.transform.translation.x = msg->x;
  17   transformStamped.transform.translation.y = msg->y;
  18   transformStamped.transform.translation.z = 0.0;
  19   tf2::Quaternion q;
  20   q.setRPY(0, 0, msg->theta);
  21   transformStamped.transform.rotation.x = q.x();
  22   transformStamped.transform.rotation.y = q.y();
  23   transformStamped.transform.rotation.z = q.z();
  24   transformStamped.transform.rotation.w = q.w();

Here we copy the information from the 3D turtle pose into the 3D transform.

  26   br.sendTransform(transformStamped);

  • This is where the real work is done. Sending a transform with a TransformBroadcaster requires passing in just the transform itself.

Note: sendTransform and StampedTransform have opposite ordering of parent and child.

Note2: you can also publish static transforms on the same pattern by instantiating a StaticTransformBroadcaster (from tf2_ros/static_transform_broadcaster.h) instead of a TransformBroadcaster. The static transforms will be published on the /tf_static topic and will be sent only when required(latched topic) and not periodically. For more details see here

Running the broadcaster

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

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

and, try to build your package:

 $ catkin_make

If everything went well, you should have a binary file called turtle_tf2_broadcaster in your bin folder. If so, we're ready to create a launch file for this demo. With your text editor, create a new file called 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"/>
    <!-- Axes -->
    <param name="scale_linear" value="2" type="double"/>
    <param name="scale_angular" value="2" type="double"/>

    <node pkg="learning_tf2" type="turtle_tf2_broadcaster"
          args="/turtle1" name="turtle1_tf2_broadcaster" />
    <node pkg="learning_tf2" type="turtle_tf2_broadcaster"
          args="/turtle2" name="turtle2_tf2_broadcaster" />

  </launch>

And mark the file for installation

## Mark other files for installation (e.g. launch and bag files, etc.)
install(FILES
 start_demo.launch
 # myfile2
 DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

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

 $ roslaunch learning_tf2 start_demo.launch

You should see the turtle sim with one turtle.

Checking the results

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

 $ 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 tf2.

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

Feedback

If you have any comments on this tutorial please comment below:

Rating:
Username: Password:

Wiki: tf2/Tutorials/Writing a tf2 broadcaster (C++) (last edited 2022-10-06 16:54:34 by ShaneLoretz)