Publishing and Visualizing ROS 2 Transforms

Use Foxglove Studio to debug and edit your robot’s transforms
José L. MillánJosé L. Millán ·
Esther WeonEsther Weon ·
10 min read
Published
Publishing and Visualizing ROS 2 Transforms

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 Studio.

Publishing transforms

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.

Static

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:

example robot

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 Studio. Once you load the app, open a Foxglove WebSocket connection with the default WebSocket URL:

Foxglove WebSocket connection

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:

Foxglove Studio layout

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.

Mobile

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:

#include <rclcpp/rclcpp.hpp>
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "tf2/LinearMath/Quaternion.h"
#include "tf2_ros/transform_broadcaster.h"

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:

class TfBroadcaster : public rclcpp::Node{
private:
    // Declare a timer for the tf_broadcaster_
    rclcpp::TimerBase::SharedPtr transform_timer_;
    // Declare the transforms broadcaster
    std::unique_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
    // Subscription for cmdVel
    rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_sub_;
    // Declare the transform to broadcast
    geometry_msgs::msg::TransformStamped transf_;

void armCallback(const geometry_msgs::msg::Twist::SharedPtr msg){
    transf_.transform.translation.x = msg->linear.x;
    transf_.transform.translation.y = msg->linear.y;
    tf2::Quaternion q;
    q.setRPY(0,0,msg->angular.z);
    transf_.transform.rotation.x = q.getX();
    transf_.transform.rotation.y = q.getY();
    transf_.transform.rotation.z = q.getZ();
    transf_.transform.rotation.w = q.getW();
}

void tfTimer(){
    // All transforms must be correctly timestamped
    transf_.header.stamp = this->get_clock()->now();
    tf_broadcaster_->sendTransform(transf_);
}

Next, let’s instantiate our broadcaster, subscribe to the arm topic, and initialize our timer:

public:
  TfBroadcaster(const std::string & name):
  Node(name){
    // Initialize the transforms broadcaster
    tf_broadcaster_ = std::make_unique<tf2_ros::TransformBroadcaster>(*this);
    // Define the "parent" frame
    transf_.header.frame_id = "arb_base_link";
    // Define the "child" frame
    transf_.child_frame_id = "arm_end_link";
    // Initialize timer for publishing transform
    transform_timer_ = create_wall_timer(std::chrono::seconds(1),
      std::bind(&TfBroadcaster::tfTimer, this));
    // Create subscriber for cmdVel
    cmd_vel_sub_ = create_subscription<geometry_msgs::msg::Twist>(
      "/cmd_vel",10,std::bind(&TfBroadcaster::armCallback, this, std::placeholders::_1));
  }

  ~TfBroadcaster(){}
};

Finally, write a main function to declare and spin the node:

int main(int argc, char const *argv[]){
  rclcpp::init(argc, argv);
  auto node = std::make_shared<TfBroadcaster>("tf_broadcaster");
  rclcpp::spin(node);
  return 0;
}

Add the following lines to your CMakeLists.txt to add the executable to the compilation list:

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(tf2 REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)

set(dependencies
std_msgs
tf2
geometry_msgs
tf2_ros
)

add_executable(tf_broadcaster src/tf_broadcaster.cpp)
ament_target_dependencies(tf_broadcaster ${dependencies})

install(TARGETS
tf_broadcaster
DESTINATION lib/${PROJECT_NAME})

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 Studio. 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:

final layout

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.

Viewing and editing transforms in Foxglove Studio

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:

$ ros2 run tf2_ros tf2_echo base_link arm_end_link
  [INFO] [1673980109.376075784] [tf2_echo]: Waiting for transform base_link ->  arm_end_link: Invalid frame ID "base_link" passed to canTransform argument target_frame - frame does not exist

  At time 1673980109.414160639
  - Translation: [2.916, -1.000, 0.000]
  - Rotation: in Quaternion [0.346, 0.000, 0.000, 0.938]

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 Studio'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:

transform tree in 3D panel

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:

editable transforms

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.

Learn more

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 Slack community to ask questions, give us feedback, and request a topic for the next tutorial!


Read more:

Publishing and Visualizing ROS 1 Transforms
tutorial
ROS
visualization
Publishing and Visualizing ROS 1 Transforms

Use Foxglove Studio to debug and edit your robot’s transforms

José L. MillánJosé L. MillánJosé L. Millán
Esther WeonEsther WeonEsther Weon
10 min read
Spotlight: Seth Winterroth on the Joys and Challenges of Working with Robotics Startups
interview
visualization
Spotlight: Seth Winterroth on the Joys and Challenges of Working with Robotics Startups

Investing in his audacious vision for a robot-powered world

Esther WeonEsther WeonEsther Weon
9 min read

Get blog posts sent directly to your inbox.

Ready to try Foxglove?

Get started for free