Utilize Foxglove to debug and modify your ROS 2 robot’s transforms efficiently.
Roboticists rely on mathematical operations called transformations (or "transforms") to situate their robots' components in relation to other objects in their world.
In this tutorial, we’ll learn how to publish static and mobile transforms in ROS, and how to visualize and edit these messages using Foxglove.
Transforms describe how objects in your robot’s world are positioned in relation to each other. They fall in one of two categories – static or mobile. Static transforms remain the same over time – e.g. a transform between a camera and the rover it’s mounted on. Mobile transforms, on the other hand, often vary from moment to moment – e.g. a transform between a rover's camera and a detected pedestrian.
ROS 2 periodically publishes mobile transforms on the /tf
topic, to track how they evolve over time. To improve bandwidth, ROS 2 only publishes static transforms on the /tf_static
topic much less infrequently – often only once for a given recording session.
Let's use the static_transform_publisher
node from the tf2_ros
package to publish a static transform. We’ll be using the example robot from our last transforms tutorial as a reference:
Execute the static_transform_publisher
node from a Terminal window – x
, y
, z
describe the relative translation, while r
, p
, y
describe the relative orientation (i.e. roll, pitch, yaw angles):
$ ros2 run tf2_ros static_transform_publisher x y z r p y parent_frame child_frame
Next, publish a static transform between your robot’s base frame (base_link
) and its arm base frame (arm_base_link
):
$ ros2 run tf2_ros static_transform_publisher 1 -1 0 0 0 0.707 base_link arm_base_link
You are now publishing static transforms!
To verify, let's inspect our broadcast messages in Foxglove. Once you load the app, open a Foxglove WebSocket connection with the default WebSocket URL:
Add a 3D panel to your layout to see all your published frames. Next, add two Raw Messages panels to look at your incoming /tf
and /tf_static
messages:
Your /tf
Raw Messages panel will be empty, as we're not yet publishing any mobile transforms. Your /tf_static
Raw Messages panel, however, should be displaying your static transform messages.
Now that we've published a static transform, let's create a broadcaster node that publishes mobile transforms to describe your robotic arm's movement.
Create a tf_broadcaster.cpp
file in your package's src/
folder, and include the necessary libraries:
Define a TfBroadcaster
class that publishes a transform message for each new arm transform detected. It should subscribe to the arm position topic (/cmd_vel
, which publishes Twist
messages), calculate a new transform whenever a new arm position is detected (armCallback
), and use a timer (transform_timer_
) to periodically publish the last-calculated transform:
Next, let’s instantiate our broadcaster, subscribe to the arm topic, and initialize our timer:
Finally, write a main
function to declare and spin the node:
Add the following lines to your CMakeLists.txt
to add the executable to the compilation list:
Compile your package with $ colcon build --symlink-install
, and run this second node:
$ ros2 run tf_pkg tf_broadcaster
You are now publishing mobile transforms!
To verify, let's inspect our broadcast messages again in Foxglove. Once you reconnect to your live data, go to the Layouts sidebar and import this example layout.
To simulate a moving robotic arm, use the provided layout's Teleop panel to publish different Twist
messages to the /cmd_vel
topic:
Note how your broadcaster node reacts to these new arm position messages by updating the /tf
topic messages. The /tf_static
topic message should remain unchanged, as the arm's movement doesn't affect the static transform between the base_link
and arm_base_link
frames.
Finally, let’s investigate our transform tree to find the relative positions of all our frames, even if they aren’t directly connected.
One way to do this is with the tf2_echo
executable – this lets you calculate any frame’s position relative to a base frame, without worrying about the string of matrices connecting them. For example, we can calculate the transform between our base_link
and arm_end_link
frames, even though these are not directly connected:
As expected, the output Translation
and Rotation
values will change whenever you modify the arm_end_link
frame’s position.
Another way to view your transform tree is to use Foxglove's 3D panel. Once you connect to your data and open the 3D panel’s settings, you’ll be able to see a list of all transforms detected in your source:
Each indented frame in the 3D panel settings represents a child of a parent frame.
You can even use the 3D panel settings to modify transforms in real time. Toggle “Editable” in the “Transforms” settings, then edit each transform’s values to see them reflected in the 3D scene:
Keep in mind that this feature is mainly for real-time debugging – whether you’re verifying the position of your robot elements or maybe correcting bad sensor readings. These updated transform values are not actually published to the /tf
and /tf_static
topics.
Transforms are one of the most potent tools that you will need in your robotics career. Being able to publish, visualize, and even edit transforms can help you better understand the world your robot is navigating.
For a reference to all the code covered in this post, check out our GitHub. And as always, feel free to reach out to the Foxglove team in our Discord community to ask questions, give us feedback, and request a topic for the next tutorial!