Scheduler Configuration
HORUS uses a single scheduler entry point — Scheduler::new() — with composable builder methods (.watchdog(), .blackbox(), .require_rt(), .max_deadline_misses()) and a fluent node builder API that gives you full control over execution class, timing, ordering, and failure handling on a per-node basis.
Creating a Scheduler
Every scheduler starts with Scheduler::new(). From there you can optionally set global parameters with builder methods before adding nodes:
use horus::prelude::*;
fn main() -> Result<()> {
let mut scheduler = Scheduler::new()
.tick_rate(1000_u64.hz()); // Global tick rate (default: 100 Hz)
// ... add nodes ...
scheduler.run()?;
Ok(())
}
Builder Methods
| Method | Description | Default |
|---|---|---|
.tick_rate(freq) | Global scheduler tick rate | 100 Hz |
.watchdog(Duration) | Frozen node detection — auto-creates safety monitor | disabled |
.blackbox(size_mb) | BlackBox flight recorder (n MB ring buffer) | disabled |
.max_deadline_misses(n) | Emergency stop after n deadline misses | 100 |
.require_rt() | Hard real-time — panics without RT capabilities | — |
.prefer_rt() | Request RT features (degrades gracefully) | — |
.verbose(bool) | Enable/disable non-emergency logging | true |
.with_recording() | Enable record/replay | — |
Adding Nodes
Add nodes with scheduler.add(n), then chain configuration calls, and finalize with .build()?:
use horus::prelude::*;
fn main() -> Result<()> {
let mut scheduler = Scheduler::new()
.tick_rate(1000_u64.hz());
// Real-time motor control — runs first every tick
// rate() auto-derives budget (80%) and deadline (95%), auto-marks as RT
scheduler.add(MotorController::new("arm"))
.order(0)
.rate(1000_u64.hz())
.on_miss(Miss::SafeMode)
.build()?;
// Sensor node — high priority, custom rate
scheduler.add(LidarDriver::new("/dev/lidar0"))
.order(10)
.rate(500_u64.hz())
.build()?;
// Compute-heavy planning — runs on a worker thread
scheduler.add(PathPlanner::new())
.order(50)
.compute()
.build()?;
// Event-driven node — wakes only when the topic has new data
scheduler.add(CollisionChecker::new())
.on("lidar.points")
.build()?;
// Async I/O — network or disk, never blocks the real-time loop
scheduler.add(TelemetryUploader::new())
.order(200)
.async_io()
.rate(10_u64.hz())
.build()?;
scheduler.run()?;
Ok(())
}
Execution Classes
Every node belongs to exactly one execution class. Set it in the builder chain:
| Method | Class | Description |
|---|---|---|
.compute() | Compute | Offloaded to a worker thread pool. Use for planning, SLAM, or ML inference. |
.on(topic) | Event-Driven | Wakes only when the named topic receives new data. |
.async_io() | Async I/O | Runs on an async executor. Use for network, disk, or cloud calls. |
If no execution class is specified, the node defaults to BestEffort. A node is automatically promoted to the RT class when you set .rate(Frequency) (which auto-derives budget at 80% and deadline at 95% of the period).
When to Use Each Class
- RT (auto-detected) — Motor controllers, safety monitors, sensor fusion, anything that must run every tick with bounded latency. Triggered by
.rate(Frequency)on a BestEffort node. .compute()— Path planning, point cloud processing, ML inference. These can take longer than a single tick without blocking RT nodes..on(topic)— Collision detection, event handlers, reactive behaviors. Only runs when there is new data, saving CPU when idle..async_io()— Telemetry upload, log shipping, cloud API calls. Never blocks any real-time or compute work.
Per-Node Configuration
Ordering and Timing
| Method | Description |
|---|---|
.order(n) | Execution priority within a tick (lower = runs first) |
.rate(Frequency) | Node-specific tick rate — auto-derives budget (80%) and deadline (95%), auto-marks as RT |
.on_miss(Miss) | What to do on deadline miss (Miss::Warn, Miss::Skip, Miss::SafeMode, Miss::Stop) |
Failure Policy
| Method | Description |
|---|---|
.failure_policy(policy) | Per-node failure handling (see Fault Tolerance) |
.build() | Finalize and register the node (returns HorusResult) |
Order Guidelines
- 0-9: Critical real-time (motor control, safety)
- 10-49: High priority (sensors, fast control loops)
- 50-99: Normal priority (processing, planning)
- 100-199: Low priority (logging, diagnostics)
- 200+: Background (telemetry, non-essential)
Global Configuration with Composable Builders
Compose the builder methods you need for each deployment stage:
use horus::prelude::*;
// Development — lightweight, profiling is always-on
let mut scheduler = Scheduler::new()
.tick_rate(1000_u64.hz());
// Production — watchdog + blackbox
let mut scheduler = Scheduler::new()
.watchdog(500_u64.ms())
.blackbox(64)
.tick_rate(1000_u64.hz());
// Hard real-time — panics without RT capabilities
let mut scheduler = Scheduler::new()
.require_rt()
.tick_rate(1000_u64.hz());
// Safety-critical — require_rt + blackbox + strict deadline misses
let mut scheduler = Scheduler::new()
.require_rt()
.watchdog(500_u64.ms())
.blackbox(64)
.tick_rate(1000_u64.hz())
.max_deadline_misses(3);
Python API
The Python API mirrors the Rust fluent builder:
from horus import Scheduler
# Fluent API — configure nodes inline with chained calls
scheduler = Scheduler(tick_rate=1000.0)
scheduler.add(motor_ctrl, order=0, rate=1000.0)
scheduler.add(planner, order=5)
scheduler.add(telemetry, order=10, rate=1.0)
You can also use keyword arguments with add():
scheduler.add(sensor, order=0, rate=100.0)
scheduler.add(controller, order=1, on_miss="safe_mode")
scheduler.add(logger, order=2, rate=10.0)
scheduler.add(monitor, order=3, failure_policy="skip")
Create a scheduler with a SchedulerConfig:
from horus._horus import SchedulerConfig
# Create scheduler with watchdog config
cfg = SchedulerConfig.with_watchdog()
cfg.tick_rate = 1000.0
scheduler = Scheduler(config=cfg)
Composable config for different deployment stages:
from horus import Scheduler
from horus._horus import SchedulerConfig
# Development — lightweight
scheduler = Scheduler()
# Production — watchdog
cfg = SchedulerConfig.with_watchdog()
cfg.tick_rate = 1000.0
scheduler = Scheduler(config=cfg)
# With blackbox
cfg = SchedulerConfig.with_watchdog()
cfg.tick_rate = 1000.0
cfg = cfg.blackbox_mb(64)
scheduler = Scheduler(config=cfg)
Execution Modes
HORUS supports sequential and parallel execution. You configure this through Scheduler::new() and per-node execution classes.
Use the default. Scheduler::new() gives you predictable, priority-ordered execution that works for most robots.
| Your Situation | Recommended Setup |
|---|---|
| Learning HORUS | Scheduler::new() with defaults |
| Prototyping | Scheduler::new() |
| Need maximum speed | Scheduler::new() with .compute() on heavy nodes |
| Safety-critical (medical, aerospace) | Scheduler::new().require_rt().tick_rate(1000_u64.hz()) with .rate() |
Don't overthink this. Start with Scheduler::new() and configure per-node execution classes as needed.
Sequential Mode (Default)
Nodes execute one-by-one in priority order — same execution order every tick. Predictable and certification-ready.
| Metric | Value |
|---|---|
| Latency | ~100-500ns per node |
| Predictable | Yes — same order every tick |
| Multi-core | No (single thread) |
| Best For | Safety-critical, certification |
When to use: Medical/surgical robots, systems needing reproducible behavior, debugging timing issues, formal verification.
use horus::prelude::*;
// Safety-critical robot controller — 1 kHz tick
// rate() auto-marks nodes as RT with derived budget + deadline
let mut scheduler = Scheduler::new()
.require_rt()
.watchdog(500_u64.ms())
.blackbox(64)
.tick_rate(1000_u64.hz());
scheduler.add(safety_monitor).order(0).rate(1000_u64.hz()).on_miss(Miss::Stop).build()?;
scheduler.add(controller).order(1).rate(1000_u64.hz()).on_miss(Miss::SafeMode).build()?;
scheduler.run()?;
Parallel Mode
Schedules independent nodes on different CPU cores. Nodes at the same order level run concurrently:
| Metric | Value |
|---|---|
| Latency | Variable (depends on workload) |
| Predictable | Ordering within same priority level varies |
| Multi-core | Yes |
| Best For | Multi-sensor fusion, compute-heavy pipelines |
When to use: Multi-sensor robots, compute-heavy pipelines, systems with many independent nodes.
use horus::prelude::*;
// Research robot with many sensors — parallel sensor processing
let mut scheduler = Scheduler::new();
// These sensor nodes run in parallel (same order number)
scheduler.add(lidar_node).order(0).build()?;
scheduler.add(camera_node).order(0).build()?;
scheduler.add(imu_node).order(0).build()?;
// Fusion runs after all sensors (higher order number)
scheduler.add(fusion_node).order(1).build()?;
scheduler.run()?;
Mode Comparison
| Feature | Sequential | Parallel |
|---|---|---|
| Predictable Order | Yes | Per-priority level |
| Multi-core | No | Yes |
| Best Latency | 87-313ns | Variable |
| Certification Ready | Yes | No |
DurationExt and Frequency
HORUS provides ergonomic extension methods for creating Duration and Frequency values, replacing verbose Duration::from_micros(200) calls:
Duration Helpers
use horus::prelude::*;
// Microseconds
let budget = 200_u64.us(); // Duration::from_micros(200)
// Milliseconds
let deadline = 1_u64.ms(); // Duration::from_millis(1)
// Seconds
let timeout = 5_u64.secs(); // Duration::from_secs(5)
Works on u64 literals via the DurationExt trait.
Frequency Type
The .hz() method creates a Frequency that auto-derives timing parameters:
use horus::prelude::*;
let freq = 100_u64.hz();
freq.value() // 100.0 Hz
freq.period() // 10ms (1/frequency)
freq.budget_default() // 8ms (80% of period)
freq.deadline_default() // 9.5ms (95% of period)
Use Frequency with the node builder's .rate() method to auto-configure RT timing:
// Auto-derives budget (80% period) and deadline (95% period)
// Also auto-marks the node as RT
scheduler.add(motor_ctrl)
.order(0)
.rate(500_u64.hz()) // period=2ms, budget=1.6ms, deadline=1.9ms
.on_miss(Miss::Skip)
.build()?;
| Method | Returns | Description |
|---|---|---|
.us() | Duration | Microseconds |
.ms() | Duration | Milliseconds |
.secs() | Duration | Seconds |
.hz() | Frequency | Frequency in Hz |
freq.value() | f64 | Frequency in Hz |
freq.period() | Duration | 1/frequency |
freq.budget_default() | Duration | 80% of period |
freq.deadline_default() | Duration | 95% of period |
See Also
- Scheduling - Scheduler overview and node ordering
- Safety Monitor - Safety monitoring and emergency stop
- Fault Tolerance - Failure policies and recovery
- Record & Replay - Recording and playback