Skip to content

TF2

Practical

TF2 (Transform Library 2) is ROS 2’s system for tracking coordinate frame relationships over time. It maintains a time-buffered tree of transforms, enabling robots to answer spatial questions like “Where was the gripper relative to the base 2 seconds ago?” or “What is the camera’s current pose in world coordinates?”

Prerequisites

Why TF2 Matters

  • Sensor fusion: Combine data from sensors in different locations
  • Motion planning: Know where the gripper is relative to the target
  • Time travel: Query where things were, not just where they are
  • Distributed: All ROS 2 nodes can access transforms from anywhere in the system

Architecture

┌─────────────────────────────────────────────────────────────┐
│ Your ROS 2 Nodes │
├─────────────────────────────────────────────────────────────┤
│ TransformBroadcaster TransformListener │
│ (publishes transforms) (receives transforms) │
│ │ │ │
│ ▼ ▼ │
│ /tf, /tf_static ┌─────────┐ │
│ (topics) │ Buffer │ │
│ │(10s log)│ │
│ └─────────┘ │
├─────────────────────────────────────────────────────────────┤
│ tf2_ros Package │
├─────────────────────────────────────────────────────────────┤
│ tf2 Core Library │
└─────────────────────────────────────────────────────────────┘

The Transform Tree

Frames form a directed tree — each frame has exactly one parent:

map ← World-fixed (from SLAM)
└── odom ← Continuous but drifts
└── base_link ← Robot body
├── camera_link
│ └── camera_optical_frame
├── lidar_link
└── arm_base_link
└── arm_link_1
└── ... → gripper_link

Static vs Dynamic Transforms

TypeTopicPurposeExample
Static/tf_staticFixed relationships, published onceSensor mounts
Dynamic/tfContinuously updated, time-stampedJoint positions, odometry

Use static transforms for sensors bolted to the robot — they’re more efficient than repeatedly publishing the same transform.

Broadcasting Transforms

import rclpy
from rclpy.node import Node
from tf2_ros import TransformBroadcaster
from geometry_msgs.msg import TransformStamped
import tf_transformations
class FrameBroadcaster(Node):
def __init__(self):
super().__init__('frame_broadcaster')
self.tf_broadcaster = TransformBroadcaster(self)
self.timer = self.create_timer(0.1, self.broadcast_callback)
def broadcast_callback(self):
t = TransformStamped()
t.header.stamp = self.get_clock().now().to_msg()
t.header.frame_id = 'odom'
t.child_frame_id = 'base_link'
# Translation
t.transform.translation.x = 1.0
t.transform.translation.y = 2.0
t.transform.translation.z = 0.0
# Rotation (quaternion from yaw)
q = tf_transformations.quaternion_from_euler(0, 0, 0.5)
t.transform.rotation.x = q[0]
t.transform.rotation.y = q[1]
t.transform.rotation.z = q[2]
t.transform.rotation.w = q[3]
self.tf_broadcaster.sendTransform(t)
def main():
rclpy.init()
rclpy.spin(FrameBroadcaster())
rclpy.shutdown()

Listening for Transforms

import rclpy
from rclpy.node import Node
from rclpy.duration import Duration
from tf2_ros import Buffer, TransformListener
from tf2_ros import LookupException, ConnectivityException, ExtrapolationException
class FrameListener(Node):
def __init__(self):
super().__init__('frame_listener')
self.tf_buffer = Buffer()
self.tf_listener = TransformListener(self.tf_buffer, self)
self.timer = self.create_timer(1.0, self.on_timer)
def on_timer(self):
try:
transform = self.tf_buffer.lookup_transform(
'base_link', # Target frame
'camera_link', # Source frame
rclpy.time.Time(), # Latest available
timeout=Duration(seconds=1.0)
)
pos = transform.transform.translation
self.get_logger().info(f'Camera at: ({pos.x:.2f}, {pos.y:.2f}, {pos.z:.2f})')
except LookupException:
self.get_logger().warn('Frame not found')
except ConnectivityException:
self.get_logger().warn('Frames not connected')
except ExtrapolationException:
self.get_logger().warn('Transform not available at requested time')

Time and Lookups

Time = 0 Means “Latest”

# Get the most recent transform available
transform = tf_buffer.lookup_transform('base_link', 'camera_link', rclpy.time.Time())

Time Travel

Query where a frame was at a past time:

from rclpy.time import Time
from rclpy.duration import Duration
now = self.get_clock().now()
past = now - Duration(seconds=5.0)
# Where was camera_link 5 seconds ago?
transform = tf_buffer.lookup_transform(
'base_link',
'camera_link',
past.to_msg(),
timeout=Duration(seconds=1.0)
)

CLI Tools

Terminal window
# Visualize the frame tree (generates frames.pdf)
ros2 run tf2_tools view_frames
# Print live transform between frames
ros2 run tf2_ros tf2_echo base_link camera_link
# Publish a static transform
ros2 run tf2_ros static_transform_publisher \
--x 0.1 --y 0.0 --z 0.2 \
--roll 0.0 --pitch 0.0 --yaw 0.0 \
--frame-id base_link \
--child-frame-id camera_link
# Monitor transform tree health
ros2 run tf2_ros tf2_monitor

Common Exceptions

ExceptionCauseSolution
LookupExceptionFrame not in treeCheck if broadcaster is running
ConnectivityExceptionNo path between framesVerify tree structure
ExtrapolationExceptionTime outside bufferUse Time() for latest, or check timestamp
TimeoutExceptionTransform not available in timeIncrease timeout or check publishers

TF2 Packages

PackagePurpose
tf2Core library (ROS-agnostic)
tf2_rosROS 2 bindings (Buffer, Listener, Broadcaster)
tf2_geometry_msgsTransform geometry_msgs types
tf2_sensor_msgsTransform PointCloud2 data
tf2_toolsCLI utilities (view_frames, tf2_echo)

NVIDIA Isaac Integration

Isaac Sim publishes transforms via the ROS 2 bridge. Best practice:

  • Use robot_state_publisher to publish static transforms from URDF
  • Let Isaac Sim publish joint states
  • Isaac ROS packages (cuVSLAM, etc.) publish standard TF2 transforms

Learn More

Sources