Nodes and Lifecycle
Nodes are the fundamental building blocks of HORUS applications. Every component in your robotics system is a node - sensors, actuators, controllers, filters, and more.
What is a Node?
A node is a self-contained unit of computation that runs in the HORUS scheduler. Nodes communicate with each other through the Hub pub/sub system using shared memory IPC.
Key Characteristics
Lifecycle Management: Nodes have explicit initialization, execution, and shutdown phases
Priority-Based Execution: Nodes run in priority order every tick cycle
Zero Boilerplate: The node! macro generates all necessary boilerplate code
Type-Safe Communication: Compile-time guarantees for message passing
Memory Safety: Written in Rust with zero unsafe code in user-facing APIs
The Node Trait
Every HORUS node implements the Node trait:
pub trait Node: Send {
fn name(&self) -> &'static str;
fn init(&mut self, ctx: &mut NodeInfo) -> Result<(), String>;
fn tick(&mut self, ctx: Option<&mut NodeInfo>);
fn shutdown(&mut self, ctx: &mut NodeInfo) -> Result<(), String>;
fn get_publishers(&self) -> Vec<TopicMetadata>;
fn get_subscribers(&self) -> Vec<TopicMetadata>;
}
Required Methods
name(): Returns a static string identifying the node
fn name(&self) -> &'static str {
"MyNode"
}
tick(): Main execution loop called repeatedly by the scheduler
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
// Your node logic here
}
Optional Methods
init(): Called once during node startup (default: no-op)
fn init(&mut self, ctx: &mut NodeInfo) -> Result<(), String> {
ctx.log_info("Node starting up");
// Initialize resources, open files, etc.
Ok(())
}
shutdown(): Called once during graceful shutdown (default: no-op)
fn shutdown(&mut self, ctx: &mut NodeInfo) -> Result<(), String> {
ctx.log_info("Node shutting down");
// Clean up resources, close connections, etc.
Ok(())
}
get_publishers(): Returns list of published topics (default: empty)
fn get_publishers(&self) -> Vec<TopicMetadata> {
vec![
TopicMetadata {
topic_name: "cmd_vel".to_string(),
type_name: "CmdVel".to_string(),
}
]
}
get_subscribers(): Returns list of subscribed topics (default: empty)
fn get_subscribers(&self) -> Vec<TopicMetadata> {
vec![
TopicMetadata {
topic_name: "laser_scan".to_string(),
type_name: "LaserScan".to_string(),
}
]
}
Node Lifecycle
Nodes transition through well-defined states during their lifetime:
Lifecycle States
Uninitialized: Node created but not registered with scheduler
Initializing: Running init() method
Running: Executing tick() in main loop
Paused: Temporarily suspended (future feature)
Stopping: Running shutdown() method
Stopped: Clean shutdown complete
Error: Recoverable error occurred
Crashed: Unrecoverable error, node terminated
State Transitions
Uninitialized Initializing Running Stopping Stopped
->
Error Running
->
Crashed (terminal)
Lifecycle Example
use horus::prelude::*;
struct LifecycleDemo {
counter: u32,
}
impl Node for LifecycleDemo {
fn name(&self) -> &'static str {
"LifecycleDemo"
}
fn init(&mut self, ctx: &mut NodeInfo) -> Result<(), String> {
// Called ONCE when node starts
ctx.log_info("Initializing resources");
self.counter = 0;
Ok(())
}
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
// Called REPEATEDLY in main loop (~60 FPS default)
self.counter += 1;
if let Some(ctx) = ctx {
ctx.log_debug(&format!("Tick #{}", self.counter));
}
}
fn shutdown(&mut self, ctx: &mut NodeInfo) -> Result<(), String> {
// Called ONCE during graceful shutdown
ctx.log_info(&format!("Shutting down after {} ticks", self.counter));
Ok(())
}
}
NodeInfo Context
The NodeInfo struct provides comprehensive context and utilities for nodes:
Structure
pub struct NodeInfo {
pub name: &'static str,
pub state: NodeState,
pub priority: NodePriority,
pub metrics: NodeMetrics,
pub publishers: Vec<TopicMetadata>,
pub subscribers: Vec<TopicMetadata>,
// Internal timing and logging fields
}
Logging Methods
log_info(): General information messages
ctx.log_info("Robot ready");
log_warning(): Warning messages that don't stop execution
ctx.log_warning("Battery low");
log_error(): Error messages
ctx.log_error("Sensor disconnected");
log_debug(): Detailed debugging information
ctx.log_debug(&format!("Position: ({}, {})", x, y));
Pub/Sub Logging
log_pub(): Automatically called when publishing (includes IPC timing)
// Called internally by Hub::send()
ctx.log_pub("cmd_vel", &velocity, ipc_ns);
// Output: [12:34:56.789] [IPC: 296ns | Tick: 12μs] MyNode --PUB--> 'cmd_vel' = 1.5
log_sub(): Automatically called when receiving (includes IPC timing)
// Called internally by Hub::recv()
ctx.log_sub("laser_scan", &scan, ipc_ns);
// Output: [12:34:56.789] [IPC: 142ns | Tick: 8μs] MyNode --SUB--> 'laser_scan' = LaserScan { ... }
Performance Metrics
NodeInfo tracks detailed performance metrics:
pub struct NodeMetrics {
pub total_ticks: u64,
pub successful_ticks: u64,
pub failed_ticks: u64,
pub avg_tick_duration_ms: f64,
pub max_tick_duration_ms: f64,
pub min_tick_duration_ms: f64,
pub last_tick_duration_ms: f64,
pub cpu_usage_percent: f64,
pub memory_usage_bytes: u64,
pub messages_sent: u64,
pub messages_received: u64,
pub errors_count: u64,
pub warnings_count: u64,
pub uptime_seconds: f64,
}
Access metrics in your node:
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
if let Some(ctx) = ctx {
let avg_duration = ctx.metrics.avg_tick_duration_ms;
if avg_duration > 1.0 {
ctx.log_warning("Tick duration exceeding 1ms");
}
}
}
Timing Methods
start_tick(): Called automatically at the start of each tick
record_tick(): Called automatically at the end of each tick
These methods track tick duration and update metrics.
Node Priority
Nodes execute in priority order each tick cycle:
Priority Levels
pub enum NodePriority {
Critical = 0, // Highest priority
High = 1,
Normal = 2, // Default
Low = 3,
Background = 4, // Lowest priority
}
Priority Usage
use horus::prelude::*;
let mut scheduler = Scheduler::new();
// Safety monitor runs FIRST every tick
scheduler.register_with_priority(safety_node, NodePriority::Critical);
// Controller runs second
scheduler.register_with_priority(control_node, NodePriority::High);
// Sensors run third
scheduler.register_with_priority(sensor_node, NodePriority::Normal);
// Logging runs LAST
scheduler.register_with_priority(logger_node, NodePriority::Background);
Priority Guidelines
Critical (0): Safety monitors, emergency stops, fault detection
High (1): Control loops, actuator commands, real-time feedback
Normal (2): Sensor processing, state estimation, path planning
Low (3): Non-critical computation, filtering, analysis
Background (4): Logging, monitoring, diagnostics, data recording
Creating Nodes
Manual Implementation
use horus::prelude::*;
struct SensorNode {
data_pub: Hub<f32>,
}
impl SensorNode {
fn new() -> HorusResult<Self> {
Ok(Self {
data_pub: Hub::new("sensor_data")?,
})
}
}
impl Node for SensorNode {
fn name(&self) -> &'static str {
"SensorNode"
}
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
let data = 42.0; // Read sensor
self.data_pub.send(data, ctx).ok();
}
}
Using the node! Macro
The node! macro eliminates boilerplate:
use horus::prelude::*;
node! {
name: SensorNode,
publishers: [sensor_data: f32],
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
let data = 42.0;
self.sensor_data.send(data, ctx).ok();
}
}
The macro generates:
- Struct definition with Hub fields
- Node trait implementation
- Constructor function
- Topic metadata methods
Node Communication Patterns
Publisher Pattern
struct Publisher {
data_pub: Hub<f32>,
}
impl Node for Publisher {
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
let data = self.generate_data();
self.data_pub.send(data, ctx).ok();
}
}
Subscriber Pattern
struct Subscriber {
data_sub: Hub<f32>,
}
impl Node for Subscriber {
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
if let Some(data) = self.data_sub.recv(ctx) {
self.process(data);
}
}
}
Pipeline Pattern
struct Filter {
input_sub: Hub<f32>,
output_pub: Hub<f32>,
}
impl Node for Filter {
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
if let Some(input) = self.input_sub.recv(ctx) {
let output = input * 2.0;
self.output_pub.send(output, ctx).ok();
}
}
}
Aggregator Pattern
struct Aggregator {
input_a: Hub<f32>,
input_b: Hub<f32>,
output_pub: Hub<f32>,
}
impl Node for Aggregator {
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
if let (Some(a), Some(b)) = (self.input_a.recv(ctx), self.input_b.recv(ctx)) {
let result = a + b;
self.output_pub.send(result, ctx).ok();
}
}
}
Best Practices
Keep tick() Fast
The tick method should complete quickly (ideally <1ms):
// GOOD: Fast computation
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
let result = self.compute_quickly();
self.pub.send(result, ctx).ok();
}
// BAD: Blocking I/O
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
let data = std::fs::read_to_string("file.txt").unwrap(); // Blocks!
// ...
}
For slow operations, use async tasks or separate threads initialized in init().
Initialize in init()
Pre-allocate resources during initialization:
fn init(&mut self, ctx: &mut NodeInfo) -> Result<(), String> {
// Pre-allocate buffer
self.buffer = vec![0.0; 1000];
// Open connections
self.connection = connect_to_device()?;
Ok(())
}
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
// Use pre-allocated resources
self.buffer[0] = 42.0;
}
Clean up in shutdown()
Release resources gracefully:
fn shutdown(&mut self, ctx: &mut NodeInfo) -> Result<(), String> {
// Close connections
self.connection.close();
// Save state
self.save_state_to_file()?;
ctx.log_info("Cleanup complete");
Ok(())
}
Use Result Types
Return errors from init() and shutdown():
fn init(&mut self, ctx: &mut NodeInfo) -> Result<(), String> {
if !self.sensor.is_available() {
return Err("Sensor not found".to_string());
}
Ok(())
}
Check ctx Before Logging
The context is optional in tick():
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
if let Some(ctx) = ctx {
ctx.log_info("This is safe");
}
}
Avoid State in Static Variables
Store state in the node struct, not static variables:
// GOOD
struct MyNode {
counter: u32, // Instance state
}
// BAD
static mut COUNTER: u32 = 0; // Unsafe global state
Error Handling
Initialization Errors
fn init(&mut self, ctx: &mut NodeInfo) -> Result<(), String> {
self.device = Device::open().map_err(|e| {
format!("Failed to open device: {}", e)
})?;
ctx.log_info("Device opened successfully");
Ok(())
}
If init() returns an error, the node transitions to Error state and won't run.
Runtime Errors
Handle errors in tick() without panicking:
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
match self.data_sub.recv(ctx) {
Some(data) => self.process(data),
None => {
// No data available - this is normal
}
}
}
Shutdown Errors
fn shutdown(&mut self, ctx: &mut NodeInfo) -> Result<(), String> {
if let Err(e) = self.device.close() {
ctx.log_warning(&format!("Failed to close device: {}", e));
// Continue shutdown anyway
}
Ok(())
}
Advanced Topics
Conditional Execution
Run logic only under certain conditions:
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
self.tick_count += 1;
// Execute every 10 ticks
if self.tick_count % 10 == 0 {
self.slow_operation();
}
}
State Machines
Implement complex behavior with state machines:
enum RobotState {
Idle,
Moving,
Stopped,
}
struct RobotController {
state: RobotState,
cmd_sub: Hub<CmdVel>,
}
impl Node for RobotController {
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
match self.state {
RobotState::Idle => {
if let Some(cmd) = self.cmd_sub.recv(ctx) {
self.state = RobotState::Moving;
}
}
RobotState::Moving => {
// Execute movement
if self.is_done() {
self.state = RobotState::Stopped;
}
}
RobotState::Stopped => {
self.state = RobotState::Idle;
}
}
}
}
Multi-Topic Synchronization
Wait for data from multiple topics:
struct Synchronizer {
topic_a: Hub<f32>,
topic_b: Hub<f32>,
last_a: Option<f32>,
last_b: Option<f32>,
}
impl Node for Synchronizer {
fn tick(&mut self, ctx: Option<&mut NodeInfo>) {
// Update cached values
if let Some(a) = self.topic_a.recv(ctx) {
self.last_a = Some(a);
}
if let Some(b) = self.topic_b.recv(ctx) {
self.last_b = Some(b);
}
// Process when both available
if let (Some(a), Some(b)) = (self.last_a, self.last_b) {
self.process(a, b);
}
}
}
Next Steps
- Learn about Hub and Pub/Sub for inter-node communication
- Understand the Scheduler for orchestrating nodes
- Explore Message Types for standard robotics data
- Read the API Reference for complete Node trait documentation