Message Types
HORUS provides 70+ standard message types for robotics. Pick the right ones for your robot:
| I'm building a... | Start with these messages |
|---|---|
| Mobile robot | CmdVel, Odometry, LaserScan, Imu, BatteryState |
| Robot arm | JointState, JointCommand, WrenchStamped, TrajectoryPoint |
| Drone | Imu, NavSatFix, MotorCommand, BatteryState, Pose3D |
| Vision system | Image, Detection, PointCloud, DepthImage, CameraInfo |
| Multi-robot | Pose2D, Heartbeat, DiagnosticStatus, TransformStamped |
| Teleoperation | JoystickInput, CmdVel, EmergencyStop |
| Industrial | JointState, MotorCommand, ForceCommand, DiagnosticReport |
Need a custom type? Use the message! macro — it handles serialization and optimization automatically:
// simplified
use horus::prelude::*;
message! {
pub struct MotorFeedback {
pub motor_id: u32,
pub velocity: f32,
pub current_amps: f32,
pub temperature_c: f32,
}
}
let topic: Topic<MotorFeedback> = Topic::new("motor.feedback")?;
All built-in messages use fixed-size structures with zero-copy shared memory transport (~50ns latency).
For zero-copy performance, make your type POD — see POD Types for details.
Typed Messages vs Generic Messages
Typed Messages (Recommended)
Strongly-typed Rust structs — all available via use horus::prelude::*:
// simplified
use horus::prelude::*;
let topic: Topic<Pose2D> = Topic::new("robot.pose")?;
topic.send(Pose2D::new(1.0, 2.0, 0.5));
Benefits:
- Ultra-fast: ~50-167ns IPC latency (zero-copy shared memory for POD types)
- Type safety: Compile-time checks prevent type mismatches
- IDE support: Autocomplete, type hints, inline documentation
- Cross-language: Rust and Python see the same typed data
Generic Messages (Prototyping)
Dynamic data for arbitrary structures using GenericMessage:
// simplified
use horus::prelude::*;
let topic: Topic<GenericMessage> = Topic::new("custom_data")?;
let data = GenericMessage::from_value(&my_dynamic_data)?;
topic.send(data);
GenericMessage uses MessagePack serialization with a 4KB maximum payload. It has an inline buffer for small messages (≤256 bytes) and an overflow buffer for larger ones.
Tradeoffs:
- Flexible — any data structure, evolving schemas
- Slower IPC — serialization overhead vs zero-copy POD types
- No compile-time type safety
Use generic messages for quick prototypes, external JSON integrations, or truly dynamic schemas. Default to typed messages for production code.
Performance Comparison
| Feature | Typed Messages | Generic Messages |
|---|---|---|
| IPC Latency | ~50-167ns (POD) | Higher (serialization) |
| Type Safety | Compile-time | Runtime only |
| IDE Support | Full autocomplete | None |
| Best For | Production | Prototyping |
LogSummary Trait
The LogSummary trait provides human-readable summaries for logging. It is not required for basic Topic::new() usage, but is required if you want logging via Topic::verbose flag (via TUI monitor).
// simplified
pub trait LogSummary {
fn log_summary(&self) -> String;
}
When is LogSummary Used?
Topic::new("name")?— noLogSummaryrequired, no logging overheadTopic::new("name")?— requiresT: LogSummary, enables logging on send/recv
When logging is active, log_summary() is called once per send/recv. Logs appear in the console and in horus monitor.
Deriving LogSummary
For most types, derive the trait to get Debug formatting automatically:
// simplified
use horus::prelude::*;
#[derive(Debug, Clone, Serialize, Deserialize, LogSummary)]
pub struct RobotState {
pub position: [f64; 3],
pub velocity: f64,
pub battery_level: f32,
}
// log_summary() outputs: RobotState { position: [1.0, 2.0, 0.0], velocity: 1.5, battery_level: 0.85 }
Custom Implementation for Large Types
For types where Debug output would be too large (images, point clouds, scans), implement LogSummary manually:
// simplified
use horus::prelude::*;
impl LogSummary for MyLargeMessage {
fn log_summary(&self) -> String {
format!("MyMsg({} items, {:.2}MB)", self.count, self.size_mb())
}
}
Guidelines:
- Keep summaries concise — they appear inline in logs
- Include units (meters, rad/s, %) to make values unambiguous
- Log metadata about the message, not the full content
Built-in LogSummary Implementations
LogSummary is implemented for:
- Primitive types:
f32,f64,i32,i64,u32,u64,usize,bool,String - Messages:
CmdVel,CompressedImage,CameraInfo,RegionOfInterest,StereoInfo,NavSatFix,GenericMessage - Descriptors:
ImageDescriptor,PointCloudDescriptor,DepthImageDescriptor,Tensor - Any type that derives
#[derive(LogSummary)](usesDebugformatting)
Geometry Messages
Spatial primitives for position, orientation, and motion. All are POD types.
CmdVel
Basic 2D velocity command:
// simplified
use horus::prelude::*;
let cmd = CmdVel::new(1.0, 0.5); // 1.0 m/s forward, 0.5 rad/s rotation
let stop = CmdVel::zero();
let cmd = CmdVel::with_timestamp(1.0, 0.5, 123456789);
| Field | Type | Description |
|---|---|---|
stamp_nanos | u64 | Timestamp in nanoseconds |
linear | f32 | Forward velocity in m/s |
angular | f32 | Rotation velocity in rad/s |
Twist
3D velocity with linear and angular components:
// simplified
use horus::prelude::*;
// 2D twist (common for mobile robots)
let cmd = Twist::new_2d(1.0, 0.5); // 1.0 m/s forward, 0.5 rad/s rotation
// 3D twist
let cmd_3d = Twist::new(
[1.0, 0.5, 0.0], // Linear velocity [x, y, z] m/s
[0.0, 0.0, 0.5] // Angular velocity [roll, pitch, yaw] rad/s
);
let stop = Twist::stop();
assert!(cmd.is_valid());
| Field | Type | Description |
|---|---|---|
linear | [f64; 3] | Linear velocity in m/s |
angular | [f64; 3] | Angular velocity in rad/s |
timestamp_ns | u64 | Nanoseconds since epoch |
Pose2D
2D position and orientation for planar robots:
// simplified
use horus::prelude::*;
let pose = Pose2D::new(1.0, 2.0, 0.5); // x=1m, y=2m, theta=0.5rad
let origin = Pose2D::origin();
let distance = pose.distance_to(&origin);
// Normalize angle to [-π, π]
let mut pose = Pose2D::new(1.0, 2.0, 3.5);
pose.normalize_angle();
| Field | Type | Description |
|---|---|---|
x | f64 | X position in meters |
y | f64 | Y position in meters |
theta | f64 | Orientation in radians |
timestamp_ns | u64 | Nanoseconds since epoch |
TransformStamped
3D transformation with translation and rotation:
// simplified
use horus::prelude::*;
let identity = TransformStamped::identity();
let tf = TransformStamped::new(
[1.0, 2.0, 3.0], // Translation [x, y, z]
[0.0, 0.0, 0.0, 1.0] // Rotation quaternion [x, y, z, w]
);
// From 2D pose
let pose2d = Pose2D::new(1.0, 2.0, 0.5);
let tf = TransformStamped::from_pose_2d(&pose2d);
// Normalize quaternion
let mut tf = tf;
tf.normalize_rotation();
| Field | Type | Description |
|---|---|---|
translation | [f64; 3] | Position in meters |
rotation | [f64; 4] | Quaternion [x, y, z, w] |
timestamp_ns | u64 | Nanoseconds since epoch |
Point3, Vector3, Quaternion
3D points, vectors, and rotations:
// simplified
use horus::prelude::*;
// Point
let point = Point3::new(1.0, 2.0, 3.0);
let distance = point.distance_to(&Point3::origin());
// Vector with operations
let vec = Vector3::new(1.0, 0.0, 0.0);
let magnitude = vec.magnitude();
let dot = vec.dot(&Vector3::new(0.0, 1.0, 0.0));
let cross = vec.cross(&Vector3::new(0.0, 1.0, 0.0));
// Quaternion
let q = Quaternion::identity();
let q = Quaternion::from_euler(0.0, 0.0, std::f64::consts::PI / 2.0);
Sensor Messages
Standard sensor data formats. All are POD types.
LaserScan
2D lidar scan data (up to 360 points):
// simplified
use horus::prelude::*;
let mut scan = LaserScan::new();
scan.ranges[0] = 5.2;
scan.angle_min = -std::f32::consts::PI;
scan.angle_max = std::f32::consts::PI;
scan.range_min = 0.1;
scan.range_max = 30.0;
scan.angle_increment = std::f32::consts::PI / 180.0;
let angle = scan.angle_at(45);
if scan.is_range_valid(0) {
println!("Range: {}m", scan.ranges[0]);
}
let valid = scan.valid_count();
if let Some(min) = scan.min_range() {
println!("Closest: {}m", min);
}
| Field | Type | Description |
|---|---|---|
ranges | [f32; 360] | Range readings in meters (0 = invalid) |
angle_min / angle_max | f32 | Scan angle range in radians |
range_min / range_max | f32 | Valid range limits in meters |
angle_increment | f32 | Angular resolution in radians |
time_increment | f32 | Time between measurements |
scan_time | f32 | Time to complete scan in seconds |
timestamp_ns | u64 | Nanoseconds since epoch |
Imu
Inertial Measurement Unit data:
// simplified
use horus::prelude::*;
let mut imu = Imu::new();
imu.set_orientation_from_euler(0.1, 0.2, 1.5); // roll, pitch, yaw
imu.angular_velocity = [0.1, 0.2, 0.3]; // rad/s
imu.linear_acceleration = [0.0, 0.0, 9.81]; // m/s²
if imu.has_orientation() {
let quat = imu.orientation;
}
assert!(imu.is_valid());
| Field | Type | Description |
|---|---|---|
orientation | [f64; 4] | Quaternion [x, y, z, w] |
orientation_covariance | [f64; 9] | 3x3 covariance matrix |
angular_velocity | [f64; 3] | Gyroscope data in rad/s |
angular_velocity_covariance | [f64; 9] | 3x3 covariance matrix |
linear_acceleration | [f64; 3] | Accelerometer data in m/s² |
linear_acceleration_covariance | [f64; 9] | 3x3 covariance matrix |
timestamp_ns | u64 | Nanoseconds since epoch |
Odometry
Combined pose and velocity from wheel encoders or visual odometry:
// simplified
use horus::prelude::*;
let mut odom = Odometry::new();
odom.set_frames("odom", "base_link");
let pose = Pose2D::new(1.0, 2.0, 0.5);
let twist = Twist::new_2d(0.5, 0.2);
odom.update(pose, twist);
| Field | Type | Description |
|---|---|---|
pose | Pose2D | Current position and orientation |
twist | Twist | Current velocity |
pose_covariance | [f64; 36] | 6x6 covariance matrix |
twist_covariance | [f64; 36] | 6x6 covariance matrix |
frame_id | [u8; 32] | Reference frame (e.g., "odom") |
child_frame_id | [u8; 32] | Child frame (e.g., "base_link") |
timestamp_ns | u64 | Nanoseconds since epoch |
Range
Single-point distance sensor (ultrasonic, infrared):
// simplified
use horus::prelude::*;
let range = Range::new(Range::ULTRASONIC, 1.5);
let mut range = Range::new(Range::INFRARED, 0.8);
range.min_range = 0.02;
range.max_range = 4.0;
range.field_of_view = 0.1;
| Field | Type | Description |
|---|---|---|
sensor_type | u8 | Range::ULTRASONIC (0) or Range::INFRARED (1) |
field_of_view | f32 | Sensor FOV in radians |
min_range / max_range | f32 | Valid range limits in meters |
range | f32 | Distance reading in meters |
timestamp_ns | u64 | Nanoseconds since epoch |
BatteryState
Battery status and charge information:
// simplified
use horus::prelude::*;
let mut battery = BatteryState::new(12.6, 75.0); // 12.6V, 75% charge
battery.current = -2.5;
battery.temperature = 28.5;
battery.power_supply_status = BatteryState::STATUS_DISCHARGING;
if battery.is_low(20.0) {
println!("Battery low!");
}
if battery.is_critical() { // Below 10%
println!("Battery critical!");
}
if let Some(time_left) = battery.time_remaining() {
println!("Time remaining: {}s", time_left);
}
| Field | Type | Description |
|---|---|---|
voltage | f32 | Battery voltage in volts |
current | f32 | Current in amperes (negative = discharging) |
charge | f32 | Remaining charge in Ah |
capacity | f32 | Total capacity in Ah |
percentage | f32 | Charge percentage (0-100) |
power_supply_status | u8 | STATUS_UNKNOWN (0), STATUS_CHARGING (1), STATUS_DISCHARGING (2), STATUS_FULL (3) |
temperature | f32 | Temperature in °C |
cell_voltages | [f32; 16] | Individual cell voltages |
cell_count | u8 | Number of cells |
timestamp_ns | u64 | Nanoseconds since epoch |
NavSatFix
GPS position data:
| Field | Type | Description |
|---|---|---|
latitude / longitude / altitude | f64 | WGS84 coordinates |
position_covariance | [f64; 9] | 3x3 covariance matrix |
status | u8 | Fix status |
satellites_visible | u16 | Number of satellites |
hdop / vdop | f32 | Dilution of precision |
speed / heading | f32 | Speed (m/s) and heading (rad) |
timestamp_ns | u64 | Nanoseconds since epoch |
Control Messages
Actuator commands and control parameters. All are POD types.
MotorCommand
Direct motor control:
| Field | Type | Description |
|---|---|---|
motor_id | u32 | Motor identifier |
mode | f32 | Control mode |
target | f32 | Target value |
max_velocity / max_acceleration | f32 | Limits |
feed_forward | f32 | Feed-forward term |
enable | u8 | Enable flag |
timestamp_ns | u64 | Nanoseconds since epoch |
DifferentialDriveCommand
Differential drive control (left/right wheels):
| Field | Type | Description |
|---|---|---|
left_velocity / right_velocity | f32 | Wheel velocities in m/s |
max_acceleration | f32 | Acceleration limit |
enable | u8 | Enable flag |
timestamp_ns | u64 | Nanoseconds since epoch |
ServoCommand
Servo position/velocity control:
| Field | Type | Description |
|---|---|---|
servo_id | u32 | Servo identifier |
position / speed | f32 | Target position and speed |
enable | u8 | Enable flag |
timestamp_ns | u64 | Nanoseconds since epoch |
JointCommand
Multi-joint position/velocity/effort (up to 16 joints):
| Field | Type | Description |
|---|---|---|
joint_names | [[u8; 32]; 16] | Joint names |
joint_count | u8 | Number of active joints |
positions / velocities / efforts | [f64; 16] | Joint commands |
modes | [u8; 16] | Control mode per joint |
timestamp_ns | u64 | Nanoseconds since epoch |
PidConfig
PID controller parameters:
| Field | Type | Description |
|---|---|---|
controller_id | u32 | Controller identifier |
kp / ki / kd | f64 | PID gains |
integral_limit / output_limit | f64 | Limits |
anti_windup | u8 | Anti-windup flag |
timestamp_ns | u64 | Nanoseconds since epoch |
TrajectoryPoint
Single point in a trajectory:
| Field | Type | Description |
|---|---|---|
position / velocity / acceleration | [f64; 3] | 3D motion |
orientation | [f64; 4] | Quaternion [x, y, z, w] |
angular_velocity | [f64; 3] | Angular velocity |
time_from_start | f64 | Time offset in seconds |
Vision Messages
Image and camera data types.
Image
RAII image type with zero-copy shared memory backing. Pixel data lives in shared memory — only a lightweight descriptor is transmitted through topics.
// simplified
use horus::prelude::*;
// Note: args are (height, width, encoding)
let mut img = Image::new(480, 640, ImageEncoding::Rgb8)?;
img.set_pixel(100, 200, &[255, 0, 0]); // Set pixel at (x=100, y=200)
let pixels: &[u8] = img.data(); // Zero-copy access
Accessor methods:
| Method | Returns | Description |
|---|---|---|
width() | u32 | Image width in pixels |
height() | u32 | Image height in pixels |
encoding() | ImageEncoding | Pixel format |
channels() | u32 | Number of channels |
step() | u32 | Row stride in bytes |
data() / data_mut() | &[u8] / &mut [u8] | Zero-copy pixel data |
pixel(x, y) | Option<&[u8]> | Get a single pixel |
set_pixel(x, y, val) | &mut Self | Set a single pixel |
copy_from(buf) | &mut Self | Copy pixel data from buffer |
fill(val) | &mut Self | Fill entire image |
roi(x, y, w, h) | Option<Vec<u8>> | Extract region of interest |
frame_id() | &str | Camera frame |
timestamp_ns() | u64 | Nanoseconds since epoch |
Supported encodings: Mono8, Mono16, Rgb8, Bgr8, Rgba8, Bgra8, Yuv422, Mono32F, Rgb32F, BayerRggb8, Depth16
CompressedImage
JPEG/PNG compressed images (variable-size, not POD):
| Field | Type | Description |
|---|---|---|
format | [u8; 8] | Compression format string |
data | Vec<u8> | Compressed image data |
width / height | u32 | Image dimensions |
frame_id | [u8; 32] | Camera frame |
timestamp_ns | u64 | Nanoseconds since epoch |
CameraInfo
Camera calibration parameters (POD type):
| Field | Type | Description |
|---|---|---|
width / height | u32 | Image dimensions |
distortion_model | [u8; 16] | Distortion model name |
distortion_coefficients | [f64; 8] | Distortion coefficients |
camera_matrix | [f64; 9] | 3x3 intrinsic matrix |
rectification_matrix | [f64; 9] | 3x3 rectification matrix |
projection_matrix | [f64; 12] | 3x4 projection matrix |
frame_id | [u8; 32] | Camera frame |
timestamp_ns | u64 | Nanoseconds since epoch |
StereoInfo
Stereo camera parameters (POD type):
| Field | Type | Description |
|---|---|---|
left_camera / right_camera | CameraInfo | Per-camera calibration |
baseline | f64 | Baseline distance in meters |
depth_scale | f64 | Depth scaling factor |
Methods: depth_from_disparity(), disparity_from_depth()
Large Data (Zero-Copy)
For most use cases, use the high-level domain types (Image, PointCloud, DepthImage) — they use zero-copy shared memory transport automatically and provide domain-specific convenience methods like pixel(), point_at(), and get_depth().
// simplified
use horus::prelude::*;
// Create an image (backed by shared memory automatically)
let mut img = Image::new(1080, 1920, ImageEncoding::Rgb8)?;
// ... fill pixels via img.data_mut() or img.set_pixel() ...
let topic: Topic<Image> = Topic::new("camera.rgb")?;
topic.send(&img);
// Receiver gets zero-copy access
if let Some(img) = topic.recv() {
println!("{}x{} {:?}", img.width(), img.height(), img.encoding());
}
Only a lightweight descriptor is transmitted through topics while the actual data stays in shared memory. For low-level tensor transport (ML inference, custom pipelines), Topic<Tensor> provides direct access to the same zero-copy shared memory path with raw shape/dtype control.
Detection Messages
Object detection results. All are POD types.
BoundingBox2D / BoundingBox3D
2D and 3D bounding boxes:
| Type | Fields |
|---|---|
BoundingBox2D | x, y, width, height (all f32) |
BoundingBox3D | cx, cy, cz (center), length, width, height, roll, pitch, yaw (all f32) |
Detection / Detection3D
2D and 3D object detections:
| Field | Type | Description |
|---|---|---|
bbox | BoundingBox2D or BoundingBox3D | Bounding box |
confidence | f32 | Detection confidence |
class_id | u32 | Class identifier |
class_name | [u8; 32] | Class name string |
instance_id | u32 | Instance identifier |
Detection3D also includes velocity: [f32; 3].
Perception Messages
3D perception data types.
PointCloud
RAII point cloud type with zero-copy shared memory backing. Point data lives in shared memory — only a lightweight descriptor is transmitted through topics.
// simplified
use horus::prelude::*;
// Create XYZ cloud: (num_points, fields_per_point, dtype)
let cloud = PointCloud::from_xyz(\&points)? // 1000 points; // 1000 XYZ points
let cloud = PointCloud::from_xyz(\&points) // 1000 points, 6 fields?; // 1000 XYZRGB points
Accessor methods:
| Method | Returns | Description |
|---|---|---|
point_count() | u64 | Number of points |
fields_per_point() | u32 | Floats per point (3=XYZ, 4=XYZI, 6=XYZRGB) |
dtype() | TensorDtype | Data type of components |
is_xyz() | bool | Whether this is a plain XYZ cloud |
has_intensity() | bool | Whether cloud has intensity |
has_color() | bool | Whether cloud has color |
data() / data_mut() | &[u8] / &mut [u8] | Zero-copy point data |
point_at(idx) | Option<&[u8]> | Get the i-th point as bytes |
extract_xyz() | Option<Vec<[f32; 3]>> | Extract all XYZ coordinates |
copy_from(buf) | &mut Self | Copy point data from buffer |
frame_id() | &str | Reference frame |
timestamp_ns() | u64 | Nanoseconds since epoch |
Fixed-Size Point Types (POD)
For zero-copy point cloud processing:
| Type | Fields | Description |
|---|---|---|
PointXYZ | x, y, z (f32) | 3D point |
PointXYZRGB | x, y, z (f32), r, g, b, a (u8) | Colored point |
PointXYZI | x, y, z, intensity (f32) | Point with intensity |
DepthImage
RAII depth image type with zero-copy shared memory backing. Supports both F32 (meters) and U16 (millimeters) formats.
// simplified
use horus::prelude::*;
let mut depth = DepthImage::meters(480, 640)?; // F32 meters
depth.set_depth(100, 200, 1.5); // Set depth at (x=100, y=200)
Accessor methods:
| Method | Returns | Description |
|---|---|---|
width() / height() | u32 | Image dimensions |
dtype() | TensorDtype | Data type (F32 or U16) |
is_meters() | bool | Whether F32 depth in meters |
is_millimeters() | bool | Whether U16 depth in mm |
depth_scale() | f32 | Depth scale factor |
data() / data_mut() | &[u8] / &mut [u8] | Zero-copy depth data |
get_depth(x, y) | Option<f32> | Get depth at pixel (meters) |
set_depth(x, y, val) | &mut Self | Set depth at pixel |
get_depth_u16(x, y) | Option<u16> | Get raw U16 depth |
depth_statistics() | (f32, f32, f32) | (min, max, mean) in meters |
frame_id() | &str | Reference frame |
timestamp_ns() | u64 | Nanoseconds since epoch |
Navigation Messages
Path planning and navigation types.
Goal / GoalResult
Navigation goal and result (both POD):
// simplified
use horus::prelude::*;
let goal = Goal::new(Pose2D::new(5.0, 3.0, 0.0), 0.1, 0.05); // pose, position_tol, angle_tol
let goal = goal.with_timeout(30.0).with_priority(1);
if goal.is_reached(¤t_pose) {
println!("Goal reached!");
}
Goal fields: target_pose (Pose2D), tolerance_position, tolerance_angle, timeout_seconds (f64), priority (u8), goal_id (u32), timestamp_ns (u64)
GoalResult fields: goal_id (u32), status (u8), distance_to_goal (f64), eta_seconds (f64), progress (f32), error_message ([u8; 64]), timestamp_ns (u64)
GoalStatus values: Pending, Active, Succeeded, Aborted, Cancelled, Preempted, TimedOut
Waypoint / Path
Waypoints and paths (both POD):
// simplified
use horus::prelude::*;
let wp = Waypoint::new(Pose2D::new(1.0, 2.0, 0.0));
let wp = wp.with_velocity(Twist::new_2d(0.5, 0.0)).with_stop();
let mut path = Path::new();
path.add_waypoint(wp);
Path holds up to 256 waypoints with fields for total_length, duration_seconds, frame_id, algorithm, and timestamp_ns.
PathPlan
Compact planned path (POD, fixed-size):
| Field | Type | Description |
|---|---|---|
waypoint_data | [f32; 768] | 256 waypoints × 3 floats (x, y, theta) |
goal_pose | [f32; 3] | Target pose |
waypoint_count | u16 | Number of waypoints |
timestamp_ns | u64 | Nanoseconds since epoch |
OccupancyGrid
2D occupancy map (variable-size, not POD — uses serialization):
// simplified
let mut grid = OccupancyGrid::new(200, 200, 0.05, Pose2D::origin()); // 200x200, 5cm resolution
if let Some((gx, gy)) = grid.world_to_grid(1.0, 2.0) {
grid.set_occupancy(gx, gy, 100); // Mark occupied (grid coords)
}
// is_free/is_occupied take world coordinates directly
if grid.is_free(1.0, 2.0) { /* navigable */ }
if grid.is_occupied(1.0, 2.0) { /* blocked */ }
Values: -1 = unknown, 0 = free, 100 = occupied.
CostMap
Cost map for path planning (variable-size, not POD):
// simplified
let costmap = CostMap::from_occupancy_grid(grid, 0.55); // 55cm inflation radius
let cost = costmap.cost(1.0, 2.0); // Get cost at world coordinates
VelocityObstacle / VelocityObstacles
For velocity obstacle-based collision avoidance (both POD). VelocityObstacles holds up to 32 velocity obstacles.
Diagnostics Messages
Health monitoring and safety. All are POD types.
Heartbeat
Node liveness signal:
| Field | Type | Description |
|---|---|---|
node_name | [u8; 32] | Node name |
node_id | u32 | Node identifier |
sequence | u64 | Sequence number |
alive | u8 | Alive flag |
uptime | f64 | Uptime in seconds |
timestamp_ns | u64 | Nanoseconds since epoch |
NodeHeartbeat
Detailed per-node health status:
| Field | Type | Description |
|---|---|---|
state / health | u8 | Node state and health |
tick_count | u32 | Total ticks executed |
target_rate / actual_rate | f32 | Expected vs actual tick rate |
error_count | u32 | Error counter |
last_tick_timestamp / heartbeat_timestamp | u64 | Timestamps |
Status
General status report:
| Field | Type | Description |
|---|---|---|
level | u8 | Severity level |
code | u32 | Status code |
message | [u8; 128] | Status message |
component | [u8; 32] | Component name |
timestamp_ns | u64 | Nanoseconds since epoch |
EmergencyStop
Emergency stop signal:
| Field | Type | Description |
|---|---|---|
engaged | u8 | E-stop engaged flag |
reason | [u8; 64] | Reason string |
source | [u8; 32] | Source of e-stop |
auto_reset | u8 | Auto-reset flag |
timestamp_ns | u64 | Nanoseconds since epoch |
SafetyStatus
Safety system state:
| Field | Type | Description |
|---|---|---|
enabled, estop_engaged, watchdog_ok, limits_ok, comms_ok | u8 | Status flags |
mode | u8 | Safety mode |
fault_code | u32 | Fault code |
timestamp_ns | u64 | Nanoseconds since epoch |
ResourceUsage
CPU/memory monitoring:
| Field | Type | Description |
|---|---|---|
cpu_percent / memory_percent / disk_percent | f32 | Usage percentages |
memory_bytes / disk_bytes | u64 | Usage in bytes |
network_tx_bytes / network_rx_bytes | u64 | Network traffic |
temperature | f32 | Temperature in °C |
thread_count | u32 | Thread count |
timestamp_ns | u64 | Nanoseconds since epoch |
DiagnosticValue / DiagnosticReport
Key-value diagnostics: DiagnosticValue holds a single key-value pair. DiagnosticReport groups up to 16 DiagnosticValue entries with a component name and severity level.
Force/Haptics Messages
Force sensing and haptic feedback. All are POD types.
| Message | Description |
|---|---|
WrenchStamped | Force/torque measurement with point of application |
ImpedanceParameters | Impedance control parameters (stiffness, damping, inertia) |
ForceCommand | Force control command with target force/torque |
ContactInfo | Contact detection state, force, normal, and point |
HapticFeedback | Haptic output command (vibration, force feedback) |
Input Messages
Human input devices. All are POD types.
| Message | Description |
|---|---|
JoystickInput | Gamepad/joystick state (buttons, axes, hats) |
KeyboardInput | Keyboard key events with modifier flags |
Segmentation, Landmark, and Tracking Messages
Computer vision pipeline types. All are POD types.
| Message | Description |
|---|---|
SegmentationMask | Semantic/instance/panoptic segmentation mask descriptor |
Landmark / Landmark3D | 2D/3D keypoints with visibility |
LandmarkArray | Set of landmarks (supports COCO, MediaPipe Pose/Hand/Face presets) |
TrackedObject | Tracked object with bbox, velocity, age, and state |
TrackingHeader | Tracking frame header with active track count |
Custom Messages
Basic Custom Message
// simplified
use serde::{Serialize, Deserialize};
use horus::prelude::*;
#[derive(Debug, Clone, Serialize, Deserialize)]
pub struct RobotStatus {
pub battery_level: f32,
pub temperature: f32,
pub error_code: u32,
pub timestamp_ns: u64,
}
let topic: Topic<RobotStatus> = Topic::new("robot_status")?;
topic.send(RobotStatus {
battery_level: 75.0,
temperature: 42.0,
error_code: 0,
timestamp_ns: timestamp_now(),
});
POD Custom Message (Zero-Copy)
For maximum performance, make your type POD-compatible:
// simplified
use horus::prelude::*;
message! {
MotorFeedback {
timestamp_ns: u64,
motor_id: u32,
velocity: f32,
current_amps: f32,
temperature_c: f32,
}
}
// Ready to use with Topic<MotorFeedback> — zero-copy automatically
let topic: Topic<MotorFeedback> = Topic::new("motor.feedback")?;
See POD Types for full requirements.
Adding LogSummary
To enable logging with Topic::verbose flag (via TUI monitor):
// simplified
use horus::prelude::*;
// Option 1: Derive (uses Debug formatting)
#[derive(Debug, Clone, Serialize, Deserialize, LogSummary)]
pub struct SmallMessage { /* ... */ }
// Option 2: Manual (for large types)
impl LogSummary for LargeMessage {
fn log_summary(&self) -> String {
format!("LargeMsg({} items)", self.count)
}
}
Working with Messages in Nodes
Publishing
// simplified
use horus::prelude::*;
struct LidarNode {
scan_pub: Topic<LaserScan>,
}
impl Node for LidarNode {
fn name(&self) -> &str { "LidarNode" }
fn tick(&mut self) {
let mut scan = LaserScan::new();
scan.ranges[0] = 5.2;
self.scan_pub.send(scan);
}
}
Subscribing
// simplified
struct ObstacleDetector {
scan_sub: Topic<LaserScan>,
}
impl Node for ObstacleDetector {
fn name(&self) -> &str { "ObstacleDetector" }
fn tick(&mut self) {
if let Some(scan) = self.scan_sub.recv() {
if let Some(min_range) = scan.min_range() {
if min_range < 0.5 {
// Obstacle too close!
}
}
}
}
}
GenericMessage
Dynamic message type for cross-language communication (Rust <-> Python). Uses MessagePack serialization internally. Maximum payload: 4KB.
// simplified
use horus::prelude::*;
use serde::{Serialize, Deserialize};
#[derive(Serialize, Deserialize)]
struct SensorReading { temperature: f64, humidity: f64 }
// Create from any serializable type
let reading = SensorReading { temperature: 22.5, humidity: 60.0 };
let msg = GenericMessage::from_value(&reading)?;
// Send through a topic
let topic: Topic<GenericMessage> = Topic::new("sensor.generic")?;
topic.send(msg);
// Receive and deserialize
if let Some(msg) = topic.recv() {
let reading: SensorReading = msg.to_value()?;
println!("Temperature: {}", reading.temperature);
}
Key Methods
| Method | Description |
|---|---|
GenericMessage::new(bytes) | Create from raw bytes |
GenericMessage::from_value(v) | Serialize any Serialize type |
GenericMessage::with_metadata(bytes, meta) | Create with metadata string |
.data() | Get raw byte payload |
.metadata() | Get metadata string (if set) |
.to_value::<T>() | Deserialize to any Deserialize type |
Performance
- Small messages (≤256 bytes): ~4.0 us (inline fast path)
- Large messages (>256 bytes): ~4.4 us (overflow buffer)
- Maximum payload: 4096 bytes
- Uses zero-copy IPC for transport
When to Use
- Cross-language communication — Python and Rust nodes sharing untyped data
- Prototyping — Quick iteration before defining typed messages
- ML pipelines — Flexible model outputs with varying schemas
- Metadata tagging — Attach routing or context info via the metadata field
For production code with known schemas, prefer typed messages for compile-time safety and ~50x lower serialization overhead.
Clock & Time Messages
| Message | Description | API Reference |
|---|---|---|
Clock | Simulation/replay time broadcast (clock_ns, sim_speed, paused) | Clock API |
TimeReference | External time sync from GPS/NTP/PTP (time_ref_ns, source, offset) | Clock API |
Audio Messages
| Message | Description | API Reference |
|---|---|---|
AudioFrame | Microphone audio data (up to 4800 samples, configurable sample rate and channels) | AudioFrame |
AudioEncoding | Encoding format enum: F32 or I16 | AudioFrame |
Design Decisions
Why Standard Message Types Instead of User-Defined Only
Robotics has well-established data formats — IMU readings, velocity commands, laser scans, odometry — that every project needs. Requiring users to define these from scratch creates fragmentation: two teams building lidar drivers would produce incompatible LaserScan types with different field names, units, and layouts. HORUS ships 70+ standard messages so that any driver, algorithm, or tool can interoperate out of the box. A motor controller from one team works with a path planner from another because both use CmdVel with the same field layout and units.
Why Rust Structs Instead of IDL Files
ROS2 uses .msg and .srv Interface Definition Language files that require a code generation step (rosidl) before compilation. This adds build complexity, creates generated code that is hard to debug, and forces a separate toolchain dependency. HORUS defines messages as plain Rust structs with derive macros. They are normal Rust code — debuggable, IDE-navigable, and compiled with the rest of the project. The message! macro and #[derive(Serialize, Deserialize)] handle serialization without a separate code generation pipeline. Python bindings are generated via PyO3, not from IDL.
Why Fixed-Size Types Get Automatic Zero-Copy
Fixed-size (POD) types have a known memory layout at compile time — every LaserScan is exactly the same number of bytes regardless of content. This means they can be written directly into shared memory and read by another process without any serialization or deserialization. HORUS detects POD types at compile time and routes them through the zero-copy path automatically (~50ns latency). Variable-size types (like OccupancyGrid with its Vec<i8> data) use MessagePack serialization because their size is not known until runtime. Users get the fastest possible transport for each type without manual optimization.
Trade-offs
| Area | Benefit | Cost |
|---|---|---|
| Standard library | Instant interoperability between all HORUS packages and drivers | Users must learn the standard types; custom types may duplicate existing ones |
| Rust-native definitions | No code generation step, full IDE support, normal debugging | Message definitions are tied to Rust — Python types are mirrored via PyO3, not generated from a shared IDL |
| Zero-copy POD | ~50ns latency for fixed-size types with no serialization overhead | POD types have fixed-size arrays (e.g., [f32; 360] for LaserScan) — wastes memory when actual data is smaller |
message! macro | One-line POD message definition with automatic zero-copy transport | Custom messages must be POD-compatible (no Vec, String, Option) to get zero-copy; otherwise they fall back to serialization |
| GenericMessage | Flexible prototyping with any data shape, cross-language support | 4KB payload limit, serialization overhead, no compile-time type safety |
| No IDL | Simpler build, fewer dependencies, no generated code to maintain | No automatic multi-language type generation from a single source — Python types must be manually kept in sync |
See Also
- POD Types — Zero-serialization for maximum performance
- Tensor Messages — Tensor, Device, TensorDtype, and tensor domain types
- Image API — Pool-backed camera images
- Topic — The unified communication API
- Basic Examples — Working examples with messages
- Architecture — How messages fit into HORUS