Nodes and Lifecycle
New to HORUS? Start with Nodes: The Building Blocks for a 5-minute introduction.
Key Takeaways
After reading this guide, you will understand:
- How nodes are self-contained units of computation that run in the scheduler
- The Node trait's lifecycle methods (init, tick, shutdown) and when each is called
- How NodeInfo provides logging, metrics, and timing context to your nodes
- When to use different priority levels (0 for safety-critical, 100 for background logging)
- Communication patterns (publisher, subscriber, pipeline, aggregator) for building node graphs
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 Topic 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. Here are the methods you'll use:
pub trait Node: Send {
// Required
fn tick(&mut self);
// Name (defaults to struct type name, e.g. `MotorController`)
fn name(&self) -> &str { /* derived from type name */ }
// Optional lifecycle
fn init(&mut self) -> Result<()> { Ok(()) }
// SAFETY: implement shutdown() for any node that controls actuators or holds hardware resources
fn shutdown(&mut self) -> Result<()> { Ok(()) }
fn on_error(&mut self, error: &str) { /* logs error */ }
// Metadata (auto-generated by node! macro — rarely implemented manually)
fn publishers(&self) -> Vec<TopicMetadata> { Vec::new() }
fn subscribers(&self) -> Vec<TopicMetadata> { Vec::new() }
// SAFETY: used by safety monitor when Miss::SafeMode triggers — override for actuator nodes
fn is_safe_state(&self) -> bool { true }
fn enter_safe_state(&mut self) { /* no-op */ }
}
Note: See the API Reference for complete method documentation.
Required Methods
tick(): Main execution loop called repeatedly by the scheduler. This is the only truly required method.
fn tick(&mut self) {
// Your node logic here
}
Optional Methods
name(): Returns a string identifying the node. The default implementation derives the name from the struct's type name (e.g., SensorNode → "SensorNode"). You can override it:
fn name(&self) -> &str {
"MyNode"
}
When using the node! macro, the name is auto-generated from the struct name.
init(): Called once during node startup, before the first tick(). Default: no-op.
fn init(&mut self) -> Result<()>
Returns: Ok(()) on success. If Err(e) is returned, the node is marked as failed and its FailurePolicy is applied (default: node is skipped, error logged).
When called: Lazily on the first call to scheduler.run() or scheduler.tick_once(). NOT called at .add().build() time.
fn init(&mut self) -> Result<()> {
self.sensor = Sensor::open("/dev/i2c-1")
.horus_context("opening IMU sensor")?;
hlog!(info, "Sensor initialized");
Ok(())
}
shutdown(): Called once during graceful shutdown (Ctrl+C or .stop()). Default: no-op.
// SAFETY: always implement shutdown() for nodes controlling motors, servos, or other actuators
fn shutdown(&mut self) -> Result<()> {
hlog!(info, "Node shutting down");
// Clean up resources, close connections, etc.
Ok(())
}
is_safe_state(): Check if the node is in a safe state. Used by the safety monitor when Miss::SafeMode triggers. Override this to report your node's safety status:
// SAFETY: override for actuator nodes — scheduler calls this during Miss::SafeMode
fn is_safe_state(&self) -> bool {
self.velocity == 0.0 && self.motor_disabled
}
enter_safe_state(): Transition the node to a safe state. Called by the scheduler when Miss::SafeMode is active and the node misses a deadline:
// SAFETY: stop all actuators and disable outputs when entering safe state
fn enter_safe_state(&mut self) {
self.velocity = 0.0;
self.disable_motor();
hlog!(warn, "Entered safe state");
}
on_error(): Called when the node's tick() panics or returns an error. Default: logs the error message.
fn on_error(&mut self, error: &str)
Parameters:
error: &str— Human-readable error description from the caught panic or error.
Override to implement custom error recovery (e.g., reset sensor state, clear buffers):
fn on_error(&mut self, error: &str) {
hlog!(error, "Node error: {}", error);
self.consecutive_errors += 1;
if self.consecutive_errors > 5 {
self.enter_safe_state();
}
}
publishers() / subscribers(): Return metadata about which topics this node uses. Default: empty. Used by the monitor, graph visualization, and introspection CLI commands (horus node info).
fn publishers(&self) -> Vec<TopicMetadata>
fn subscribers(&self) -> Vec<TopicMetadata>
Returns: Vec<TopicMetadata> where each entry has:
topic_name: String— The topic name (e.g.,"cmd_vel")type_name: String— The message type name (e.g.,"CmdVel")
When using the node! macro, these are auto-generated from your pub {} and sub {} blocks. When implementing Node manually, override them for accurate introspection:
fn publishers(&self) -> Vec<TopicMetadata> {
vec![TopicMetadata {
topic_name: "cmd_vel".to_string(),
type_name: std::any::type_name::<CmdVel>().to_string(),
}]
}
Note: Per-node tick rates are set via the scheduler builder (
.rate(100_u64.hz())) when adding the node, not on the Node trait itself.
Node Lifecycle
Nodes transition through well-defined states during their lifetime:
NodeState
The NodeState enum tracks which lifecycle phase a node is in:
| Variant | Description |
|---|---|
Uninitialized | Created but not yet initialized |
Initializing | init() is running |
Running | Actively ticking |
Stopping | shutdown() is running |
Stopped | Clean shutdown complete |
Error(msg) | Error state with message |
Crashed(msg) | Unrecoverable crash |
HealthStatus
The HealthStatus enum represents the health of a running node as observed by the scheduler and safety monitor:
| Variant | Description |
|---|---|
Healthy | Operating normally |
Warning | Degraded performance |
Error | Errors occurring but still running |
Critical | Fatal errors, about to crash |
Unknown | No heartbeat received |
State Transitions
Lifecycle Example
use horus::prelude::*;
struct LifecycleDemo {
counter: u32,
}
impl Node for LifecycleDemo {
fn name(&self) -> &str {
"LifecycleDemo"
}
fn init(&mut self) -> Result<()> {
// NOTE: called ONCE when node starts — open resources, allocate buffers here
hlog!(info, "Initializing resources");
self.counter = 0;
Ok(())
}
fn tick(&mut self) {
// NOTE: called REPEATEDLY in main loop (~60 FPS default)
self.counter += 1;
hlog!(debug, "Tick #{}", self.counter);
}
// SAFETY: called ONCE during graceful shutdown — release resources, stop actuators here
fn shutdown(&mut self) -> Result<()> {
hlog!(info, "Shutting down after {} ticks", self.counter);
Ok(())
}
}
Logging and Metrics
The scheduler tracks node state, metrics, and lifecycle internally. You don't interact with internal tracking directly — instead, use the hlog! macro for logging and the scheduler API for metrics.
Logging with hlog!
Use the hlog! macro for structured logging:
Info: General information messages
hlog!(info, "Robot ready");
Warn: Warning messages that don't stop execution
hlog!(warn, "Battery low");
Error: Error messages
hlog!(error, "Sensor disconnected");
Debug: Detailed debugging information
hlog!(debug, "Position: ({}, {})", x, y);
Pub/Sub Logging
With the zero-overhead IPC, send() and recv() don't take any context parameter. For introspection, use CLI tools instead:
fn tick(&mut self) {
self.velocity_pub.send(1.5);
// IMPORTANT: call recv() every tick to avoid stale data accumulation
if let Some(scan) = self.lidar_sub.recv() {
self.process(scan);
}
}
For monitoring without code changes, use CLI tools: horus topic echo, horus topic hz, horus monitor.
Performance Metrics
NodeInfo tracks detailed performance metrics:
pub struct NodeMetrics {
pub name: String,
pub order: u32,
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 messages_sent: u64,
pub messages_received: u64,
pub errors_count: u64,
pub warnings_count: u64,
pub uptime_seconds: f64,
}
Access metrics via the scheduler:
fn init(&mut self) -> Result<()> {
hlog!(info, "Node initializing");
Ok(())
}
fn tick(&mut self) {
// Track state internally if needed
self.tick_count += 1;
}
Tick Timing
The scheduler automatically tracks tick duration and updates metrics for each node. You don't need to call any timing methods manually.
Node Priority
Nodes execute in priority order each tick cycle:
Priority Levels
Priorities are represented as u32 values where lower numbers = higher priority.
Common priority values:
// Recommended priority constants
const CRITICAL: u32 = 0; // Highest priority
const HIGH: u32 = 10;
const NORMAL: u32 = 50; // Default
const LOW: u32 = 80;
const BACKGROUND: u32 = 100; // Lowest priority
You can use any u32 value for fine-grained control (e.g., 5, 15, 25, 37, 42, etc.).
Priority Usage
use horus::prelude::*;
let mut scheduler = Scheduler::new();
// Safety monitor runs FIRST every tick (order 0)
scheduler.add(safety_node).order(0).build()?;
// Controller runs second (order 10)
scheduler.add(control_node).order(10).build()?;
// Sensors run third (order 50)
scheduler.add(sensor_node).order(50).build()?;
// Logging runs LAST (order 100)
scheduler.add(logger_node).order(100).build()?;
// Fine-grained priorities for complex systems
scheduler.add(emergency_stop).order(0).build()?; // Highest
scheduler.add(motor_control).order(15).build()?; // Between HIGH and NORMAL
scheduler.add(vision_processing).order(55).build()?; // Slightly lower than normal
scheduler.add(telemetry).order(90).build()?; // Between LOW and BACKGROUND
Priority Guidelines
0 (Critical): Safety monitors, emergency stops, fault detection
10 (High): Control loops, actuator commands, real-time feedback
50 (Normal): Sensor processing, state estimation, path planning
80 (Low): Non-critical computation, filtering, analysis
100 (Background): Logging, monitoring, diagnostics, data recording
Custom Values: Use any u32 value for fine-grained priority control in complex systems
Creating Nodes
Manual Implementation
use horus::prelude::*;
struct SensorNode {
data_pub: Topic<f32>,
}
impl SensorNode {
fn new() -> Result<Self> {
Ok(Self {
data_pub: Topic::new("sensor_data")?,
})
}
}
impl Node for SensorNode {
fn name(&self) -> &str {
"SensorNode"
}
fn tick(&mut self) {
let data = 42.0; // Read sensor
self.data_pub.send(data);
}
// SAFETY: no actuators controlled — shutdown is optional for pure publisher nodes
fn shutdown(&mut self) -> Result<()> {
hlog!(info, "SensorNode stopped");
Ok(())
}
}
Using the node! Macro
The node! macro eliminates boilerplate:
use horus::prelude::*;
node! {
SensorNode {
pub {
sensor_data: f32 -> "sensor_data",
}
tick {
let data = 42.0;
self.sensor_data.send(data);
}
}
}
The macro generates:
- Struct definition with Topic fields
- Node trait implementation
- Constructor function (
SensorNode::new()) - Topic metadata methods
The macro also supports sub {} (subscribers), data {} (internal state), init {}, shutdown {}, and impl {} blocks. See The node! Macro Guide for the full syntax including lifecycle hooks, custom names, and advanced patterns.
Node Communication Patterns
Publisher Pattern
struct Publisher {
data_pub: Topic<f32>,
}
impl Node for Publisher {
fn tick(&mut self) {
let data = self.generate_data();
self.data_pub.send(data);
}
// SAFETY: implement shutdown() if this publisher controls actuators
fn shutdown(&mut self) -> Result<()> { Ok(()) }
}
Subscriber Pattern
struct Subscriber {
data_sub: Topic<f32>,
}
impl Node for Subscriber {
fn tick(&mut self) {
// IMPORTANT: call recv() every tick to drain the buffer and avoid stale data
if let Some(data) = self.data_sub.recv() {
self.process(data);
}
}
fn shutdown(&mut self) -> Result<()> { Ok(()) }
}
Pipeline Pattern
// PATTERN: Pipeline — subscribe, transform, republish
struct Filter {
input_sub: Topic<f32>,
output_pub: Topic<f32>,
}
impl Node for Filter {
fn tick(&mut self) {
// IMPORTANT: call recv() every tick to drain the buffer and avoid stale data
if let Some(input) = self.input_sub.recv() {
let output = input * 2.0;
self.output_pub.send(output);
}
}
fn shutdown(&mut self) -> Result<()> { Ok(()) }
}
Aggregator Pattern
// PATTERN: Aggregator — combine multiple inputs into one output
// NOTE: if either input has no data, BOTH recv() calls still execute but output is skipped.
// This means data from the other input is consumed and lost. For independent draining,
// use the Multi-Topic Synchronization pattern below instead.
struct Aggregator {
input_a: Topic<f32>,
input_b: Topic<f32>,
output_pub: Topic<f32>,
}
impl Node for Aggregator {
fn tick(&mut self) {
// IMPORTANT: both recv() calls run every tick — data is consumed even if the other is None
if let (Some(a), Some(b)) = (self.input_a.recv(), self.input_b.recv()) {
let result = a + b;
self.output_pub.send(result);
}
}
fn shutdown(&mut self) -> Result<()> { Ok(()) }
}
Best Practices
Keep tick() Fast
The tick method should complete quickly (ideally <1ms):
// IMPORTANT: keep tick() under 1ms — the scheduler monitors tick duration
fn tick(&mut self) {
let result = self.compute_quickly();
self.pub.send(result);
}
// WARNING: blocking I/O in tick() causes deadline misses — use .async_io() or .compute() instead
fn tick(&mut self) {
let data = std::fs::read_to_string("file.txt").unwrap(); // Blocks!
// ...
}
For slow operations, use async tasks or separate threads initialized in init().
What to Include in init()
The init() method runs once when your node starts. Use it to set up everything your node needs before tick() begins.
Always include in init():
| Category | Examples | Why |
|---|---|---|
| Hardware connections | Serial ports, I2C/SPI devices, GPIO pins | Must be opened before use |
| Network connections | TCP/UDP sockets, WebSocket clients | Establish before tick loop |
| File handles | Config files, log files, data files | Open once, use in tick |
| Pre-allocated buffers | Image buffers, point cloud arrays | Avoid allocation in tick |
| Calibration/setup | Sensor calibration, motor homing | One-time setup operations |
| Initial state | Reset counters, clear flags | Start from known state |
fn init(&mut self) -> Result<()> {
hlog!(info, "Initializing MyMotorNode");
// 1. Open hardware connections
self.serial_port = serialport::new("/dev/ttyUSB0", 115200)
.open()
.map_err(|e| Error::node("MyMotorNode", format!("Failed to open serial: {}", e)))?;
// IMPORTANT: pre-allocate buffers here — allocation in tick() causes jitter
self.command_buffer = vec![0u8; 256];
// 3. Initialize hardware state
self.send_init_sequence()?;
// SAFETY: start with actuators in a known safe state
self.velocity = 0.0;
self.is_armed = false;
hlog!(info, "MyMotorNode initialized successfully");
Ok(())
}
What to Include in shutdown()
The shutdown() method runs once when your application exits (Ctrl+C, SIGINT, SIGTERM). Use it to safely stop hardware and release resources.
Always include in shutdown():
| Category | Examples | Why |
|---|---|---|
| Stop actuators | Motors, servos, pumps, valves | CRITICAL SAFETY - prevent runaway |
| Disable hardware | Disable motor drivers, turn off outputs | Safe state for power-off |
| Close connections | Serial ports, network sockets | Release system resources |
| Release GPIO | Unexport pins, set to input mode | Allow other processes to use |
| Save state | Log final position, save calibration | Preserve data for next run |
| Flush buffers | Write pending data to disk | Prevent data loss |
// SAFETY: shutdown() is called once on SIGINT/SIGTERM — stop all actuators before releasing resources
fn shutdown(&mut self) -> Result<()> {
hlog!(info, "MyMotorNode shutting down");
// CRITICAL: stop all actuators FIRST — before closing connections or releasing resources
self.velocity = 0.0;
self.send_stop_command();
// SAFETY: disable hardware outputs to prevent runaway on power cycle
self.disable_motor_driver();
// 3. Close hardware connections
if let Some(port) = self.serial_port.take() {
drop(port); // Closes the port
}
// 4. Save any important state
self.save_position_to_file()?;
hlog!(info, "MyMotorNode shutdown complete");
Ok(())
}
Complete Custom Node Example
Here's a complete example showing proper init() and shutdown() implementation:
use horus::prelude::*;
struct MyMotorController {
// Hardware
serial_port: Option<Box<dyn serialport::SerialPort>>,
// Communication
cmd_sub: Topic<MotorCommand>,
status_pub: Topic<MotorStatus>,
// State
velocity: f64,
position: i32,
is_enabled: bool,
}
impl MyMotorController {
fn new() -> Result<Self> {
Ok(Self {
serial_port: None,
cmd_sub: Topic::new("motor.cmd")?,
status_pub: Topic::new("motor.status")?,
velocity: 0.0,
position: 0,
is_enabled: false,
})
}
fn send_velocity(&mut self, vel: f64) {
if let Some(ref mut port) = self.serial_port {
let cmd = format!("V{}\n", vel);
let _ = port.write(cmd.as_bytes());
}
}
}
impl Node for MyMotorController {
fn name(&self) -> &str { "MyMotorController" }
fn init(&mut self) -> Result<()> {
hlog!(info, "Opening serial connection to motor controller");
// Open hardware connection
self.serial_port = Some(
serialport::new("/dev/ttyUSB0", 115200)
.timeout(std::time::Duration::from_millis(100))
.open()
.map_err(|e| Error::node("MyMotorController", format!("Serial open failed: {}", e)))?
);
// Initialize motor to stopped state
self.send_velocity(0.0);
self.is_enabled = true;
hlog!(info, "Motor controller ready");
Ok(())
}
fn tick(&mut self) {
// IMPORTANT: call recv() every tick to drain the command buffer
if let Some(cmd) = self.cmd_sub.recv() {
self.velocity = cmd.velocity;
self.send_velocity(self.velocity);
}
// Publish status
let status = MotorStatus {
velocity: self.velocity,
position: self.position,
};
self.status_pub.send(status);
}
// SAFETY: must stop motors before releasing serial port
fn shutdown(&mut self) -> Result<()> {
hlog!(info, "Stopping motor for safe shutdown");
// CRITICAL: stop motor first — before closing serial port
self.velocity = 0.0;
self.send_velocity(0.0);
// Close serial port
self.serial_port = None;
self.is_enabled = false;
hlog!(info, "Motor stopped safely");
Ok(())
}
}
When init() and shutdown() Are NOT Optional
While the default implementations are no-ops, you should implement them when:
| Scenario | init() Required | shutdown() Required |
|---|---|---|
| Controls motors/actuators | Setup | YES - SAFETY CRITICAL |
| Opens serial/I2C/SPI ports | YES | YES |
| Uses GPIO pins | YES | YES |
| Opens network connections | YES | Recommended |
| Allocates large buffers | YES | No |
| Reads config files | YES | No |
| Writes log/data files | Optional | YES (flush) |
| Pure computation node | No | No |
Use Result Types
Return errors from init() and shutdown():
fn init(&mut self) -> Result<()> {
if !self.sensor.is_available() {
return Err(Error::node("MyNode", "Sensor not found"));
}
Ok(())
}
Use hlog! for Logging in tick()
Since tick() no longer receives ctx, use the hlog! macro for logging:
fn tick(&mut self) {
hlog!(info, "Processing data");
hlog!(debug, "Detailed debug info: {:?}", self.state);
}
Avoid State in Static Variables
Store state in the node struct, not static variables:
// IMPORTANT: store state in the node struct — the scheduler owns your node's lifetime
struct MyNode {
counter: u32, // Instance state
}
// WARNING: static mut is unsound and breaks multi-node isolation
static mut COUNTER: u32 = 0; // Unsafe global state
Error Handling
Initialization Errors
fn init(&mut self) -> Result<()> {
self.device = Device::open().map_err(|e| {
Error::node("MyNode", format!("Failed to open device: {}", e))
})?;
hlog!(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) {
// IMPORTANT: call recv() every tick — None is normal (no new data this tick)
match self.data_sub.recv() {
Some(data) => self.process(data),
None => {
// No data available - this is normal
}
}
}
Shutdown Errors
// SAFETY: never panic in shutdown — log errors and continue cleanup
fn shutdown(&mut self) -> Result<()> {
if let Err(e) = self.device.close() {
hlog!(warn, "Failed to close device: {}", e);
// Continue shutdown anyway
}
Ok(())
}
Advanced Topics
Conditional Execution
Run logic only under certain conditions:
fn tick(&mut self) {
self.tick_count += 1;
// Execute every 10 ticks
if self.tick_count % 10 == 0 {
self.slow_operation();
}
}
State-Based Logic
Implement complex behavior with enum-based state patterns:
// PATTERN: State machine — use enum states for complex behavior
enum RobotState {
Idle,
Moving,
Stopped,
}
struct RobotController {
state: RobotState,
cmd_sub: Topic<CmdVel>,
last_cmd: Option<CmdVel>,
}
impl Node for RobotController {
fn tick(&mut self) {
// CRITICAL: always call recv() outside the match — calling it only in one branch
// causes the buffer to fill up in other states, leading to stale commands
// executing immediately on state transition
self.last_cmd = self.cmd_sub.recv();
match self.state {
RobotState::Idle => {
if self.last_cmd.is_some() {
self.state = RobotState::Moving;
}
}
RobotState::Moving => {
// Execute movement
if self.is_done() {
self.state = RobotState::Stopped;
}
}
RobotState::Stopped => {
self.state = RobotState::Idle;
}
}
}
// SAFETY: stop actuators on shutdown even if in Moving state
fn shutdown(&mut self) -> Result<()> {
self.state = RobotState::Stopped;
Ok(())
}
}
Multi-Topic Synchronization
Wait for data from multiple topics:
// PATTERN: Multi-Topic Synchronization — cache latest from each input, process when all available
struct Synchronizer {
topic_a: Topic<f32>,
topic_b: Topic<f32>,
last_a: Option<f32>,
last_b: Option<f32>,
}
impl Node for Synchronizer {
fn tick(&mut self) {
// IMPORTANT: call recv() on ALL topics every tick — never skip a recv() conditionally
if let Some(a) = self.topic_a.recv() {
self.last_a = Some(a);
}
if let Some(b) = self.topic_b.recv() {
self.last_b = Some(b);
}
// NOTE: processes with stale data from slower topic until both update
if let (Some(a), Some(b)) = (self.last_a, self.last_b) {
self.process(a, b);
}
}
fn shutdown(&mut self) -> Result<()> { Ok(()) }
}
Graceful Shutdown & Motor Safety
When a HORUS application receives a termination signal (Ctrl+C, SIGINT, SIGTERM), the scheduler automatically calls shutdown() on all registered nodes. This is critical for robotics safety.
Signal Handling
The scheduler intercepts termination signals and ensures proper cleanup:
Why shutdown() Matters for Motors
Without shutdown(): If you stop your robot with Ctrl+C while motors are running, they continue at their last commanded velocity - potentially dangerous for autonomous vehicles!
With shutdown(): Motors receive stop commands before the application exits:
// SAFETY: without this, motors continue at last commanded velocity after Ctrl+C
fn shutdown(&mut self) -> Result<()> {
hlog!(info, "Stopping all motors for safe shutdown");
// CRITICAL: send stop command to all motors FIRST
self.emergency_stop();
// SAFETY: disable motor drivers to prevent runaway
self.disable_all_drivers();
hlog!(info, "Motors stopped safely");
Ok(())
}
Python Node Shutdown Behavior
Python nodes also support shutdown callbacks. When the scheduler stops, your shutdown function runs automatically:
import horus
velocity = [0.0, 0.0]
def motor_tick(node):
msg = node.recv("cmd_vel")
if msg is not None:
velocity[0], velocity[1] = msg
def motor_shutdown(node):
velocity[0], velocity[1] = 0.0, 0.0
print("Motors stopped safely")
motor = horus.Node(name="MotorController", tick=motor_tick,
shutdown=motor_shutdown, order=10,
subs=["cmd_vel"])
horus.run(motor)
See the Python Bindings documentation for details.
Implementing shutdown() in Custom Nodes
Always implement shutdown() for nodes that control actuators:
impl Node for MyMotorController {
fn name(&self) -> &str { "MyMotorController" }
fn tick(&mut self) {
// Normal operation - motors running
self.motor_pub.send(self.velocity);
}
// SAFETY: called on SIGINT/SIGTERM — stop actuators before releasing hardware
fn shutdown(&mut self) -> Result<()> {
hlog!(info, "MyMotorController shutting down");
// CRITICAL: stop all motors FIRST — before closing any connections
self.velocity = 0.0;
self.motor_pub.send(0.0);
// Close hardware connections
if let Some(port) = self.serial_port.take() {
port.close();
}
hlog!(info, "All motors stopped safely");
Ok(())
}
}
Testing Shutdown Behavior
Test your shutdown implementation before deploying:
# Start your application
horus run
# In another terminal, send SIGINT
kill -SIGINT <pid>
# Or simply press Ctrl+C in the application terminal
Verify in logs:
[12:34:56.789] [INFO] MyMotorController shutting down
[12:34:56.790] [INFO] All motors stopped safely
Best Practices for Shutdown
- Always stop actuators first - Motors, servos, and other actuators should receive stop commands
- Close hardware connections - Serial ports, I2C, SPI, CAN bus connections
- Release system resources - GPIO pins, file handles, network sockets
- Log shutdown progress - Helps debug shutdown issues
- Don't panic in shutdown - Handle errors gracefully, continue cleanup
// SAFETY: never panic in shutdown — always attempt all cleanup steps
fn shutdown(&mut self) -> Result<()> {
// CRITICAL: always try to stop motors, even if other cleanup fails
if let Err(e) = self.stop_motors() {
hlog!(error, "Failed to stop motors: {}", e);
// Continue with other cleanup anyway
}
// Close connections (non-critical)
if let Err(e) = self.close_connection() {
hlog!(warn, "Failed to close connection: {}", e);
}
Ok(())
}
Next Steps
- Learn about Topic 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