Skip to content

Transforms

Practical

Transforms are mathematical objects that describe the position and orientation of one coordinate frame relative to another. They are the foundation of robotics math, enabling robots to understand spatial relationships between the world, their body, sensors, and objects they interact with.

Prerequisites

Coordinate Frames

A coordinate frame is a reference point with three axes (x, y, z). Every robot component has its own frame:

z
|
|
+----→ y
/
/
x
ROS Convention (REP-103):
x = forward
y = left
z = up

Standard frames in a robot system (REP-105):

FrameDescription
mapGlobal world-fixed frame
odomOdometry frame (continuous but drifts)
base_linkRobot body center
sensor_frameIndividual sensor frames

Homogeneous Transformation Matrices

Transforms are represented as 4x4 matrices combining rotation and translation:

T = | R p | R = 3x3 rotation matrix
| 0 1 | p = 3x1 translation vector
| r₁₁ r₁₂ r₁₃ px |
T = | r₂₁ r₂₂ r₂₃ py |
| r₃₁ r₃₂ r₃₃ pz |
| 0 0 0 1 |

Key properties:

  • Composable: T_world_gripper = T_world_base @ T_base_gripper
  • Invertible: T⁻¹ gives the reverse transform
  • Non-commutative: T₁ × T₂ ≠ T₂ × T₁

Rotation Representations

RepresentationSizeProsCons
Rotation Matrix9 valuesFast compositionRedundant, numerical drift
Euler Angles3 valuesHuman-readableGimbal lock, 24 conventions
Quaternion4 valuesCompact, no gimbal lockLess intuitive
Axis-Angle4 valuesIntuitive single rotationComposition harder

Gimbal Lock

When two rotation axes align, you lose a degree of freedom:

Normal: Gimbal Lock (pitch = 90°):
Roll ──┐ Roll ─────┐
│ │ (same axis!)
Pitch ─┤ Pitch ────┘
Yaw ───┘ Yaw (lost!)

Solution: Use quaternions internally, Euler angles only for display.

ROS 2 TF2 System

TF2 maintains a tree of transforms between all frames:

map
└── odom
└── base_link
├── camera_link
│ └── camera_optical
├── lidar_link
└── arm_base
└── gripper

Broadcasting Transforms

import rclpy
from rclpy.node import Node
from tf2_ros import TransformBroadcaster
from geometry_msgs.msg import TransformStamped
import tf_transformations
class TFBroadcaster(Node):
def __init__(self):
super().__init__('tf_broadcaster')
self.broadcaster = TransformBroadcaster(self)
self.timer = self.create_timer(0.1, self.broadcast)
def broadcast(self):
t = TransformStamped()
t.header.stamp = self.get_clock().now().to_msg()
t.header.frame_id = 'base_link'
t.child_frame_id = 'camera_link'
# Translation: 10cm forward, 20cm up
t.transform.translation.x = 0.1
t.transform.translation.y = 0.0
t.transform.translation.z = 0.2
# Rotation: quaternion (no rotation here)
t.transform.rotation.w = 1.0
self.broadcaster.sendTransform(t)

Listening for Transforms

from tf2_ros import Buffer, TransformListener
from rclpy.duration import Duration
class TFListener(Node):
def __init__(self):
super().__init__('tf_listener')
self.tf_buffer = Buffer()
self.tf_listener = TransformListener(self.tf_buffer, self)
def get_transform(self):
try:
transform = self.tf_buffer.lookup_transform(
'base_link', # target frame
'camera_link', # source frame
rclpy.time.Time(),
timeout=Duration(seconds=1.0)
)
return transform
except Exception as e:
self.get_logger().error(f'Lookup failed: {e}')

Python: SciPy Transforms

import numpy as np
from scipy.spatial.transform import Rotation
# Create rotation (90° about Z-axis)
rot = Rotation.from_euler('z', 90, degrees=True)
# Apply to a point
point = np.array([1.0, 0.0, 0.0])
rotated = rot.apply(point)
# Result: [0, 1, 0]
# Convert between representations
quat = rot.as_quat() # [x, y, z, w]
matrix = rot.as_matrix() # 3x3
euler = rot.as_euler('xyz', degrees=True)

C++: Eigen Transforms

#include <Eigen/Geometry>
// Create rigid transform
Eigen::Isometry3d T = Eigen::Isometry3d::Identity();
// Set rotation (90° about Z)
T.rotate(Eigen::AngleAxisd(M_PI_2, Eigen::Vector3d::UnitZ()));
// Set translation
T.pretranslate(Eigen::Vector3d(1.0, 0.0, 0.5));
// Apply to point
Eigen::Vector3d p(1.0, 0.0, 0.0);
Eigen::Vector3d result = T * p;
// Compose and invert
Eigen::Isometry3d T_combined = T1 * T2;
Eigen::Isometry3d T_inv = T.inverse();

Debugging Tools

Terminal window
# Visualize TF tree as 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 --z 0.2 \
--frame-id base_link --child-frame-id sensor

Learn More

Sources