Python TransformFrame
HORUS provides a Python API for coordinate frame management — registering frames, updating transforms, and looking up transformations between any two frames in the tree.
Transform
A 3D rigid transformation (translation + quaternion rotation).
Creating Transforms
# simplified
from horus import Transform
# Identity transform
tf = Transform.identity()
# From translation and rotation quaternion
tf = Transform(translation=[1.0, 2.0, 0.0], rotation=[0.0, 0.0, 0.0, 1.0])
# From translation only (identity rotation)
tf = Transform.from_translation([1.0, 2.0, 3.0])
# From Euler angles (translation + roll/pitch/yaw)
tf = Transform.from_euler([1.0, 0.0, 0.5], [0.0, 0.1, 1.57])
# From 4x4 homogeneous matrix
tf = Transform.from_matrix(matrix_4x4)
Properties
# simplified
tf.translation # [x, y, z] as list of floats
tf.rotation # [x, y, z, w] quaternion as list of floats
Both are readable and writable:
# simplified
tf.translation = [2.0, 3.0, 0.0]
tf.rotation = [0.0, 0.0, 0.383, 0.924] # 45 degrees around Z
Methods
# simplified
# Convert to Euler angles
roll, pitch, yaw = tf.to_euler()
# Compose transforms: result = self * other
combined = parent_tf.compose(child_tf)
# Inverse transform
inv = tf.inverse()
# Apply to a point
point_in_world = tf.transform_point([1.0, 0.0, 0.0])
# Apply rotation only (no translation)
rotated = tf.transform_vector([1.0, 0.0, 0.0])
# Interpolate between two transforms (SLERP for rotation)
halfway = tf_a.interpolate(tf_b, t=0.5)
# Magnitudes
dist = tf.translation_magnitude() # Translation distance
angle = tf.rotation_angle() # Rotation angle in radians
# Export as 4x4 matrix
matrix = tf.to_matrix() # [[f64; 4]; 4]
| Method | Returns | Description |
|---|---|---|
identity() | Transform | No translation, no rotation |
from_translation([x,y,z]) | Transform | Translation only |
from_euler([x,y,z], [r,p,y]) | Transform | Translation + Euler angles |
from_matrix(4x4) | Transform | From homogeneous matrix |
to_euler() | [roll, pitch, yaw] | Get Euler angles |
compose(other) | Transform | Chain transforms (self * other) |
inverse() | Transform | Compute inverse |
transform_point([x,y,z]) | [x,y,z] | Apply full transform to point |
transform_vector([x,y,z]) | [x,y,z] | Apply rotation only to vector |
interpolate(other, t) | Transform | SLERP interpolation (0.0-1.0) |
translation_magnitude() | float | Translation distance |
rotation_angle() | float | Rotation angle in radians |
to_matrix() | 4x4 list | Export as homogeneous matrix |
TransformFrame
The frame tree manager. Stores a hierarchy of coordinate frames and computes transforms between any two frames.
Creating a TransformFrame
# simplified
from horus import TransformFrame, TransformFrameConfig
# Default configuration
tf_tree = TransformFrame()
# With custom config
config = TransformFrameConfig(max_frames=1024, history_len=64)
tf_tree = TransformFrame(config=config)
# Preset sizes
tf_tree = TransformFrame.small() # 256 frames, ~550KB
tf_tree = TransformFrame.medium() # 1024 frames, ~2.2MB
tf_tree = TransformFrame.large() # 4096 frames, ~9MB
tf_tree = TransformFrame.massive() # 16384 frames, ~35MB
Registering Frames
# simplified
# Register child frame under a parent — returns frame ID (int)
frame_id = tf_tree.register_frame("base_link", "world")
tf_tree.register_frame("lidar", "base_link")
tf_tree.register_frame("camera", "base_link")
# Unregister a frame (raises HorusNotFoundError if not found)
tf_tree.unregister_frame("camera")
Updating Transforms
# simplified
from horus import Transform
# Set the transform from parent to child (raises on unknown frame)
tf_tree.update_transform("base_link", Transform(
translation=[1.0, 0.0, 0.0],
rotation=[0.0, 0.0, 0.0, 1.0]
))
# With optional explicit timestamp
tf_tree.update_transform("lidar", Transform.from_translation([0.0, 0.0, 0.3]),
timestamp_ns=1234567890)
Looking Up Transforms
# simplified
# Get transform from source frame to target frame
tf = tf_tree.tf("lidar", "world")
print(f"Lidar in world: {tf.translation}")
# With specific timestamp (for interpolation)
tf = tf_tree.tf_at("lidar", "world", timestamp_ns=1234567890)
Querying the Tree
# simplified
# List all registered frames
frames = tf_tree.all_frames() # ["world", "base_link", "lidar", "camera"]
# Get parent of a frame
parent = tf_tree.parent("lidar") # "base_link"
# Get children of a frame
children = tf_tree.children("base_link") # ["lidar", "camera"]
# Seconds since last transform update (None if never updated)
age = tf_tree.time_since_last_update("lidar") # e.g., 0.015
# Wait for a transform to become available (blocking with timeout)
tf = tf_tree.wait_for_transform("lidar", "world", timeout_sec=1.0)
print(f"Got transform: {tf.translation}")
Frame Registration
| Method | Returns | Description |
|---|---|---|
register_frame(name, parent) | int | Register dynamic frame, returns frame ID |
register_static_frame(name, transform, parent=None) | int | Register frame with fixed transform |
unregister_frame(name) | None | Remove a frame |
has_frame(name) | bool | Check if frame exists |
frame_count() | int | Number of registered frames |
frame_id(name) | int | Get numeric frame ID from name |
frame_name(id) | str | Get frame name from numeric ID |
Updating Transforms
| Method | Returns | Description |
|---|---|---|
update_transform(name, tf, timestamp_ns=None) | None | Set transform for a frame |
update_transform_by_id(frame_id, tf, timestamp_ns=None) | None | Update by numeric ID (faster) |
set_static_transform(name, transform) | None | Set a static (never-changing) transform |
Looking Up Transforms
| Method | Returns | Description |
|---|---|---|
tf(source, target) | Transform | Latest transform between frames |
tf_at(source, target, ts) | Transform | Transform at specific timestamp (interpolated) |
tf_at_strict(source, target, ts) | Transform | Exact timestamp match (no interpolation) |
tf_at_with_tolerance(src, dst, ts, tolerance_ns=100_000_000) | Transform | Interpolated with tolerance window |
tf_by_id(src_id, dst_id) | Transform | Look up by numeric IDs (fastest) |
can_transform(source, target) | bool | Check if transform path exists |
can_transform_at(src, dst, ts) | bool | Check if available at timestamp |
can_transform_at_with_tolerance(src, dst, ts, tolerance_ns) | bool | Check with tolerance |
wait_for_transform(src, dst, timeout_sec) | Transform | Block until available |
wait_for_transform_async(src, dst, timeout_sec) | Future[Transform] | Async wait (returns concurrent.futures.Future) |
Applying Transforms
| Method | Returns | Description |
|---|---|---|
transform_point(source, target, [x,y,z]) | [x,y,z] | Transform a point between frames |
transform_vector(source, target, [x,y,z]) | [x,y,z] | Transform a vector (rotation only) |
Querying the Tree
| Method | Returns | Description |
|---|---|---|
all_frames() | list[str] | All registered frame names |
parent(name) | str or None | Parent frame name |
children(name) | list[str] | Child frame names |
frame_chain(source, target) | list[str] | Frame path from source to target |
time_since_last_update(name) | float or None | Seconds since last update |
is_stale(name, max_age_sec=1.0) | bool | Check if frame data is stale |
Diagnostics
| Method | Returns | Description |
|---|---|---|
stats() | dict | Frame tree statistics |
validate() | bool | Validate tree integrity |
frame_info(name) | dict | Metadata for a single frame |
frame_info_all() | list[dict] | Metadata for all frames |
format_tree() | str | Human-readable tree visualization |
frames_as_dot() | str | DOT graph format (for Graphviz) |
frames_as_yaml() | str | YAML export of frame tree |
stats() Return Value
The stats() method returns a dictionary with the following keys:
| Key | Type | Description |
|---|---|---|
total_frames | int | Total registered frames |
static_frames | int | Frames that never change |
dynamic_frames | int | Frames updated at runtime |
max_frames | int | Maximum capacity |
history_len | int | Transform history buffer size |
tree_depth | int | Maximum depth of the frame tree |
root_count | int | Number of root frames (no parent) |
# simplified
stats = tf_tree.stats()
print(f"Frames: {stats['total_frames']}/{stats['max_frames']}")
print(f"Tree depth: {stats['tree_depth']}, Roots: {stats['root_count']}")
frame_info(name) Return Value
The frame_info(name) method returns a dictionary with metadata for a single frame:
| Key | Type | Description |
|---|---|---|
name | str | Frame name |
id | int | Internal frame ID |
parent | str or None | Parent frame name (None for root) |
is_static | bool | Whether this frame never changes |
# simplified
info = tf_tree.frame_info("camera")
print(f"Frame: {info['name']}, Parent: {info['parent']}, Static: {info['is_static']}")
Advanced Usage
# simplified
# Static frames — set once, never changes
tf_tree.register_static_frame("lidar", Transform.from_translation([0.0, 0.0, 0.3]), parent="base_link")
# Transform points directly between frames
world_point = tf_tree.transform_point("lidar", "world", [5.0, 0.0, 0.0])
# Async wait (non-blocking)
import concurrent.futures
future = tf_tree.wait_for_transform_async("lidar", "world", timeout_sec=2.0)
tf = future.result() # Blocks until ready
# Check staleness before using data
if tf_tree.is_stale("base_link", max_age_sec=0.1):
print("Odometry data is stale!")
# Diagnostics
print(tf_tree.format_tree()) # Visual tree
print(tf_tree.stats()) # {"frames": 5, "lookups": 1234, ...}
tf_tree.validate() # Checks tree integrity
TransformFrameConfig
Configuration for the frame tree.
# simplified
from horus import TransformFrameConfig
# Custom
config = TransformFrameConfig(max_frames=512, history_len=16)
# Presets
config = TransformFrameConfig.small() # 256 frames, ~550KB
config = TransformFrameConfig.medium() # 1024 frames, ~2.2MB
config = TransformFrameConfig.large() # 4096 frames, ~9MB
config = TransformFrameConfig.massive() # 16384 frames, ~35MB
# Check memory usage
print(config.max_frames) # 512
print(config.history_len) # 16
print(config.memory_estimate()) # "~1.1MB"
Complete Example
# simplified
from horus import Node, Scheduler, TransformFrame, Transform
import math
# Global transform tree
tf_tree = TransformFrame.medium()
def setup_frames(node):
tf_tree.register_frame("base_link", "world")
tf_tree.register_frame("lidar", "base_link")
tf_tree.register_frame("camera", "base_link")
# Static transform: lidar is 30cm above base
tf_tree.update_transform("lidar", Transform.from_translation([0.0, 0.0, 0.3]))
# Static transform: camera is 10cm forward, 15cm up
tf_tree.update_transform("camera", Transform.from_translation([0.1, 0.0, 0.15]))
tick_count = 0
def odometry_tick(node):
global tick_count
tick_count += 1
# Simulate robot moving in a circle
t = tick_count * 0.01
x = math.cos(t) * 2.0
y = math.sin(t) * 2.0
yaw = t + math.pi / 2
# Update base_link in world
tf_tree.update_transform("base_link",
Transform.from_euler([x, y, 0.0], [0.0, 0.0, yaw]))
def perception_tick(node):
# Transform a lidar point into world coordinates
try:
lidar_to_world = tf_tree.tf("lidar", "world")
point_in_world = lidar_to_world.transform_point([5.0, 0.0, 0.0])
node.log_info(f"Obstacle at world: {point_in_world}")
except Exception:
pass # Frame not yet available
odom = Node(name="odom", tick=odometry_tick, init=setup_frames, rate=100, order=0)
percept = Node(name="perception", tick=perception_tick, rate=10, order=1)
scheduler = Scheduler()
scheduler.add(odom)
scheduler.add(percept)
scheduler.run(duration=10)
Utility
# simplified
from horus import get_timestamp_ns
# Get current time in nanoseconds (same clock as Rust)
now = get_timestamp_ns()
Error Handling
| Operation | Exception | When |
|---|---|---|
tf_tree.tf("missing", "world") | HorusNotFoundError | Frame not registered |
tf_tree.tf("lidar", "disconnected_tree") | HorusTransformError | No path between frames |
tf_tree.wait_for_transform(..., timeout_sec=1.0) | HorusTimeoutError | Transform not available within timeout |
tf_tree.unregister_frame("missing") | HorusNotFoundError | Frame doesn't exist |
tf_tree.register_frame("child", "missing_parent") | HorusNotFoundError | Parent frame not registered |
tf_tree.tf_at_strict(src, dst, stale_ts) | HorusTransformError | No exact timestamp match |
Transform.from_matrix(bad_matrix) | ValueError | Not a valid 4x4 matrix |
# simplified
from horus import HorusNotFoundError, HorusTransformError, HorusTimeoutError
# Safe transform lookup
try:
tf = tf_tree.tf("lidar", "world")
point_in_world = tf.transform_point([5.0, 0.0, 0.0])
except HorusNotFoundError:
pass # Frame not yet registered — skip this tick
except HorusTransformError as e:
print(f"Transform failed: {e}") # Stale data or disconnected tree
Design Decisions
Why SLERP for rotation interpolation? Linear interpolation of quaternions produces non-unit quaternions (invalid rotations). SLERP (Spherical Linear Interpolation) follows the shortest arc on the unit sphere, producing valid rotations at every interpolation step. This matters because transform lookups between timestamps use interpolation — incorrect interpolation means incorrect robot pose, which compounds through the frame tree.
Why bounded transform history instead of unlimited? Each frame stores the last N transforms (configurable via history_len). Unlimited history would leak memory in long-running robots. Bounded history means old transforms are discarded — if you query a timestamp older than the history window, you get a HorusTransformError. The default history length (64) covers ~1 second at typical update rates, which is sufficient for sensor fusion and safe enough for memory.
Why separate static and dynamic frames? Static frames (sensor mounts, fixed offsets) never change — storing history for them wastes memory and adds lookup overhead. register_static_frame() stores exactly one transform and skips interpolation. Dynamic frames (robot base, moving joints) need timestamped history for interpolation. Separating them lets the system optimize each case: static lookups are O(1) with no interpolation, dynamic lookups use binary search + SLERP.
Why lock-free shared memory for the frame tree? Multiple nodes read transforms concurrently (perception, control, visualization). A mutex-protected tree would serialize all readers, creating a bottleneck. The lock-free implementation uses atomic operations so readers never block each other or the writer. The cost is slightly more complex update logic, but the benefit is zero contention in multi-node systems.
See Also
- TransformFrame Concepts — Architecture and design
- Python Bindings — Core Python API
- Python Geometry Messages — TransformStamped type