Odometry
Combines a 2D pose (position + heading) with a twist (velocity), covariance matrices, and coordinate frame IDs. The standard output from wheel encoders, visual odometry, or any localization system.
Python: Available via
horus.Odometry(x, y, theta, linear_velocity, angular_velocity). See Python Sensor Messages.ROS2 equivalent:
nav_msgs/Odometry— similar structure (pose + twist + covariances + frame IDs).
// simplified
use horus::prelude::*;
Quick Reference — Fields
| Field | Type | Unit | Description |
|---|---|---|---|
pose | Pose2D | m, rad | Current position (x, y) and heading (theta) |
twist | Twist | m/s, rad/s | Current velocity (linear + angular) |
pose_covariance | [f64; 36] | — | 6x6 row-major covariance for pose (x, y, z, roll, pitch, yaw) |
twist_covariance | [f64; 36] | — | 6x6 row-major covariance for velocity |
frame_id | [u8; 32] | — | Coordinate frame for pose (e.g., "odom", "map") |
child_frame_id | [u8; 32] | — | Coordinate frame for twist (e.g., "base_link") |
timestamp_ns | u64 | ns | Timestamp in nanoseconds since epoch |
Quick Reference — Methods
| Method | Returns | Description |
|---|---|---|
new() | Odometry | Creates at origin with zero velocity and current timestamp |
set_frames(frame, child_frame) | () | Sets coordinate frame IDs |
update(pose, twist) | () | Updates pose and velocity, refreshes timestamp |
is_valid() | bool | Checks if pose and twist contain finite values |
Constructor Methods
new()
Creates an odometry message at the origin with zero velocity.
Signature
// simplified
pub fn new() -> Self
Parameters
None.
Returns
Odometry — with these defaults:
pose:Pose2D::origin()(x=0, y=0, theta=0)twist:Twist::stop()(all zeros)pose_covariance:[0.0; 36]twist_covariance:[0.0; 36]frame_id: empty (set viaset_frames())child_frame_id: empty (set viaset_frames())timestamp_ns: current time viatimestamp_now()
Panics
Never.
Example
// simplified
use horus::prelude::*;
let mut odom = Odometry::new();
odom.pose = Pose2D { x: 1.5, y: 2.0, theta: 0.785, timestamp_ns: 0 };
odom.twist.linear[0] = 0.3; // forward velocity (m/s)
odom.twist.angular[2] = 0.05; // yaw rate (rad/s)
odom.set_frames("odom", "base_link");
let topic: Topic<Odometry> = Topic::new("odom")?;
topic.send(odom);
Python Constructor
Creates an odometry message from flat parameters.
Signature
Odometry(x=0.0, y=0.0, theta=0.0, linear_velocity=0.0, angular_velocity=0.0, timestamp_ns=0)
Parameters
| Name | Type | Required | Description |
|---|---|---|---|
x | f64 | no | Position X in meters. Default: 0.0. |
y | f64 | no | Position Y in meters. Default: 0.0. |
theta | f64 | no | Heading in radians. Default: 0.0. |
linear_velocity | f64 | no | Forward velocity in m/s. Default: 0.0. |
angular_velocity | f64 | no | Yaw rate in rad/s. Default: 0.0. |
timestamp_ns | u64 | no | Timestamp. Default: 0. |
Returns
Odometry instance.
Behavior
- Python provides flat property access:
odom.x,odom.y,odom.theta,odom.linear_velocity,odom.angular_velocity(all read/write) - Internally maps to the nested Rust struct:
x→pose.x,linear_velocity→twist.linear[0],angular_velocity→twist.angular[2]
Example
from horus import Odometry, Topic
odom = Odometry(x=1.5, y=2.0, theta=0.785, linear_velocity=0.3, angular_velocity=0.05)
odom.set_frames("odom", "base_link")
topic = Topic(Odometry)
topic.send(odom)
print(f"Position: ({odom.x}, {odom.y}), heading: {odom.theta}")
print(f"Velocity: {odom.linear_velocity} m/s, yaw: {odom.angular_velocity} rad/s")
Methods
set_frames(frame, child_frame)
Sets the coordinate frame IDs for this odometry message.
Signature
// simplified
pub fn set_frames(&mut self, frame: &str, child_frame: &str)
Parameters
| Name | Type | Required | Description |
|---|---|---|---|
frame | &str | yes | Coordinate frame for the pose (e.g., "odom", "map"). Max 31 characters. |
child_frame | &str | yes | Coordinate frame for the twist (e.g., "base_link"). Max 31 characters. |
Returns
Nothing (()).
Behavior
- Copies frame strings into fixed-size
[u8; 32]arrays with null termination - Strings longer than 31 characters are silently truncated
- Convention:
frame_idis the reference frame (where the pose is expressed),child_frame_idis the body frame (where the twist is expressed)
When to use
- Always — consumers need frame IDs to integrate odometry into the transform tree
- Standard convention:
frame_id = "odom",child_frame_id = "base_link"
Example
// simplified
use horus::prelude::*;
let mut odom = Odometry::new();
odom.set_frames("odom", "base_link");
update(pose, twist)
Updates the pose and twist, and refreshes the timestamp to the current time.
Signature
// simplified
pub fn update(&mut self, pose: Pose2D, twist: Twist)
Parameters
| Name | Type | Required | Description |
|---|---|---|---|
pose | Pose2D | yes | New position and heading estimate |
twist | Twist | yes | New velocity estimate |
Returns
Nothing (()).
Behavior
- Overwrites
self.poseandself.twist - Sets
self.timestamp_nsto the current time viatimestamp_now() - Does NOT update covariances — set those separately if needed
When to use
- Drive nodes that integrate wheel encoders each tick
- Fusion nodes that update the pose estimate
Example
// simplified
use horus::prelude::*;
fn tick(&mut self) {
let new_pose = Pose2D { x: self.x, y: self.y, theta: self.theta, timestamp_ns: 0 };
let new_twist = Twist {
linear: [self.speed, 0.0, 0.0],
angular: [0.0, 0.0, self.omega],
timestamp_ns: 0,
};
self.odom.update(new_pose, new_twist);
self.odom_pub.send(self.odom);
}
is_valid()
Checks whether the pose and twist contain finite values.
Signature
// simplified
pub fn is_valid(&self) -> bool
Parameters
None.
Returns
true if both self.pose.is_valid() and self.twist.is_valid() return true. false if any field is NaN or infinite.
When to use
- Validating odometry before feeding it to a planner or fusion node
- Detecting encoder faults or integration overflow
Production Example
Wheel encoder odometry node with frame IDs:
// simplified
use horus::prelude::*;
struct WheelOdom {
odom_pub: Topic<Odometry>,
odom: Odometry,
x: f64,
y: f64,
theta: f64,
}
impl Node for WheelOdom {
fn name(&self) -> &str { "WheelOdom" }
fn tick(&mut self) {
// Read encoders, compute dx, dtheta
let (dx, dtheta) = self.read_encoders();
self.x += dx * self.theta.cos();
self.y += dx * self.theta.sin();
self.theta += dtheta;
self.odom.pose = Pose2D {
x: self.x, y: self.y, theta: self.theta, timestamp_ns: 0,
};
self.odom.twist.linear[0] = dx * 100.0; // dx per tick * rate
self.odom.twist.angular[2] = dtheta * 100.0;
self.odom.set_frames("odom", "base_link");
self.odom_pub.send(self.odom);
}
}
See Also
- Sensor Messages (Rust) — Full Rust API
- Sensor Messages (Python) — Python API
- Pose2D — 2D position and heading
- Twist — 3D velocity
- Differential Drive Recipe — Publishes odometry from wheel encoders
- Multi-Sensor Fusion Recipe — Combine odometry with IMU