Scheduler API
The Scheduler orchestrates node execution with composable builder configuration.
use horus::prelude::*;
Scheduler
Constructor
let mut scheduler = Scheduler::new();
Creates a scheduler with auto-detected platform capabilities (RT support, CPU topology, memory locking).
Builder Methods
All builder methods return Self for chaining:
let mut scheduler = Scheduler::new()
.tick_rate(1000_u64.hz())
.prefer_rt()
.watchdog(500_u64.ms())
.blackbox(64)
.max_deadline_misses(3)
.verbose(false)
.with_recording();
// Named scheduler (useful for multi-scheduler setups)
let mut scheduler = Scheduler::new()
.name("motor_control")
.tick_rate(1000_u64.hz());
| Method | Default | Description |
|---|---|---|
.name(name) | "Scheduler" | Set the scheduler name |
.tick_rate(freq) | 100 Hz | Global scheduler tick rate |
.prefer_rt() | — | Try RT features (mlockall, SCHED_FIFO), warn on failure |
.require_rt() | — | Enable RT features, panic if unavailable |
.deterministic(bool) | false | Sequential single-threaded execution (no parallelism) |
.watchdog(Duration) | disabled | Detect frozen nodes (auto-creates safety monitor) |
.blackbox(size_mb) | disabled | Flight recorder for crash forensics |
.max_deadline_misses(n) | 100 | Emergency stop threshold |
.cores(&[usize]) | all cores | Pin scheduler threads to specific CPU cores |
.verbose(bool) | true | Enable/disable non-emergency logging |
.with_recording() | disabled | Enable session record/replay |
.telemetry(endpoint) | disabled | Export metrics to HTTP endpoint |
Detailed Method Reference
new
pub fn new() -> Self
Creates a scheduler with auto-detected platform capabilities.
What happens on construction:
- Detects RT capabilities:
SCHED_FIFOsupport,mlockallpermission, CPU topology (~30-100us) - Cleans up stale SHM namespaces from previously crashed processes (< 1ms)
- Sets default tick rate to 100 Hz
Returns: Scheduler with default configuration. No nodes registered.
Example:
let mut scheduler = Scheduler::new();
// Scheduler is ready — add nodes and call .run()
tick_rate
pub fn tick_rate(self, freq: Frequency) -> Self
Sets the global scheduler loop frequency.
Parameters:
freq: Frequency— Target tick rate. Create with.hz()extension:100_u64.hz(),1000_u64.hz(). TheFrequencytype validates at construction — panics on 0, NaN, infinite, or negative values.
Returns: Self (chainable).
Panics: Indirectly — the Frequency constructor panics on invalid values:
0_u64.hz(); // PANICS: zero frequency
Relationship to node rates: Node .rate(freq) can differ from the global tick rate. The scheduler runs at its rate; nodes with different rates are tick-divided.
Examples:
// 100 Hz default control loop
let s = Scheduler::new().tick_rate(100.hz());
// 1 kHz high-frequency servo control
let s = Scheduler::new().tick_rate(1000.hz());
prefer_rt
pub fn prefer_rt(self) -> Self
Try to enable OS-level RT features. Degrades gracefully if unavailable.
What it enables: mlockall (prevent page faults) + SCHED_FIFO (real-time scheduling class).
Behavior: If the system lacks RT capabilities (no SCHED_FIFO or mlockall), logs a warning and continues without them. Your code still runs — just without RT guarantees.
When to use: Production robots where RT is desired but the system might not support it (e.g., development on a non-RT kernel).
Example:
let s = Scheduler::new().prefer_rt();
// On RT kernel: mlockall + SCHED_FIFO enabled
// On non-RT kernel: warning logged, runs normally
require_rt
pub fn require_rt(self) -> Self
Enable OS-level RT features. Panics if unavailable.
Panics: If the system has neither SCHED_FIFO nor mlockall support.
When to use: Safety-critical deployments where running without RT is unacceptable. Forces the developer to fix the deployment environment rather than silently degrading.
Example:
let s = Scheduler::new().require_rt();
// On non-RT kernel: PANICS with "RT capabilities required but not available"
deterministic
pub fn deterministic(self, enabled: bool) -> Self
Enable deterministic execution mode.
Parameters:
enabled: bool—trueto enable,falseto disable (default).
What changes:
- Clock switches from
WallClocktoSimClock(virtual time, advances by exactdtper tick) - Execution is sequential (no parallelism) to ensure deterministic ordering
- Two runs with same inputs produce identical results regardless of CPU speed
When to use: Simulation, reproducible testing, CI pipelines.
Example:
let s = Scheduler::new()
.tick_rate(100.hz())
.deterministic(true);
// Time advances exactly 10ms per tick, regardless of actual CPU time
See Also: Clock API, Deterministic Mode
build (NodeBuilder)
pub fn build(self) -> Result<&mut Scheduler>
Validate the node configuration and register it with the scheduler.
Returns: Result<&mut Scheduler> — the scheduler for further .add() calls.
Errors (rejects):
- Budget or deadline set on non-RT execution class →
Error - Zero budget or deadline →
Error - Empty topic name in
.on("")→Error - Budget > deadline →
Error
Warnings (allows but warns):
.priority()on non-RT node → logged warning.core()on non-RT node → logged warning.on_miss()on node without deadline → logged warning
What happens internally:
finalize()runs RT auto-derivation: if.rate()was set on a BestEffort node, promotes to RT with 80% budget and 95% deadline- Validates all constraints
- Registers node with the scheduler
Example:
// This succeeds:
scheduler.add(my_node).rate(100.hz()).build()?;
// This fails (budget > deadline):
scheduler.add(my_node)
.budget(10.ms())
.deadline(5.ms())
.build()?; // Err: budget exceeds deadline
run
pub fn run(&mut self) -> Result<()>
Start the main scheduler loop. Blocks until Ctrl+C or .stop() is called.
Returns: Result<()> — Ok on graceful shutdown, Err on fatal error.
Behavior:
- Installs
SIGINT/SIGTERMsignal handler - Calls
init()on all nodes (lazy init on first run) - Loops: tick all nodes → sleep until next period → repeat
- On shutdown: calls
shutdown()on all nodes, prints timing report
Example:
scheduler.run()?; // Blocks until Ctrl+C
tick_once
pub fn tick_once(&mut self) -> Result<()>
Execute exactly one tick cycle, then return. No loop, no sleep.
Behavior:
- Calls
init()on all nodes if not yet initialized (lazy init) - Ticks every registered node once in order
- Returns immediately after all nodes have ticked
When to use: Testing, simulation stepping, integration tests.
Example:
let mut scheduler = Scheduler::new();
scheduler.add(my_node).build()?;
// Step through 100 ticks manually
for _ in 0..100 {
scheduler.tick_once()?;
}
Adding Nodes
scheduler.add(my_node)
.order(10)
// NOTE: .rate() auto-enables RT scheduling with 80% budget and 95% deadline
.rate(500_u64.hz())
.build()?;
.add(node) accepts any node — your own structs, driver handles, or factory results. Chain configuration, then .build() to register.
Node configuration chain:
| Method | Default | Description |
|---|---|---|
.order(u32) | 100 | Execution priority (lower = earlier). 0-9: critical, 10-49: sensors, 50-99: processing, 100+: background |
.rate(Frequency) | global | Per-node tick rate. Auto-enables RT scheduling with 80% budget, 95% deadline |
.budget(Duration) | 80% of period | Max execution time per tick. If deadline is not set, deadline = budget (auto-derived) |
.deadline(Duration) | 95% of period | Hard deadline per tick. When exceeded, the Miss policy fires |
.on_miss(Miss) | Warn | What to do on deadline miss: Warn, Skip, SafeMode, Stop |
.failure_policy(FailurePolicy) | none | Recovery on tick failure: Fatal, restart(n, backoff), skip(n, cooldown), Ignore |
.compute() | — | Run on parallel thread pool (CPU-bound work) |
.on(topic) | — | Event-triggered: tick when topic receives data (empty topic rejected) |
.async_io() | — | Run on tokio blocking pool (I/O-bound work) |
.priority(i32) | none | OS SCHED_FIFO priority (1-99, RT only — warned if non-RT) |
.core(usize) | none | Pin to CPU core (RT only — warned if non-RT) |
.watchdog(Duration) | global | Per-node watchdog timeout override |
.build() | — | Validate configuration and register. Rejects conflicts, warns misuse |
What
.build()validates: Rejects budget/deadline on non-RT classes, zero budget/deadline, empty.on("")topics. Warns (but allows).priority(),.core(), and.on_miss()on nodes without RT/deadline. See Validation & Conflicts for the full matrix.
Execution Control
| Method | Returns | Description |
|---|---|---|
.run() | Result<()> | Main loop — runs until Ctrl+C or .stop() |
.run_for(duration) | Result<()> | Run for specific duration, then shut down |
.tick_once() | Result<()> | Execute exactly one tick cycle (no loop, no sleep) |
.tick(&[names]) | Result<()> | One tick for specific nodes only |
.set_node_rate(name, freq) | &mut Self | Change a node's tick rate at runtime |
.stop() | () | Signal graceful shutdown |
.is_running() | bool | Check if scheduler is actively ticking |
Monitoring
| Method | Returns | Description |
|---|---|---|
.metrics() | Vec<NodeMetrics> | Performance metrics for all nodes |
.node_list() | Vec<String> | Names of all registered nodes |
.status() | String | Formatted status report |
Example
use horus::prelude::*;
fn main() -> Result<()> {
let mut scheduler = Scheduler::new()
.tick_rate(1000_u64.hz())
.prefer_rt()
.watchdog(500_u64.ms());
// NOTE: .rate() auto-promotes this node to RT with budget=1.6ms (80%) and deadline=1.9ms (95%)
scheduler.add(SensorNode::new())
.order(0)
.rate(500_u64.hz())
.build()?;
// NOTE: .compute() runs on a worker thread pool — no RT scheduling applied
scheduler.add(PlannerNode::new())
.order(50)
.compute()
.build()?;
scheduler.add(ControlNode::new())
.order(10)
// NOTE: .rate() auto-promotes to RT; .on_miss(SafeMode) calls enter_safe_state() on deadline miss
.rate(1000_u64.hz())
.on_miss(Miss::SafeMode)
.build()?;
scheduler.run()?;
Ok(())
}
Node Configuration
After .add(node), chain these methods to configure the node before .build().
Timing & Ordering
| 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 |
.budget(Duration) | Explicit CPU time budget per tick |
.deadline(Duration) | Explicit deadline per tick |
.on_miss(Miss) | Deadline miss policy: Warn, Skip, SafeMode, Stop |
Execution Class
| Method | Class | Description |
|---|---|---|
.compute() | Compute | Offloaded to worker thread pool (planning, SLAM, ML) |
.on(topic) | Event | Wakes only when the named topic has new data |
.async_io() | AsyncIo | Runs on async executor (network, disk, cloud) |
| (none) | BestEffort | Default — ticks every scheduler cycle |
.rate(freq) | RT (auto) | Auto-promoted when rate is set on a BestEffort node |
Failure & Finalization
| Method | Description |
|---|---|
.failure_policy(policy) | Per-node failure handling (Fatal, Restart, Skip, Ignore) |
.build() | Finalize and register — returns Result<&mut Scheduler> |
Order Guidelines
| Range | Use |
|---|---|
| 0-9 | Critical real-time (motor control, safety) |
| 10-49 | High priority (sensors, fast loops) |
| 50-99 | Normal (processing, planning) |
| 100-199 | Low (logging, diagnostics) |
| 200+ | Background (telemetry) |
Node Builder Detailed Reference
rate (NodeBuilder)
pub fn rate(self, freq: Frequency) -> Self
Set a per-node tick rate. Automatically promotes the node to RT execution class with derived budget (80% of period) and deadline (95% of period).
Parameters:
freq: Frequency— Node-specific tick rate. Created with.hz():500_u64.hz().
Auto-derivation: When .rate() is called on a BestEffort node:
budget = period * 0.80(e.g., 500 Hz → period 2ms → budget 1.6ms)deadline = period * 0.95(e.g., 500 Hz → period 2ms → deadline 1.9ms)- Execution class →
Rt
Interaction with .budget() and .deadline(): Explicit .budget() or .deadline() override the auto-derived values. Order doesn't matter — derivation happens at finalize().
Example:
scheduler.add(sensor)
.rate(500.hz()) // RT: budget=1.6ms, deadline=1.9ms
.build()?;
scheduler.add(motor)
.rate(1000.hz())
.budget(500.us()) // Override: budget=0.5ms instead of 0.8ms
.build()?;
budget (NodeBuilder)
pub fn budget(self, duration: Duration) -> Self
Set the maximum CPU time allowed per tick.
Parameters:
duration: Duration— Maximum execution time. Created with.us()or.ms():200_u64.us(),1_u64.ms().
Errors: .build() rejects if:
budgetis zerobudget > deadlinebudgetis set on a non-RT node (no.rate()or explicit RT class)
Example:
scheduler.add(planner)
.rate(100.hz())
.budget(5.ms()) // Must complete tick within 5ms
.deadline(8.ms()) // Hard deadline at 8ms
.on_miss(Miss::Skip)
.build()?;
on_miss (NodeBuilder)
pub fn on_miss(self, policy: Miss) -> Self
Set the policy for when a node exceeds its deadline.
Parameters:
policy: Miss— One ofWarn,Skip,SafeMode,Stop.
Default: Miss::Warn.
Miss Enum
| Variant | Behavior | Use Case |
|---|---|---|
Miss::Warn | Log warning, continue | Soft real-time (logging, UI) |
Miss::Skip | Skip this tick | Firm real-time (video encoding) |
Miss::SafeMode | Call enter_safe_state() | Motor controllers, safety nodes |
Miss::Stop | Stop entire scheduler | Hard real-time safety-critical |
Default is Miss::Warn.
NodeMetrics
Returned by scheduler.metrics(). Read-only performance data for each node.
| Method | Returns | Description |
|---|---|---|
.name() | &str | Node name |
.order() | u32 | Execution order |
.total_ticks() | u64 | Total tick count |
.successful_ticks() | u64 | Ticks without errors |
.avg_tick_duration_ms() | f64 | Mean tick duration |
.max_tick_duration_ms() | f64 | Worst-case tick duration |
.min_tick_duration_ms() | f64 | Best-case tick duration |
.last_tick_duration_ms() | f64 | Most recent tick duration |
.messages_sent() | u64 | Total messages published |
.messages_received() | u64 | Total messages consumed |
.errors_count() | u64 | Error count |
.warnings_count() | u64 | Warning count |
.uptime_seconds() | f64 | Node uptime |
Performance Monitoring Example
// After running for a while, check node health
for metric in scheduler.metrics() {
if metric.max_tick_duration_ms() > 1.0 {
hlog!(warn, "Node '{}' worst case: {:.2}ms (avg: {:.2}ms)",
metric.name(),
metric.max_tick_duration_ms(),
metric.avg_tick_duration_ms(),
);
}
}
RtStats
Real-time execution statistics for nodes with .rate() set. Access via node-level timing reports.
| Method | Returns | Description |
|---|---|---|
.deadline_misses() | u64 | Total deadline misses |
.budget_violations() | u64 | Total budget violations |
.worst_execution() | Duration | Worst-case tick duration |
.last_execution() | Duration | Most recent tick duration |
.jitter_us() | f64 | Execution jitter in microseconds |
.avg_execution_us() | f64 | Average tick duration in microseconds |
.sampled_ticks() | u64 | Number of ticks sampled |
.summary() | String | Formatted timing summary |
Example
use horus::prelude::*;
let mut scheduler = Scheduler::new()
.tick_rate(1000_u64.hz())
.prefer_rt();
scheduler.add(MotorController::new())
.order(0)
// NOTE: .rate(1000.hz()) auto-derives budget=0.8ms and deadline=0.95ms
.rate(1000_u64.hz())
// NOTE: Miss::SafeMode calls enter_safe_state() on the node when a deadline is missed
.on_miss(Miss::SafeMode)
.build()?;
// Run for 5 seconds, then check stats
scheduler.run_for(5_u64.secs())?;
for metric in scheduler.metrics() {
println!("{}: avg={:.2}ms, worst={:.2}ms, misses={}",
metric.name(),
metric.avg_tick_duration_ms(),
metric.max_tick_duration_ms(),
metric.errors_count(),
);
}
Advanced Runtime Methods
These methods require elevated privileges (root or CAP_SYS_NICE) on Linux. They fail gracefully with an error on unsupported platforms.
| Method | Description |
|---|---|
set_os_priority(i32) | Set OS-level SCHED_FIFO priority (1-99, higher = more priority) |
pin_to_cpu(usize) | Pin scheduler thread to a specific CPU core |
lock_memory() | Lock all memory pages to prevent swapping (mlockall) |
prefault_stack(usize) | Pre-allocate stack pages to avoid page faults during execution |
// Production RT setup — call before run()
scheduler.set_os_priority(80)?; // High SCHED_FIFO priority
scheduler.pin_to_cpu(2)?; // Isolated CPU core
scheduler.lock_memory()?; // Prevent page faults
scheduler.prefault_stack(512 * 1024)?; // 512KB stack
scheduler.run()?;
These are automatically applied when using .require_rt() on the builder. Use these methods when you need manual control over which features to enable.
Monitoring & Metrics
| Method | Returns | Description |
|---|---|---|
rt_stats(node_name) | Option<&RtStats> | RT timing stats for a specific node (deadline misses, worst execution, jitter) |
safety_stats() | Option<SafetyStats> | Aggregate safety stats (budget overruns, watchdog expirations) |
metrics() | Vec<NodeMetrics> | Per-node metrics (tick counts, durations, errors) |
node_list() | Vec<String> | Names of all registered nodes |
running_flag() | Arc<AtomicBool> | Shared flag for external stop control |
// Check RT performance after a test run
if let Some(stats) = scheduler.rt_stats("motor_ctrl") {
println!("Deadline misses: {}", stats.deadline_misses());
println!("Worst execution: {:?}", stats.worst_execution());
println!("Jitter: {:.1} μs", stats.jitter_us());
}
Scheduler Method Reference
new
pub fn new() -> Self
Create a scheduler with default settings. Detects runtime capabilities (~30-100μs) but applies no OS-level features until builder methods opt in.
Returns: Scheduler with default config (100Hz tick rate, no watchdog, no blackbox).
Example:
let mut scheduler = Scheduler::new();
name
pub fn name(mut self, name: &str) -> Self
Set the scheduler's name (for logging and diagnostics). Default: "Scheduler".
Example:
let mut sched = Scheduler::new().name("MainControl");
tick_rate
pub fn tick_rate(mut self, freq: Frequency) -> Self
Set the global tick rate. Default: 100 Hz. Individual nodes can override with .rate().
Parameters:
freq: Frequency— Target rate (e.g.,1000.hz())
Example:
let mut sched = Scheduler::new().tick_rate(1000.hz()); // 1kHz main loop
watchdog
pub fn watchdog(mut self, timeout: Duration) -> Self
Enable frozen node detection. Creates a safety monitor that checks node tick duration against the timeout. If a node doesn't complete within the timeout, graduated degradation triggers.
Parameters:
timeout: Duration— Maximum allowed tick duration (e.g.,500.ms())
Example:
let mut sched = Scheduler::new().watchdog(500.ms());
blackbox
pub fn blackbox(mut self, size_mb: usize) -> Self
Enable the BlackBox flight recorder. Records node ticks, timing, and events in a circular buffer for post-mortem analysis.
Parameters:
size_mb: usize— Buffer size in megabytes
Example:
let mut sched = Scheduler::new().blackbox(64); // 64MB flight recorder
require_rt
pub fn require_rt(mut self) -> Self
Require all RT features. Panics if RT capabilities are unavailable (no CAP_SYS_NICE, no PREEMPT_RT kernel). Applies: SCHED_FIFO priority, memory locking (mlockall), CPU affinity.
Panics: If the system doesn't support real-time scheduling.
Example:
let mut sched = Scheduler::new().require_rt(); // panics without RT support
prefer_rt
pub fn prefer_rt(mut self) -> Self
Request RT features with graceful degradation. Applies what's available, records degradations for features that fail. Use degradations() to check what wasn't applied.
Example:
let mut sched = Scheduler::new().prefer_rt(); // best-effort RT
deterministic
pub fn deterministic(mut self, enabled: bool) -> Self
Enable deterministic execution mode. Uses SimClock (fixed dt), seeded RNG, and lockstep execution. Essential for simulation and replay.
Example:
let mut sched = Scheduler::new().deterministic(true);
max_deadline_misses
pub fn max_deadline_misses(mut self, n: u64) -> Self
Set the threshold for consecutive deadline misses before a node is isolated. Default: 100.
Example:
let mut sched = Scheduler::new()
.watchdog(500.ms())
.max_deadline_misses(5); // isolate after 5 consecutive misses
verbose
pub fn verbose(mut self, enabled: bool) -> Self
Enable/disable non-emergency logging. Default: true. Set false for quieter production logs.
with_recording
pub fn with_recording(mut self) -> Self
Enable session recording for replay and debugging.
NodeBuilder Method Reference
Returned by scheduler.add(node). Chain methods to configure the node, then call .build().
order
pub fn order(mut self, order: u32) -> Self
Set execution priority. Lower = runs first. Typical: 0 (safety), 10 (control), 50 (sensors), 100+ (logging).
Example:
scheduler.add(safety_node).order(0).build()?;
scheduler.add(motor_ctrl).order(10).build()?;
rate
pub fn rate(mut self, freq: Frequency) -> Self
Set per-node tick rate. Auto-derives budget (80% of period) and deadline (95% of period). Auto-marks as RT execution class.
Parameters:
freq: Frequency— Tick rate (e.g.,1000.hz())
Caveats: Setting .rate() then .compute() produces Compute (not RT) due to deferred finalize. Last execution class setter wins.
Example:
scheduler.add(imu_reader).order(0).rate(1000.hz()).build()?;
budget
pub fn budget(mut self, budget: Duration) -> Self
Set tick execution time budget. Overrides the auto-derived budget from .rate(). Auto-marks as RT.
Parameters:
budget: Duration— Max tick execution time (e.g.,500.us())
Example:
scheduler.add(motor)
.order(0)
.rate(1000.hz())
.budget(300.us()) // override auto-derived 800μs
.build()?;
deadline
pub fn deadline(mut self, deadline: Duration) -> Self
Set hard deadline. When exceeded, the Miss policy fires. Auto-marks as RT.
Parameters:
deadline: Duration— Hard deadline (e.g.,950.us())
on_miss
pub fn on_miss(mut self, policy: Miss) -> Self
Set the deadline miss policy.
Parameters:
policy: Miss—Miss::Warn,Miss::Skip,Miss::SafeMode, orMiss::Stop
Example:
scheduler.add(motor)
.rate(1000.hz())
.on_miss(Miss::SafeMode) // enter safe state on deadline miss
.build()?;
compute
pub fn compute(mut self) -> Self
Mark as CPU-bound. Runs on a worker thread pool, not the main tick loop. Use for planning, ML inference, image processing.
on
pub fn on(mut self, topic: &str) -> Self
Event-driven execution. Node ticks only when the named topic receives a new message.
Example:
scheduler.add(handler).on("emergency_stop").build()?;
async_io
pub fn async_io(mut self) -> Self
Run on the tokio async runtime. Use for network I/O, file I/O, HTTP requests.
failure_policy
pub fn failure_policy(mut self, policy: FailurePolicy) -> Self
Set error handling policy for this node.
priority
pub fn priority(mut self, prio: i32) -> Self
Set OS-level thread priority (SCHED_FIFO, 1-99). Requires CAP_SYS_NICE.
core
pub fn core(mut self, cpu_id: usize) -> Self
Pin this node's thread to a specific CPU core.
Example:
scheduler.add(motor).order(0).rate(1000.hz()).core(2).build()?;
build
pub fn build(mut self) -> HorusResult<&'a mut Scheduler>
Finalize and register the node. Validates configuration, applies deferred finalize (RT auto-detection), and adds the node to the scheduler.
Returns: HorusResult<&mut Scheduler> — the scheduler for chaining, or error if validation fails.
Panics: Never panics — returns Err on invalid config.
Example:
scheduler.add(my_node)
.order(0)
.rate(100.hz())
.build()?; // registered and ready
Execution Method Reference
run
pub fn run(&mut self) -> HorusResult<()>
Start the tick loop. Blocks until Ctrl+C, stop(), or fatal error. Calls init() on all nodes (lazy, first call only), then ticks in priority order.
Example:
scheduler.run()?; // blocks until Ctrl+C
run_for
pub fn run_for(&mut self, duration: Duration) -> HorusResult<()>
Run for a specific duration, then shut down.
Example:
scheduler.run_for(30.secs())?; // run 30 seconds then stop
tick_once
pub fn tick_once(&mut self) -> HorusResult<()>
Execute exactly one tick cycle. Essential for deterministic testing — tick, verify, tick, verify.
Example:
scheduler.tick_once()?;
let stats = scheduler.metrics();
// verify one tick executed
stop
pub fn stop(&self)
Signal graceful shutdown. The current tick completes, then shutdown() runs on all nodes in reverse order.
Production Patterns
Warehouse AGV
Mobile robot with safety monitor, lidar SLAM, path planner, and motor control:
let mut sched = Scheduler::new()
.watchdog(500_u64.ms())
.blackbox(64)
.tick_rate(100.hz());
// Safety runs first every tick — never skip
sched.add(EmergencyStopMonitor::new()?).order(0).rate(100.hz()).on_miss(Miss::Stop).build()?;
// Sensors at 50Hz
sched.add(LidarDriver::new()?).order(10).rate(50.hz()).build()?;
sched.add(WheelOdometry::new()?).order(11).rate(100.hz()).build()?;
// SLAM is CPU-heavy — runs on thread pool
sched.add(SlamNode::new()?).order(20).compute().build()?;
// Planner at 10Hz — doesn't need to be fast
sched.add(PathPlanner::new()?).order(30).rate(10.hz()).build()?;
// Motor control at 100Hz with strict deadline
sched.add(MotorController::new()?).order(40).rate(100.hz()).budget(5.ms()).on_miss(Miss::Skip).build()?;
// Logger at 1Hz — background priority
sched.add(TelemetryLogger::new()?).order(200).rate(1.hz()).build()?;
sched.run()?;
Drone Flight Controller
High-frequency IMU processing with tight deadlines:
let mut sched = Scheduler::new()
.require_rt()
.watchdog(100_u64.ms())
.tick_rate(1000.hz());
sched.add(ImuReader::new()?).order(0).rate(1000.hz()).budget(200.us()).build()?;
sched.add(AttitudeController::new()?).order(1).rate(1000.hz()).budget(300.us()).on_miss(Miss::SafeMode).build()?;
sched.add(PositionController::new()?).order(2).rate(200.hz()).budget(1.ms()).build()?;
sched.add(MotorMixer::new()?).order(3).rate(1000.hz()).budget(100.us()).build()?;
sched.run()?;
Other Methods
scheduler_name() -> &str
Returns the scheduler's name (set via .name() builder or defaults to "Scheduler").
let sched = Scheduler::new().name("MainLoop");
assert_eq!(sched.scheduler_name(), "MainLoop");
add_critical_node(node_name, watchdog_timeout) -> Result<&mut Self>
Mark a node as critical with a custom watchdog timeout. If this node freezes, the safety monitor triggers immediately (not waiting for the global watchdog). Requires .watchdog() to be enabled.
let mut sched = Scheduler::new().watchdog(500.ms());
sched.add(MotorController::new()?).order(0).build()?;
sched.add_critical_node("MotorController", 100.ms())?; // 100ms watchdog for this node
Advanced: Most users should use the per-node
.watchdog()builder method instead.add_critical_nodeis for post-registration configuration.
apply_config(config) -> &mut Self
Advanced: Apply a
SchedulerConfigstruct to the scheduler. Most users should use the builder methods (.watchdog(),.blackbox(),.tick_rate()) instead.
See Also
- Scheduler Concepts — Conceptual overview and architecture
- Scheduler Configuration — Advanced tuning and deployment patterns
- Safety Monitor — Budget enforcement and graduated degradation
- BlackBox — Flight recorder for post-mortem analysis
- Node API — The Node trait and lifecycle
- HealthStatus — Node health states (Healthy, Warning, Unhealthy, Isolated)
- NodeState — Node lifecycle states and transitions
- Python Bindings — Python Scheduler API
- Driver API — Load hardware from config