Library Reference
The HORUS Standard Library (horus_library) provides ready-to-use message types, nodes, algorithms, and tools for robotics applications. Use these components to accelerate development and ensure compatibility across projects.
Overview
The library includes:
- Standard Messages - Memory-safe message types for common robotics data
- Pre-built Nodes - Ready-to-use nodes for sensors, actuators, and control
- Example Applications - Complete multi-node demonstrations
- Development Tools - Simulators and testing utilities
Installation:
[dependencies]
horus_library = "0.1"
Import:
use horus_library::prelude::*;
// Or specific items:
use horus_library::{CmdVel, LaserScan, PidControllerNode};
Standard Messages
All messages are designed for shared memory safety with fixed-size fields.
Motion & Control
CmdVel
Velocity command for mobile robots.
pub struct CmdVel {
pub linear: f64, // Linear velocity (m/s)
pub angular: f64, // Angular velocity (rad/s)
}
Size: 16 bytes Latency: 296ns
Usage:
let cmd = CmdVel {
linear: 1.5, // Move forward at 1.5 m/s
angular: 0.5, // Turn at 0.5 rad/s
};
cmd_hub.send(cmd, ctx).ok();
Twist
Full 3D velocity (position and orientation).
pub struct Twist {
pub linear: Vector3, // Linear velocity (m/s)
pub angular: Vector3, // Angular velocity (rad/s)
}
pub struct Vector3 {
pub x: f64,
pub y: f64,
pub z: f64,
}
Size: 48 bytes Use for: Drones, robotic arms, 3D movement
PIDState
PID controller state.
pub struct PIDState {
pub kp: f64, // Proportional gain
pub ki: f64, // Integral gain
pub kd: f64, // Derivative gain
pub setpoint: f64, // Target value
pub error: f64, // Current error
pub integral: f64, // Accumulated integral
pub derivative: f64, // Error derivative
pub output: f64, // Control output
}
Size: 64 bytes
Sensors
LaserScan
2D LIDAR scan data.
pub struct LaserScan {
pub ranges: [f32; 360], // Distance readings (m)
pub angle_min: f32, // Start angle (rad)
pub angle_max: f32, // End angle (rad)
pub angle_increment: f32, // Angular resolution
pub time_increment: f32, // Time between readings
pub scan_time: f32, // Total scan time
pub range_min: f32, // Minimum valid range
pub range_max: f32, // Maximum valid range
}
Size: 1.5 KB Latency: 1.31µs
Usage:
if let Some(scan) = lidar_hub.recv(ctx) {
for (i, range) in scan.ranges.iter().enumerate() {
if *range < 0.5 { // Obstacle within 0.5m
ctx.log_warning("Obstacle detected!");
}
}
}
IMU
Inertial Measurement Unit data.
pub struct IMU {
pub orientation: Quaternion, // Orientation
pub angular_velocity: Vector3, // Gyroscope (rad/s)
pub linear_acceleration: Vector3, // Accelerometer (m/s²)
pub timestamp: u64, // Microseconds
}
pub struct Quaternion {
pub w: f64,
pub x: f64,
pub y: f64,
pub z: f64,
}
Size: 304 bytes Latency: 718ns
Image
Camera image data.
pub struct Image {
pub width: u32,
pub height: u32,
pub encoding: ImageEncoding,
pub data: [u8; MAX_IMAGE_SIZE], // Fixed-size buffer
}
pub enum ImageEncoding {
RGB8, // 8-bit RGB
BGR8, // 8-bit BGR
MONO8, // 8-bit grayscale
JPEG, // JPEG compressed
}
Note: For high-resolution images, consider using zero-copy loan() API.
Navigation
Odometry
Robot position and velocity estimate.
pub struct Odometry {
pub pose: Pose, // Position estimate
pub twist: Twist, // Velocity estimate
pub timestamp: u64,
}
pub struct Pose {
pub position: Vector3,
pub orientation: Quaternion,
}
Size: 736 bytes Latency: 650ns
Path
Navigation path.
pub struct Path {
pub waypoints: [Pose; MAX_WAYPOINTS],
pub length: usize,
pub timestamp: u64,
}
Use for: Path planning, trajectory following
Input
KeyboardInput
Keyboard events.
pub struct KeyboardInput {
pub key: KeyCode,
pub event: KeyEvent,
pub modifiers: KeyModifiers,
}
pub enum KeyCode {
Up, Down, Left, Right,
W, A, S, D,
Space, Enter, Esc,
// ... full keyboard
}
pub enum KeyEvent {
Press,
Release,
}
Size: 16 bytes
Usage:
if let Some(input) = keyboard_hub.recv(ctx) {
match (input.key, input.event) {
(KeyCode::W, KeyEvent::Press) => move_forward(),
(KeyCode::Space, KeyEvent::Press) => stop(),
_ => {}
}
}
JoystickInput
Game controller input.
pub struct JoystickInput {
pub axes: [f32; 8], // Analog axes [-1.0, 1.0]
pub buttons: [bool; 16], // Button states
pub timestamp: u64,
}
Typical mapping:
axes[0]- Left stick Xaxes[1]- Left stick Yaxes[2]- Right stick Xaxes[3]- Right stick Ybuttons[0]- A buttonbuttons[1]- B button
Diagnostics
Health
Node health status.
pub struct Health {
pub status: HealthStatus,
pub cpu_percent: f32,
pub memory_mb: u64,
pub error_count: u32,
pub warning_count: u32,
pub message: [u8; 256], // Status message
}
pub enum HealthStatus {
Healthy,
Warning,
Error,
Critical,
}
SystemInfo
System diagnostics.
pub struct SystemInfo {
pub cpu_usage: f32,
pub memory_usage: u64,
pub disk_usage: u64,
pub network_tx: u64,
pub network_rx: u64,
pub uptime_seconds: u64,
}
Pre-Built Nodes
Sensor Nodes
CameraNode
Captures images from camera.
Usage:
use horus_library::CameraNode;
let camera = CameraNode::new(
"/dev/video0", // Device path
"camera/image", // Output topic
30 // FPS
)?;
scheduler.register(Box::new(camera), 0, Some(true));
Topics:
- Publishes:
camera/imageImage
Features:
- V4L2 support (Linux)
- Multiple encodings (RGB, BGR, JPEG)
- Configurable resolution and FPS
- Auto-exposure
LidarNode
Captures 2D laser scans.
Usage:
use horus_library::LidarNode;
let lidar = LidarNode::new(
"/dev/ttyUSB0", // Serial port
"scan" // Output topic
)?;
scheduler.register(Box::new(lidar), 0, Some(true));
Topics:
- Publishes:
scanLaserScan
Supported devices:
- RPLidar A1/A2/A3
- Hokuyo URG-04LX
- SICK TiM series
ImuNode
Reads IMU data.
Usage:
use horus_library::ImuNode;
let imu = ImuNode::new(
"/dev/i2c-1", // I2C device
"imu/data" // Output topic
)?;
scheduler.register(Box::new(imu), 0, Some(true));
Topics:
- Publishes:
imu/dataIMU
Supported sensors:
- MPU6050, MPU9250
- BNO055
- ICM-20948
Input Nodes
KeyboardInputNode
Captures keyboard events.
Usage:
use horus_library::KeyboardInputNode;
let keyboard = KeyboardInputNode::new("keyboard/input")?;
scheduler.register(Box::new(keyboard), 0, Some(true));
Topics:
- Publishes:
keyboard/inputKeyboardInput
Features:
- Non-blocking input
- Terminal mode (raw input)
- Modifier key support
JoystickInputNode
Reads game controller input.
Usage:
use horus_library::JoystickInputNode;
let joystick = JoystickInputNode::new(
0, // Controller ID
"joystick/input" // Output topic
)?;
scheduler.register(Box::new(joystick), 0, Some(true));
Topics:
- Publishes:
joystick/inputJoystickInput
Supported:
- Xbox controllers
- PlayStation controllers
- Generic USB gamepads
Control Nodes
PidControllerNode
PID controller implementation.
Usage:
use horus_library::PidControllerNode;
let pid = PidControllerNode::new(
1.0, // Kp
0.1, // Ki
0.01, // Kd
"setpoint", // Setpoint topic
"feedback", // Feedback topic
"control_output" // Output topic
)?;
scheduler.register(Box::new(pid), 5, Some(true));
Topics:
- Subscribes:
setpointf64,feedbackf64 - Publishes:
control_outputf64
Features:
- Anti-windup protection
- Derivative filtering
- Output clamping
- Configurable sample rate
DifferentialDriveNode
Differential drive controller.
Usage:
use horus_library::DifferentialDriveNode;
let drive = DifferentialDriveNode::new(
"cmd_vel", // Input topic
"motor/left", // Left motor topic
"motor/right", // Right motor topic
0.2 // Wheel separation (m)
)?;
scheduler.register(Box::new(drive), 10, Some(true));
Topics:
- Subscribes:
cmd_velCmdVel - Publishes:
motor/leftf64,motor/rightf64
Features:
- Inverse kinematics
- Velocity limiting
- Acceleration smoothing
Safety Nodes
EmergencyStopNode
Emergency stop handler.
Usage:
use horus_library::EmergencyStopNode;
let estop = EmergencyStopNode::new(
"emergency_stop", // E-stop signal topic
"cmd_vel" // Velocity topic to override
)?;
scheduler.register(Box::new(estop), 0, Some(true));
Topics:
- Subscribes:
emergency_stopbool,cmd_velCmdVel - Publishes:
cmd_velCmdVel(zeroed when e-stop active)
Features:
- Zero latency override
- Automatic hold-off period
- Status reporting
SafetyMonitorNode
System safety monitoring.
Usage:
use horus_library::SafetyMonitorNode;
let safety = SafetyMonitorNode::new(
"system/health" // Health output topic
)?;
// Add monitored topics
safety.monitor_topic("scan", 100); // Expect updates every 100ms
safety.monitor_topic("imu/data", 50);
scheduler.register(Box::new(safety), 0, Some(true));
Topics:
- Subscribes: Any monitored topics
- Publishes:
system/healthHealth
Features:
- Timeout detection
- Message rate monitoring
- CPU/memory monitoring
- Automatic alerts
Navigation Nodes
PathPlannerNode
A* path planning.
Usage:
use horus_library::PathPlannerNode;
let planner = PathPlannerNode::new(
"map", // Map topic
"goal", // Goal pose topic
"path" // Output path topic
)?;
scheduler.register(Box::new(planner), 5, Some(true));
Topics:
- Subscribes:
mapOccupancyGrid,goalPose - Publishes:
pathPath
Algorithms:
- A* search
- Dijkstra
- RRT (Rapidly-exploring Random Tree)
LocalizationNode
Particle filter localization.
Usage:
use horus_library::LocalizationNode;
let localization = LocalizationNode::new(
"scan", // LIDAR input
"odom", // Odometry input
"pose" // Pose estimate output
)?;
scheduler.register(Box::new(localization), 5, Some(true));
Topics:
- Subscribes:
scanLaserScan,odomOdometry - Publishes:
posePose
Industrial Nodes
ModbusNode
Modbus TCP/RTU communication.
Usage:
use horus_library::ModbusNode;
let modbus = ModbusNode::new(
"192.168.1.100:502", // Modbus TCP address
"modbus/input", // Input register topic
"modbus/output" // Output register topic
)?;
scheduler.register(Box::new(modbus), 10, Some(true));
Topics:
- Subscribes:
modbus/outputModbusWrite - Publishes:
modbus/inputModbusRead
Features:
- TCP and RTU support
- Read coils, inputs, holding registers
- Write coils, holding registers
- Error handling and retries
Hardware Interface Nodes
ServoControllerNode
Multi-channel servo control.
Usage:
use horus_library::ServoControllerNode;
let servos = ServoControllerNode::new(
"/dev/ttyACM0", // Serial port
"servo/command" // Command topic
)?;
scheduler.register(Box::new(servos), 10, Some(true));
Topics:
- Subscribes:
servo/commandServoCommand
Features:
- Multi-channel (up to 16)
- PWM control
- Position/velocity/torque modes
EncoderNode
Quadrature encoder reading.
Usage:
use horus_library::EncoderNode;
let encoder = EncoderNode::new(
17, 18, // GPIO pins (BCM numbering)
"encoder/ticks" // Output topic
)?;
scheduler.register(Box::new(encoder), 0, Some(true));
Topics:
- Publishes:
encoder/ticksi64
Example Applications
SnakeSim
Multi-node snake game demonstration.
Architecture:
KeyboardInputNode (priority 0)
──> SnakeControlNode (priority 2)
──> GUINode (priority 3)
Run:
cd horus_library/apps/snakesim/snake_scheduler
cargo run --release
Key concepts:
- Multi-node coordination
- Input handling
- Game state management
- Terminal rendering
TankSim
Tank physics simulation.
Run:
cd horus_library/apps/tanksim
cargo run --release
Key concepts:
- Physics integration
- Collision detection
- Controller input
Development Tools
Sim2D
2D physics simulator with visualization.
Features:
- Rapier2D physics engine
- Bevy rendering
- URDF robot models
- Real-time visualization
Run:
cd horus_library/tools/sim2d
cargo run --release
Usage:
// Create simulated robot
let robot = Sim2DRobot::from_urdf("robot.urdf")?;
// Connect to HORUS nodes
robot.subscribe_to_hub("cmd_vel");
robot.publish_to_hub("odom");
// Run simulation
simulator.run()?;
Feature Flags
Enable optional node features:
[dependencies]
horus_library = { version = "0.1", features = ["full"] }
# Or specific features:
horus_library = { version = "0.1", features = [
"control-nodes", # PID, differential drive
"input-nodes", # Keyboard, joystick
"safety-nodes", # E-stop, safety monitor
"basic-sensors", # Camera, LIDAR, IMU
"industrial-nodes", # Modbus
"raspberry-pi", # RPi-specific hardware
]}
Available features:
control-nodes- Control algorithmsinput-nodes- Input devicessafety-nodes- Safety monitoringbasic-sensors- Camera, LIDAR, IMUindustrial-nodes- Modbus, industrial protocolsraspberry-pi- Raspberry Pi GPIOopencv-backend- OpenCV image processingv4l2-backend- V4L2 camera support
Best Practices
Message Type Selection
Fixed-size types (recommended):
// Good - fixed size, safe for shared memory
pub struct LaserScan {
pub ranges: [f32; 360], // Fixed array
}
Dynamic types (avoid in messages):
// Bad - heap allocation, not safe for shared memory
pub struct BadMessage {
pub data: Vec<f32>, // Heap-allocated
pub name: String, // Heap-allocated
}
Node Configuration
Provide sensible defaults:
impl CameraNode {
pub fn new(device: &str) -> Self {
Self {
device: device.to_string(),
width: 640, // Default resolution
height: 480,
fps: 30, // Default FPS
// ...
}
}
pub fn with_resolution(mut self, width: u32, height: u32) -> Self {
self.width = width;
self.height = height;
self
}
}
Usage:
// Default configuration
let camera = CameraNode::new("/dev/video0")?;
// Custom configuration
let camera = CameraNode::new("/dev/video0")?
.with_resolution(1920, 1080)
.with_fps(60);
Error Handling
Return results for initialization:
impl MyNode {
pub fn new(config: Config) -> Result<Self, Box<dyn Error>> {
// Validate configuration
if config.port == 0 {
return Err("Invalid port".into());
}
// Initialize hardware
let device = Device::open(config.device)
.map_err(|e| format!("Failed to open device: {}", e))?;
Ok(Self { device, config })
}
}
Handle tick errors gracefully:
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
match self.read_sensor() {
Ok(data) => {
self.output.send(data, ctx).ok();
}
Err(e) => {
if let Some(ctx) = ctx {
ctx.log_error(&format!("Sensor error: {}", e));
}
self.error_count += 1;
}
}
}
Next Steps
- Message Types Guide - Detailed message documentation
- node! Macro - Create custom nodes easily
- Examples - Complete applications
- API Reference - Full API documentation