TransformFrame Transform System

TransformFrame is HORUS's coordinate frame management system — a real-time-safe replacement for ROS2 TF2. It manages the spatial relationships between coordinate frames (e.g., "where is the camera relative to the robot base?") with lock-free lookups and sub-microsecond performance.

Why TransformFrame?

Problem with TF2TransformFrame Solution
Mutex-based lockingLock-free seqlock protocol
Unbounded latency spikesPredictable sub-microsecond latency
String-only frame lookupDual API: Integer IDs + Names
No hard real-time supportReal-time safe, no allocations in hot path

Performance

OperationTransformFrameROS2 TF2Speedup
Lookup by ID~50nsN/A-
Lookup by name~200ns~2us10x
Chain resolution (depth 3)~150ns~5us33x
Chain resolution (depth 10)~2.5us~15us6x
Concurrent reads (4 threads)~800ns~8us10x

Basic Usage

// simplified
use horus::prelude::*; // Provides TransformFrame, TransformFrameConfig, Transform, timestamp_now

// Create with default config (256 frames)
let hf = TransformFrame::new();

// Register frame hierarchy: world → base_link → camera
hf.register_frame("world", None)?;
hf.register_frame("base_link", Some("world"))?;
hf.register_frame("camera", Some("base_link"))?;

// Update transform (camera position relative to base_link)
let tf = Transform::new(
    [0.1, 0.0, 0.3],         // translation [x, y, z] in meters
    [0.0, 0.0, 0.0, 1.0],    // quaternion [x, y, z, w]
);
hf.update_transform("camera", &tf, timestamp_now())?;

// Query: where is camera relative to world?
let camera_to_world = hf.tf("camera", "world")?;
let point_in_world = camera_to_world.transform_point([1.0, 0.0, 0.0]);

Transform Type

// simplified
pub struct Transform {
    pub translation: [f64; 3],  // [x, y, z] in meters
    pub rotation: [f64; 4],     // quaternion [x, y, z, w] (Hamilton convention)
}

Creating Transforms

// simplified
// From translation + quaternion
let tf = Transform::new([1.0, 2.0, 3.0], [0.0, 0.0, 0.0, 1.0]);

// Translation only (identity rotation)
let tf = Transform::from_translation([1.0, 0.0, 0.0]);

// Rotation only (no translation)
let tf = Transform::from_rotation([0.0, 0.0, 0.0, 1.0]);

// From Euler angles (roll, pitch, yaw)
let tf = Transform::from_euler([1.0, 0.0, 0.0], [0.1, 0.2, 0.3]);

// From axis-angle (translation, axis, angle)
let tf = Transform::from_axis_angle([0.0, 0.0, 0.0], [0.0, 0.0, 1.0], std::f64::consts::PI / 2.0);

// Identity transform
let tf = Transform::identity();

Transform Operations

// simplified
// Compose two transforms
let composed = tf1.compose(&tf2);

// Invert a transform
let inverse = tf.inverse();

// Apply to a point (translation + rotation)
let point_world = tf.transform_point([1.0, 0.0, 0.0]);

// Apply to a vector (rotation only)
let vector_world = tf.transform_vector([1.0, 0.0, 0.0]);

// Interpolate between transforms (t=0.0 to 1.0)
// Uses linear interpolation for translation, SLERP for rotation
let tf_mid = tf1.interpolate(&tf2, 0.5);

// Convert to/from 4x4 matrix
let matrix = tf.to_matrix();
let tf = Transform::from_matrix(matrix);

// Extract Euler angles [roll, pitch, yaw]
let euler = tf.to_euler();

Frame Registration

Dynamic Frames

Dynamic frames have transforms that change over time (e.g., robot joints, camera tracking):

// simplified
// Register with parent relationship
let camera_id = hf.register_frame("camera", Some("base_link"))?;

// Root frame (no parent)
hf.register_frame("world", None)?;

// Update transform over time
hf.update_transform("camera", &new_tf, timestamp_now())?;

// Or use cached frame ID for faster updates
hf.update_transform_by_id(camera_id, &new_tf, timestamp_now());

Static Frames

Static frames have transforms that never change (e.g., sensor mounts, fixed offsets):

// simplified
// Register with initial transform
let mount_tf = Transform::from_translation([0.1, 0.0, 0.2]);
hf.register_static_frame("lidar_mount", Some("base_link"), &mount_tf)?;

// Update static transform (rare, e.g., recalibration)
hf.set_static_transform("lidar_mount", &new_tf)?;

Static frames use less memory since they don't maintain a history buffer.

Frame Queries

// simplified
// Get frame ID (cache this for hot paths!)
let id: Option<FrameId> = hf.frame_id("camera");

// Get frame name by ID
let name: Option<String> = hf.frame_name(id);

// Check if frame exists
if hf.has_frame("camera") { /* ... */ }

// List all frames
let all: Vec<String> = hf.all_frames();

// Get parent/children
let parent: Option<String> = hf.parent("camera");
let children: Vec<String> = hf.children("base_link");

Transform Lookups

By Name

// simplified
// Get transform from source frame to destination frame
let tf = hf.tf("camera", "world")?;

// Check if transform path exists
if hf.can_transform("camera", "world") {
    let tf = hf.tf("camera", "world")?;
}

By ID (Hot Path)

For control loops running at 1kHz+, cache frame IDs and use the ID-based API:

// simplified
// Cache IDs once at startup
let camera_id = hf.frame_id("camera").unwrap();
let world_id = hf.frame_id("world").unwrap();

// Use IDs in hot loop (~50ns vs ~200ns for name-based)
loop {
    let tf = hf.tf_by_id(camera_id, world_id);
    if let Some(tf) = tf {
        let target_in_world = tf.transform_point(target_in_camera);
        // Control logic...
    }
}

Time-Travel Queries

TransformFrame maintains a history buffer of past transforms, enabling queries at past timestamps with interpolation:

// simplified
// Get transform at a specific past time
let past = timestamp_now() - 100_000_000; // 100ms ago
let tf = hf.tf_at("camera", "world", past)?;

// ID-based version
let tf = hf.tf_at_by_id(camera_id, world_id, past);

If the exact timestamp isn't available, TransformFrame interpolates between the two nearest samples:

  • Translation: Linear interpolation
  • Rotation: SLERP (Spherical Linear Interpolation)

Configuration

Presets

// simplified
// Default / Small (256 frames, ~550KB)
let hf = TransformFrame::new();       // Same as TransformFrame::small()
let hf = TransformFrame::small();

// Medium (1024 frames, ~2.2MB)
let hf = TransformFrame::medium();

// Large (4096 frames, ~9MB)
let hf = TransformFrame::large();
PresetFramesStaticHistoryCacheMemory
small()2561283264~550KB
medium()102451232128~2.2MB
large()4096204832256~9MB

Additional presets for simulation:

// simplified
// Massive (16384 frames, ~35MB) - 100+ robot simulations
let hf = TransformFrame::with_config(TransformFrameConfig::massive());

// Unlimited frames (HashMap overflow for dynamic environments)
let hf = TransformFrame::with_config(TransformFrameConfig::unlimited());

Custom Configuration

// simplified
let hf = TransformFrame::with_config(TransformFrameConfig {
    max_frames: 2048,           // Total frames (16-65536)
    max_static_frames: 1024,    // Static frames (less memory, faster)
    history_len: 64,            // Past transforms per dynamic frame (4-256)
    enable_overflow: false,     // Allow HashMap for unlimited frames
    chain_cache_size: 256,      // LRU cache for chain lookups
});

Or use the builder:

// simplified
let hf = TransformFrame::with_config(
    TransformFrameConfig::custom()
        .max_frames(512)
        .history_len(64)
        .build()?
);

CLI Tools

HORUS provides CLI equivalents of ROS2 tf2 tools:

# List all coordinate frames
horus tf list
horus tf list --json     # JSON output

# Echo transform between frames (like ros2 run tf2_ros tf2_echo)
horus tf echo camera base_link
horus tf echo camera world --rate 10  # 10 Hz

# Show frame tree (like ros2 run tf2_tools view_frames)
horus tf tree

# Get detailed info about a specific frame
horus tf info camera

# Check if transform exists between two frames
horus tf can camera world

# Monitor transform update rates
horus tf hz

Statistics and Inspection

TransformFrameStats

Get system-wide statistics via tf.stats():

// simplified
let stats = hf.stats();
println!("{}", stats.summary());
println!("Frames: {}/{}", stats.total_frames, stats.max_frames);
println!("Tree depth: {}, Roots: {}", stats.tree_depth, stats.root_count);
FieldTypeDescription
total_framesusizeTotal registered frames
static_framesusizeFrames that never change
dynamic_framesusizeFrames updated at runtime
max_framesusizeMaximum capacity
history_lenusizeTransform history buffer size
tree_depthusizeMaximum depth of the frame tree
root_countusizeNumber of root frames (no parent)

FrameInfo

Get metadata for a specific frame via tf.frame_info(name):

// simplified
if let Some(info) = hf.frame_info("camera_link") {
    println!("Frame: {}, Parent: {:?}, Static: {}", info.name, info.parent, info.is_static);
}
FieldTypeDescription
nameStringFrame name
idFrameIdInternal frame ID
parentOption<String>Parent frame name (None for root)
is_staticboolWhether this frame never changes

Diagnostics

// simplified
// Validate frame tree integrity
hf.validate()?;

Design Decisions

Why Lock-Free Seqlock Instead of Mutex

Coordinate frame lookups happen inside control loops running at 1kHz or faster. A mutex-based design (as in ROS2 TF2) means a writer updating a transform can block readers — and in a real-time system, priority inversion from mutex contention causes unbounded latency spikes. TransformFrame uses a seqlock protocol: writers increment a sequence number before and after updating, and readers retry if they detect a concurrent write. This guarantees that readers never block, even under heavy write load. The worst case for a reader is a retry (~50ns extra), not an unbounded wait.

Why Dual API (Integer IDs + String Names)

String-based frame lookups require hashing and comparison on every call — acceptable for setup code but wasteful in a 1kHz control loop that looks up the same frames every tick. TransformFrame provides both: string-based registration (register_frame("camera", ...)) for clarity at startup, and integer ID-based lookups (tf_by_id(camera_id, world_id)) for the hot path. Users cache frame IDs once during initialization and use them in the loop body, cutting lookup time from ~200ns to ~50ns. The string API remains available for introspection, CLI tools, and non-performance-critical code.

Why Built-In Instead of a Separate Package

In ROS2, TF2 is a separate package that must be installed, configured, and launched independently. This creates a common failure mode: new users forget to run a transform broadcaster, and their system silently produces wrong results. TransformFrame is part of horus_library and available via use horus::prelude::* — no extra dependency, no separate process, no configuration. Every HORUS project has access to coordinate transforms by default. The CLI (horus tf list, horus tf echo) also works out of the box without installing additional tools.

Trade-offs

AreaBenefitCost
Seqlock protocolReaders never block; predictable sub-microsecond latency under contentionReaders may retry during a concurrent write — rare but adds ~50ns when it happens
Integer ID API~50ns lookups in hot paths — 4x faster than string-basedUsers must cache IDs at startup; using IDs without caching defeats the purpose
History bufferTime-travel queries with interpolation for sensor fusion and replayFixed-size ring buffer per dynamic frame (default 32 entries) consumes memory even if time-travel is unused
Pre-allocated frame slotsNo heap allocation during runtime — real-time safe after initializationMaximum frame count must be chosen at startup; exceeding it requires enable_overflow (which uses a HashMap and is not RT-safe)
Built-in to horus_libraryZero-config availability, no forgotten dependenciesAdds to the base library size even for projects that do not use coordinate transforms
Static frame optimizationStatic frames skip the history buffer — less memory, faster lookupsChanging a static frame (e.g., recalibration) requires an explicit set_static_transform call instead of the normal update_transform path

See Also