Adora
智能数据流导向机器人架构 (Agentic Dataflow-Oriented Robotic Architecture) – 一个 100% Rust 的实时机器人与 AI 应用框架。
为什么选择 Adora?
Performance
- 10-17x faster than ROS2 Python – 100% Rust internals with zero-copy shared memory IPC for messages >4KB, flat latency from 4KB to 4MB payloads
- Apache Arrow native – columnar memory format end-to-end with zero serialization overhead; shared across all language bindings
Developer Experience
- Single CLI, full lifecycle –
adora runfor local dev,adora up/startfor distributed prod, plus build, logs, monitoring, record/replay all from one tool - Declarative YAML dataflows – define pipelines as directed graphs, connect nodes through typed inputs/outputs, optional type annotations with static validation
- Multi-language nodes – write nodes in Rust, Python, C, or C++ with native APIs (not wrappers); mix languages freely in one dataflow
- Reusable modules – compose sub-graphs as standalone YAML files with typed inputs/outputs, parameters, and nested composition
- Hot reload – live-reload Python operators without restarting the dataflow
Production Readiness
- Fault tolerance – per-node restart policies (never/on-failure/always), exponential backoff, health monitoring, circuit breakers with configurable input timeouts
- Distributed by default – local shared memory between co-located nodes, automatic Zenoh pub-sub for cross-machine communication, SSH-based cluster management with label scheduling
- Configurable queue policies –
drop_oldest(default) orbackpressureper input, with metrics on dropped messages - OpenTelemetry – built-in structured logging with rotation/routing, metrics, distributed tracing
Debugging and Observability
- Record/replay – capture dataflow messages to
.adorecfiles, replay offline at any speed with node substitution - Topic inspection –
topic echoto print live data,topic hzTUI for frequency analysis,topic infofor schema and bandwidth - Resource monitoring –
adora topTUI showing per-node CPU, memory, queue depth, network I/O across all machines - Log aggregation – subscribe to
adora/logsto receive structured log messages from all nodes without extra wiring - Trace inspection –
trace listandtrace viewfor viewing coordinator spans without external infrastructure
Ecosystem
- Communication patterns – built-in service (request/reply), action (goal/feedback/result), and streaming (session/segment/chunk) patterns via well-known metadata keys
- ROS2 bridge – bidirectional interop with ROS2 topics, services, and actions
- In-process operators – lightweight functions that run inside a shared runtime, avoiding per-node process overhead
下一步
安装
From crates.io (recommended)
cargo install adora-cli # CLI(adora 命令)
pip install adora-rs # Python 节点/算子 API
从源码安装
git clone https://github.com/dora-rs/adora.git
cd adora
cargo build --release -p adora-cli
PATH=$PATH:$(pwd)/target/release
# Python API (requires maturin >= 1.8: pip install maturin)
# Must run from the package directory for dependency resolution
cd apis/python/node && maturin develop --uv && cd ../../..
平台安装器
macOS / Linux:
curl --proto '=https' --tlsv1.2 -LsSf \
https://github.com/dora-rs/adora/releases/latest/download/adora-cli-installer.sh | sh
Windows:
powershell -ExecutionPolicy ByPass -c "irm https://github.com/dora-rs/adora/releases/latest/download/adora-cli-installer.ps1 | iex"
构建特性
| 特性 | 描述 | 默认 |
|---|---|---|
tracing | OpenTelemetry 追踪支持 | 是 |
metrics | OpenTelemetry 指标收集 | 否 |
python | Python 算子支持(PyO3) | 否 |
redb-backend | 持久化协调器状态(redb) | 否 |
prometheus | 协调器上的 Prometheus /metrics 端点 | 否 |
cargo install adora-cli --features redb-backend
验证
adora --version
adora status
Python 快速入门
本指南将引导你使用 Python 编写 adora 数据流的节点和算子。
前提条件
cargo install adora-cli # CLI(adora 命令)
pip install adora-rs # Python 节点/算子 API
adora-rs 包已包含 pyarrow 作为依赖。
从源码构建(替代 pip install adora-rs):
pip install maturin # requires >= 1.8
cd apis/python/node && maturin develop --uv && cd ../../..
Hello World:发送者与接收者
创建三个文件:
sender.py – 发送 100 条带编号的消息:
import pyarrow as pa
from adora import Node
node = Node()
for i in range(100):
node.send_output("message", pa.array([i]))
receiver.py – 接收并打印消息:
from adora import Node
node = Node()
for event in node:
if event["type"] == "INPUT":
values = event["value"].to_pylist()
print(f"Received {event['id']}: {values}")
elif event["type"] == "STOP":
break
dataflow.yml – 将发送者连接到接收者:
nodes:
- id: sender
path: sender.py
outputs:
- message
- id: receiver
path: receiver.py
inputs:
message: sender/message
运行:
adora run dataflow.yml
Events
每次调用 node.next() 或通过 for event in node 迭代都会返回一个事件字典:
| Key | 类型 | 描述 |
|---|---|---|
type | str | "INPUT", "INPUT_CLOSED", "STOP", 或 "ERROR" |
id | str | 输入名称(例如 "message")– 仅适用于 INPUT 事件 |
value | pyarrow.Array 或 None | 数据载荷 |
metadata | dict | 追踪/路由元数据 |
通过检查 event["type"] 来处理事件:
for event in node:
match event["type"]:
case "INPUT":
process(event["id"], event["value"])
case "INPUT_CLOSED":
print(f"Input {event['id']} closed")
case "STOP":
break
使用 Arrow 数据
所有数据在 adora 中以 Apache Arrow 数组的形式流动。常见模式:
import pyarrow as pa
# Simple values
node.send_output("count", pa.array([42]))
node.send_output("names", pa.array(["alice", "bob"]))
# Read values back
values = event["value"].to_pylist() # [42] or ["alice", "bob"]
# Structured data
struct = pa.StructArray.from_arrays(
[pa.array([1.5]), pa.array(["hello"])],
names=["x", "y"],
)
node.send_output("point", struct)
# Raw bytes (images, serialized data, etc.)
node.send_output("frame", pa.array(raw_bytes))
Operators
算子是节点的轻量级替代方案。它们在 adora 运行时进程内运行(无需单独的操作系统进程),因此对于简单的转换操作更加高效。
定义一个包含 on_event 方法的 Operator 类:
# doubler_op.py
import pyarrow as pa
from adora import AdoraStatus
class Operator:
def on_event(self, event, send_output) -> AdoraStatus:
if event["type"] == "INPUT":
value = event["value"].to_pylist()[0]
send_output("doubled", pa.array([value * 2]), event["metadata"])
return AdoraStatus.CONTINUE
在 YAML 中使用 operator 而非 path 来引用它:
nodes:
- id: timer
path: adora/timer/millis/500
outputs:
- tick
- id: doubler
operator:
python: doubler_op.py
inputs:
tick: timer/tick
outputs:
- doubled
何时使用算子 vs 节点:
| Nodes | Operators | |
|---|---|---|
| 进程模型 | 独立的操作系统进程 | 进程内(共享运行时) |
| 启动开销 | Higher | Lower |
| Isolation | 完全的进程隔离 | 共享内存空间 |
| 最适用于 | 长时间运行、重计算任务 | 轻量级转换、过滤 |
异步节点
对于需要异步 I/O(HTTP 调用、数据库查询等)的节点,请使用 recv_async():
import asyncio
from adora import Node
async def main():
node = Node()
for _ in range(50):
event = await node.recv_async()
if event["type"] == "STOP":
break
# Do async work here
result = await fetch_data(event["value"])
node.send_output("result", result)
asyncio.run(main())
参见 examples/python-async 获取完整示例。
日志
使用 node.log() 进行结构化日志记录,可与 adora logs 集成:
node.log("info", "Processing item", {"count": str(i)})
或者使用 Python 标准的 logging 模块 – adora 会自动捕获 stdout/stderr:
import logging
logging.info("Processing item %d", i)
参见 examples/python-logging 了解日志模块集成。
Timers
内置的定时器节点无需编写任何代码即可生成周期性的定时信号:
nodes:
- id: tick-source
path: adora/timer/millis/100 # tick every 100ms
outputs:
- tick
- id: my-node
path: my_node.py
inputs:
tick: tick-source/tick
也可使用:adora/timer/hz/30 表示 30 Hz。
下一步
- Python API 参考 – Node、Operator、DataflowBuilder、CUDA 的完整 API 文档
- 通信模式 – 服务(请求/应答)和动作(目标/反馈/结果)模式
- 示例 – python-dataflow、python-async、python-drain、python-concurrent-rw、python-multiple-arrays
- 分布式部署 – 使用
adora up跨多台机器运行
Adora Architecture
Comprehensive architecture reference for Adora (AI-Dora, Agentic Dataflow-Oriented Robotic Architecture) — a 100% Rust framework for real-time robotics and AI applications.
Overview and Design Philosophy
Adora is built on four core principles:
- Dataflow-oriented: Applications are directed graphs of nodes connected by typed data channels. Nodes declare inputs and outputs; the framework handles routing, scheduling, and lifecycle.
- Zero-copy performance: Messages above 4 KiB use shared memory with 128-byte aligned buffers and atomic coordination, achieving 10-17x lower latency than ROS2.
- Multi-language: First-class support for Rust, Python (PyO3), C, and C++ nodes — all sharing the same Apache Arrow data format.
- Four-layer stack: Message protocol, core libraries, daemon/runtime execution, and CLI/coordinator orchestration.
Architecture Stack
┌─────────────────────────────────────────────────┐
│ CLI (adora) Coordinator (orchestrator) │ Layer 4: Orchestration
├─────────────────────────────────────────────────┤
│ Daemon (per-machine) Runtime (operators) │ Layer 3: Execution
├─────────────────────────────────────────────────┤
│ adora-core shared-memory-server Node API │ Layer 2: Core Libraries
├─────────────────────────────────────────────────┤
│ adora-message (protocol + Arrow types) │ Layer 1: Protocol
└─────────────────────────────────────────────────┘
Workspace Structure
Rust edition 2024, MSRV 1.85.0, workspace version 0.1.0. All crates share the workspace version.
Binaries (7)
| Path | Crate | Role |
|---|---|---|
binaries/cli | adora-cli | CLI binary (adora command) — build, run, stop dataflows |
binaries/coordinator | adora-coordinator | Orchestrates distributed multi-daemon deployments; WebSocket server |
binaries/daemon | adora-daemon | Spawns nodes, manages shared-memory/TCP communication per machine |
binaries/runtime | adora-runtime | In-process operator execution (Python/C/C++ via dlopen/PyO3) |
binaries/ros2-bridge-node | adora-ros2-bridge-node | ROS2 integration node |
binaries/record-node | adora-record-node | Records dataflow messages to .adorec format |
binaries/replay-node | adora-replay-node | Replays recorded messages from .adorec files |
Core Libraries (6)
| Path | Crate | Role |
|---|---|---|
libraries/message | adora-message | All inter-component message types, protocol definitions, Arrow metadata |
libraries/core | adora-core | Dataflow descriptor parsing, build utilities, Zenoh config |
libraries/shared-memory-server | shared-memory-server | Zero-copy IPC for messages >= 4 KiB |
libraries/recording | adora-recording | Recording format (.adorec): bincode header + entries + footer |
libraries/arrow-convert | adora-arrow-convert | Arrow type conversions (numeric, datetime) |
libraries/coordinator-store | adora-coordinator-store | State persistence for coordinator (in-memory or redb backend) |
Extension Libraries (5)
| Path | Crate | Role |
|---|---|---|
libraries/extensions/telemetry/tracing | adora-tracing | OpenTelemetry distributed tracing (OTLP exporter) |
libraries/extensions/telemetry/metrics | adora-metrics | System metrics collection (CPU, memory, disk) |
libraries/extensions/download | adora-download | HTTP file download utility for operator/node binaries |
libraries/extensions/ros2-bridge | adora-ros2-bridge | ROS2 integration: topic pub/sub, services, actions |
libraries/log-utils | adora-log-utils | Log parsing, merging, filtering, formatting |
API Crates (9)
| Path | Crate | Language |
|---|---|---|
apis/rust/node | adora-node-api | Rust |
apis/rust/operator | adora-operator-api | Rust |
apis/rust/operator/macros | adora-operator-api-macros | Rust (proc-macro) |
apis/rust/operator/types | adora-operator-api-types | Rust (FFI-safe types) |
apis/python/node | adora-node-api-python | Python (PyO3) – builds the adora module |
apis/python/operator | adora-operator-api-python | Python (PyO3) – compiled into adora-node-api-python |
apis/c/node | adora-node-api-c | C |
apis/c/operator | adora-operator-api-c | C/C++ |
Component Architecture
CLI
The adora command provides three command groups:
Lifecycle (run, up, down, build, start, stop, restart):
adora runexecutes a dataflow locally without coordinator/daemon (single-machine shortcut)adora up/adora downmanage coordinator + daemon infrastructureadora start/adora stopcontrol dataflows on a running coordinator
Monitoring (list, logs, inspect, topic, node, record, replay, trace):
- Real-time inspection with
adora inspect top - Topic subscription and data inspection
- Recording and replay via
.adorecfiles
Setup (status, new, graph, system, completion, self):
- Project scaffolding, dataflow visualization, self-update
Coordinator
The coordinator is an Axum-based WebSocket server that orchestrates distributed deployments.
┌──────────────────┐
│ Coordinator │
WS /api/control │ ┌────────────┐ │ WS /api/daemon
CLI ◄──────────────────► │ │ State │ │ ◄──────────────────► Daemon(s)
│ │ Store │ │
│ └────────────┘ │
│ /api/artifacts │
│ /health │
└──────────────────┘
WebSocket routes:
/api/control— CLI control plane (build, start, stop, list, logs, topic subscribe)/api/daemon— Daemon registration and event stream/api/artifacts/{build_id}/{node_id}— Binary artifact downloads/health— Health check endpoint
State management: In-memory by default, optional persistent storage via redb backend.
Daemon
The daemon runs one per machine and manages the lifecycle of all nodes on that machine.
┌──────────────────────────────────────────────────────┐
│ Daemon │
│ │
│ ┌──────────┐ ┌───────────┐ ┌──────────────────┐ │
│ │ Event │ │ Spawner │ │ Node Comm │ │
│ │ Loop │──│ (nodes) │ │ ┌──────────────┐ │ │
│ │ │ └───────────┘ │ │ TCP listener │ │ │
│ │ Sources: │ ┌───────────┐ │ │ Shmem server │ │ │
│ │ • Coord │ │ Fault │ │ │ Unix socket │ │ │
│ │ • Nodes │──│ Tolerance │ │ └──────────────┘ │ │
│ │ • Zenoh │ └───────────┘ └──────────────────┘ │
│ │ • Timers │ │
│ └──────────┘ │
│ │
│ ┌──────────────────────────────────────────────┐ │
│ │ Running Dataflows │ │
│ │ ├─ Node A (process) ◄──► TCP/Shmem │ │
│ │ ├─ Node B (process) ◄──► TCP/Shmem │ │
│ │ └─ Runtime (operators) ◄──► TCP/Shmem │ │
│ └──────────────────────────────────────────────┘ │
└──────────────────────────────────────────────────────┘
Event loop (Daemon::run_inner()): Async Tokio event loop merging:
- Coordinator commands (WebSocket)
- Node events (TCP/shared memory)
- Inter-daemon events (Zenoh)
- Heartbeat (5s interval), metrics collection (2s), health checks (5s default)
Node spawning:
- Create working directory for the node
- Set up communication channel (TCP, shmem, or Unix domain socket)
- Serialize
NodeConfigto environment variable - Spawn process with sanitized environment (blocks
LD_PRELOAD,DYLD_INSERT_LIBRARIES, etc.) - Monitor via
ProcessHandle
Runtime
The runtime executes in-process operators (Python, shared library, WASM) in a dedicated process.
┌──────────────────────────────┐
│ Runtime │
│ │
│ ┌────────────────────────┐ │
│ │ Operator Runner │ │
│ │ (separate thread) │ │
│ │ │ │
│ │ SharedLibrary → dlopen │ │
│ │ Python → PyO3 │ │
│ │ Wasm → (planned) │ │
│ └──────────┬─────────────┘ │
│ │ flume(2) │
│ ┌──────────▼─────────────┐ │
│ │ Event Merge Loop │ │
│ │ ├─ OperatorEvent │ │
│ │ └─ DaemonEvent │ │
│ └────────────────────────┘ │
└──────────────────────────────┘
- Single-threaded Tokio runtime
- Operator runs in a separate thread, communicates via
flume::bounded(2)channel - Input queue size per data ID configurable (default: 10)
Nodes
Nodes are standalone processes that communicate with the daemon.
Lifecycle:
- Node starts, reads
NodeConfigfrom environment - Registers with daemon via
DaemonRequest::Register - Subscribes to events via
DaemonRequest::Subscribe - Processes events in a loop (
NextEvent→ handle →SendMessage) - Reports drop tokens for shared memory cleanup
- Signals completion via
OutputsDone
Communication Protocols
CLI to Coordinator (WebSocket)
| Property | 值 |
|---|---|
| Transport | WebSocket over TCP |
| Default port | 6013 |
| Auth | Bearer token in Authorization header |
| Control messages | JSON text frames (request/response/event) |
| Topic data | Binary frames: [16-byte UUID][bincode payload] |
| Rate limit | 20 connections per IP per 60s |
| Max connections | 256 |
JSON-RPC-like message format:
// Request (client → server)
{"id": "uuid", "method": "control", "params": {...}}
// Response (server → client)
{"id": "uuid", "result": {...}}
// or
{"id": "uuid", "error": "message"}
// Event (fire-and-forget, either direction)
{"event": "log", "payload": {...}}
Key control methods: Build, Start, Stop, List, Logs, TopicSubscribe, TopicUnsubscribe, Reload, Restart, Destroy.
Coordinator to Daemon (WebSocket)
| Property | 值 |
|---|---|
| Transport | WebSocket (daemon connects to coordinator) |
| Route | /api/daemon |
| Retry | Exponential backoff 1s → 30s, max 50 attempts |
| Registration | DaemonRegisterRequest with version, machine_id, labels |
Daemon events (daemon → coordinator): BuildResult, SpawnResult, AllNodesReady, AllNodesFinished, Heartbeat, StatusReport, Log, NodeMetrics, Exit.
Coordinator commands (coordinator → daemon): Build, Spawn, AllNodesReady, StopDataflow, ReloadDataflow, Logs, Destroy, Heartbeat.
Daemon to Node (Local)
Three transport options, configured via LocalCommunicationConfig:
TCP (default):
- Binds
127.0.0.1:0(ephemeral port),TCP_NODELAYenabled - Frame format:
[8-byte u64 LE length][bincode payload] - Max message: 64 MiB, read timeout: 30s
Shared Memory (zero-copy):
- Four 4 KiB regions per node: control, events, drop tokens, events-close
- Used for messages >= 4096 bytes (
ZERO_COPY_THRESHOLD) - Atomic synchronization with acquire/release ordering
Unix Domain Socket (Unix only):
- Socket at
/tmp/{dataflow_id}/{node_id}.sock - Permissions:
0o700 - Same bincode frame format as TCP
Node → Daemon requests: Register, Subscribe, SendMessage, CloseOutputs, OutputsDone, NextEvent, ReportDropTokens, SubscribeDrop, NodeConfig.
Daemon → Node replies: Result, PreparedMessage, NextEvents, NextDropEvents, NodeConfig, Empty.
Node events: Stop, Reload, Input, InputClosed, InputRecovered, NodeRestarted, AllInputsClosed.
Daemon to Daemon (Zenoh)
| Property | 值 |
|---|---|
| Transport | Zenoh pub-sub |
| Router port | 7447 |
| Peer port | 5456 |
| Routing | linkstate |
| Serialization | bincode |
Topic pattern:
adora/{network_id}/{dataflow_id}/output/{node_id}/{output_id}
Default network_id is "default".
InterDaemonEvent:
Output { dataflow_id, node_id, output_id, metadata, data }— data messageOutputClosed { dataflow_id, node_id, output_id }— stream end
Message Types and Wire Formats
Timestamped Wrapper
All inter-component messages are wrapped in a timestamp:
#![allow(unused)]
fn main() {
pub struct Timestamped<T> {
pub inner: T,
pub timestamp: uhlc::Timestamp, // 混合逻辑时钟
}
}
DataMessage
Transport abstraction for payloads:
#![allow(unused)]
fn main() {
pub enum DataMessage {
Vec(AVec<u8, ConstAlign<128>>), // inline, 128-byte aligned
SharedMemory {
shared_memory_id: String,
len: usize,
drop_token: DropToken, // UUIDv7, tracks lifetime
},
}
}
LogMessage
#![allow(unused)]
fn main() {
pub struct LogMessage {
pub build_id: Option<BuildId>,
pub dataflow_id: Option<DataflowId>,
pub node_id: Option<NodeId>,
pub daemon_id: Option<DaemonId>,
pub level: LogLevelOrStdout, // Stdout | LogLevel(Error/Warn/Info/Debug/Trace)
pub target: Option<String>,
pub module_path: Option<String>,
pub file: Option<String>,
pub line: Option<u32>,
pub message: String,
pub timestamp: DateTime<Utc>,
pub fields: Option<BTreeMap<String, String>>,
}
}
NodeError
#![allow(unused)]
fn main() {
pub struct NodeError {
pub timestamp: uhlc::Timestamp,
pub cause: NodeErrorCause, // GraceDuration | Cascading | FailedToSpawn | Other
pub exit_status: NodeExitStatus, // Success | IoError | ExitCode | Signal | Unknown
}
}
Data Format and Metadata
Apache Arrow
All data payloads use Apache Arrow columnar format with 128-byte alignment. Arrow type information is carried in every message via ArrowTypeInfo:
#![allow(unused)]
fn main() {
pub struct ArrowTypeInfo {
pub data_type: DataType, // Arrow DataType
pub len: usize,
pub null_count: usize,
pub validity: Option<Vec<u8>>, // null bitmap
pub offset: usize,
pub buffer_offsets: Vec<BufferOffset>,
pub child_data: Vec<ArrowTypeInfo>, // recursive for nested types
}
}
元数据
Every message carries structured metadata:
#![allow(unused)]
fn main() {
pub struct Metadata {
metadata_version: u16,
timestamp: uhlc::Timestamp,
pub type_info: ArrowTypeInfo,
pub parameters: MetadataParameters, // BTreeMap<String, Parameter>
}
}
Parameter Types
#![allow(unused)]
fn main() {
pub enum Parameter {
Bool(bool),
Integer(i64),
String(String),
ListInt(Vec<i64>),
Float(f64),
ListFloat(Vec<f64>),
ListString(Vec<String>),
Timestamp(DateTime<Utc>),
}
}
Well-Known Metadata Keys
| Key | 用途 |
|---|---|
request_id | Service request/reply correlation |
goal_id | Action goal identifier |
goal_status | Action completion: succeeded, aborted, canceled |
session_id | Streaming session identifier |
segment_id | Streaming segment within a session |
seq | Streaming chunk sequence number |
fin | Last chunk of a streaming segment |
flush | Discard older queued messages on input |
零拷贝共享内存
架构
┌────────────────────────────────────────────────────┐
│ Shared Memory Region │
│ │
│ ┌──────────┐ ┌──────────┐ ┌──────┐ ┌────┐ ┌────┐│
│ │ Server │ │ Client │ │Discon│ │Len │ │Data││
│ │ Event │ │ Event │ │(bool)│ │(u64)│ │ ││
│ └──────────┘ └──────────┘ └──────┘ └────┘ └────┘│
│ (raw_sync_2) (raw_sync_2) AtomicBool AtomicU64 │
└────────────────────────────────────────────────────┘
ShmemChannel
#![allow(unused)]
fn main() {
pub struct ShmemChannel {
memory: Shmem,
server_event: Box<dyn EventImpl>,
client_event: Box<dyn EventImpl>,
disconnect_offset: usize,
len_offset: usize,
data_offset: usize,
server: bool,
}
}
Synchronization Protocol
Send (write → release store length → signal event → check disconnect):
- Copy data to shared memory buffer
- Store message length with
Releaseordering (publishes data) - Signal event to wake receiver
- Check disconnect flag with
Acquireordering
Receive (wait event → check disconnect → acquire load length → read data):
- Wait for event signal
- Check disconnect flag with
Acquireordering - Load message length with
Acquireordering (ensures all writes visible) - Read and deserialize data from buffer
Thresholds and Limits
| 参数 | 值 |
|---|---|
ZERO_COPY_THRESHOLD | 4096 bytes |
| Control region size | 4 KiB per node |
| Events region size | 4 KiB per node |
| Drop region size | 4 KiB per node |
| Max cache count | 20 regions |
| Max cache bytes | 256 MiB |
DropToken Lifecycle
- Sender allocates shared memory, generates
DropToken(UUIDv7) - Sender transmits
DataMessage::SharedMemory { shared_memory_id, len, drop_token } - Receiver processes data, returns
drop_tokenviaReportDropTokens - Sender receives confirmed token, returns memory to cache for reuse
Dataflow Specification
YAML Format
nodes:
# Standard node (executable)
- id: my-node
build: cargo build --release
path: target/release/my-node
inputs:
tick: adora/timer/millis/100
data: other-node/output
outputs:
- result
restart_policy: on-failure
max_restarts: 3
restart_delay: 1.0
env:
DEBUG: true
# Single operator (Python)
- id: processor
operator:
python: process.py
inputs:
image: camera/frame
outputs:
- detection
# Multi-operator runtime
- id: pipeline
operators:
- id: stage1
python: stage1.py
inputs:
data: source/output
outputs:
- intermediate
- id: stage2
shared-library: target/release/libstage2.so
inputs:
data: stage1/intermediate
outputs:
- final
# ROS2 bridge
- id: ros-input
ros2:
topic: /robot/state
message_type: sensor_msgs/JointState
direction: subscribe
qos:
reliable: true
outputs:
- joints
Descriptor Structs
#![allow(unused)]
fn main() {
pub struct Descriptor {
pub nodes: Vec<Node>,
pub communication: CommunicationConfig,
pub deploy: Option<Deploy>,
pub debug: Debug,
pub health_check_interval: Option<f64>, // default 5.0s
}
}
Node types (mutually exclusive fields):
path— standard executable/scriptoperator— single in-process operatoroperators— multiple in-process operatorscustom— legacy configurationros2— declarative ROS2 bridge
Timer Nodes
Built-in timer nodes generate periodic ticks:
adora/timer/millis/<N>— every N millisecondsadora/timer/secs/<N>— every N seconds
Operator Sources
#![allow(unused)]
fn main() {
pub enum OperatorSource {
SharedLibrary(String), // .so/.dll path
Python(PythonSource), // Python module
Wasm(String), // WebAssembly (planned)
}
}
Deploy Configuration
#![allow(unused)]
fn main() {
pub struct Deploy {
pub machine: Option<String>,
pub working_dir: Option<PathBuf>,
pub labels: BTreeMap<String, String>,
pub distribute: DistributeStrategy, // Local | Scp | Http
}
}
容错
重启策略
#![allow(unused)]
fn main() {
pub enum RestartPolicy {
Never, // default
OnFailure, // restart on non-zero exit
Always, // restart unless user-stopped or inputs closed
}
}
Configuration fields per node:
max_restarts— 0 = unlimitedrestart_delay— initial backoff in seconds (doubles each attempt)max_restart_delay— caps exponential backoffrestart_window— reset counter after N seconds (enables “N restarts per M seconds”)health_check_timeout— kill node if no activity within this duration
健康监测
- Heartbeat interval: 5 seconds (daemon → coordinator)
- Health check interval: 5 seconds (configurable per dataflow)
- Metrics collection: 2-second interval (CPU, memory, disk, pending messages)
Circuit Breaker
Per-input timeout detection with automatic recovery:
- Input configured with
input_timeout: <seconds> - If no data arrives within timeout →
InputClosedevent sent to node - Node marks input as degraded, can use cached last-known value
- When upstream recovers →
InputRecoveredevent, circuit breaker re-opens - Node status transitions:
Running→Degraded→Running
Cascading Error Tracking
#![allow(unused)]
fn main() {
pub struct CascadingErrorCauses {
pub caused_by: BTreeMap<NodeId, NodeId>,
}
}
Tracks which node failure caused downstream failures, enabling root-cause analysis.
Fault Tolerance Metrics
#![allow(unused)]
fn main() {
pub struct FaultToleranceSnapshot {
pub restarts: u64,
pub health_check_kills: u64,
pub input_timeouts: u64,
pub circuit_breaker_recoveries: u64,
}
}
Reported per daemon via heartbeat events. Visible via adora inspect top.
分布式部署
Multi-Daemon Architecture
┌──────────┐ Zenoh ┌──────────┐
│ Daemon A │◄──────────────────►│ Daemon B │
│ Machine 1│ pub/sub │ Machine 2│
│ │ │ │
│ Node 1 │ │ Node 3 │
│ Node 2 │ │ Node 4 │
└────┬─────┘ └────┬─────┘
│ WS │ WS
└──────────┐ ┌────────────────┘
▼ ▼
┌──────────┐
│Coordinator│
│ :6013 │
└──────────┘
Zenoh Topic Naming
adora/{network_id}/{dataflow_id}/output/{node_id}/{output_id}
network_idisolates separate Adora clusters (default:"default")- Zenoh router port: 7447, peer port: 5456
- Routing mode:
linkstate
Build Distribution
Three strategies via DistributeStrategy:
- Local — each daemon builds from source (default)
- Scp — CLI pushes built binaries via SSH/SCP
- Http — daemons pull from coordinator’s
/api/artifactsendpoint
Machine Labels
Nodes can target specific machines via labels:
_unstable_deploy:
labels:
gpu: "true"
arch: "arm64"
Recording and Replay
.adorec Binary Format
[HEADER]
├─ MAGIC: 8 bytes ("ADORAREC")
├─ version: u16 LE (currently 1)
├─ start_nanos: u64 LE (Unix epoch nanoseconds)
├─ dataflow_id: 16 bytes (UUID)
├─ yaml_len: u32 LE
└─ descriptor_yaml: [u8; yaml_len]
[ENTRIES] (repeated)
├─ record_len: u32 LE
├─ node_id_len: u16 LE
├─ node_id: [u8; node_id_len]
├─ output_id_len: u16 LE
├─ output_id: [u8; output_id_len]
├─ timestamp_offset_nanos: u64 LE
├─ event_bytes_len: u32 LE
└─ event_bytes: [u8; event_bytes_len] (bincode InterDaemonEvent)
[FOOTER] (optional, written on clean finish)
├─ FOOTER_MAGIC: 8 bytes ("ADORAEND")
├─ total_messages: u64 LE
└─ total_bytes: u64 LE
Writer/Reader API
#![allow(unused)]
fn main() {
pub struct RecordingWriter<W: Write> { /* ... */ }
impl<W: Write> RecordingWriter<W> {
pub fn new(inner: W, header: &RecordingHeader) -> Result<Self>;
pub fn write_entry(&mut self, entry: &RecordEntry) -> Result<()>;
pub fn finish(self) -> Result<RecordingFooter>;
}
pub struct RecordingReader<R: Read> { /* ... */ }
impl<R: Read> RecordingReader<R> {
pub fn open(inner: R) -> Result<Self>;
pub fn header(&self) -> &RecordingHeader;
pub fn next_entry(&mut self) -> Result<Option<RecordEntry>>;
}
}
Extensions
Telemetry
Distributed Tracing (adora-tracing):
- OpenTelemetry with OTLP exporter (compatible with Jaeger, Zipkin, Tempo)
- Context propagation across nodes
- Setup:
set_up_tracing(name: &str)
Metrics (adora-metrics):
- System metrics via
sysinfo(CPU, memory, disk) - OpenTelemetry meter with OTLP exporter
- Async process observer:
run_metrics_monitor(meter_id)
ROS2 桥接
Declarative YAML-based ROS2 integration supporting:
Topics — subscribe (ROS2 → Adora) or publish (Adora → ROS2):
ros2:
topic: /camera/image
message_type: sensor_msgs/Image
direction: subscribe
Services — client or server role:
ros2:
service: /add_two_ints
service_type: example_interfaces/AddTwoInts
role: 客户端
Actions — goal/feedback/result lifecycle:
ros2:
action: /fibonacci
action_type: example_interfaces/Fibonacci
role: 客户端
QoS configuration:
qos:
reliable: true
durability: transient_local
keep_last: 10
Download
File download utility for fetching operator/node binaries from HTTP URLs. Sanitizes filenames, sets executable permissions on Unix.
Key Constants and Defaults
| Constant | 值 | Location |
|---|---|---|
ADORA_COORDINATOR_PORT_WS_DEFAULT | 6013 | 协调器 WebSocket 端口 |
ADORA_DAEMON_LOCAL_LISTEN_PORT_DEFAULT | 53291 | Daemon TCP listener port |
ZERO_COPY_THRESHOLD | 4096 bytes | Shared memory activation |
MAX_MESSAGE_BYTES | 64 MiB | Max TCP/bincode message |
MAX_CONTROL_MESSAGE_BYTES | 1 MiB | Max control plane JSON message |
TCP_READ_TIMEOUT | 30 秒 | Socket read timeout |
WS_PING_INTERVAL | 10 seconds | WebSocket keepalive |
MAX_WS_CONNECTIONS | 256 | Concurrent WebSocket limit |
MAX_CONNECTIONS_PER_IP | 20 / 60s | Rate limiting |
MAX_TOPICS_PER_SUBSCRIBE | 64 | Topic batch limit |
MAX_SUBSCRIPTIONS_PER_CONNECTION | 16 | Per-connection limit |
MAX_BINARY_PAYLOAD_BYTES | 64 MiB | Topic data frame limit |
WATCHDOG_INTERVAL | 5 seconds | Heartbeat to coordinator |
METRICS_INTERVAL | 2 seconds | Metrics collection |
HEALTH_CHECK_INTERVAL | 5 seconds | Default node health check |
MAX_BUFFERED_LOG_MESSAGES | 10,000 | Log buffer capacity |
MAX_PENDING_REPLIES | 256 | Pending coordinator replies |
MAX_ERROR_BYTES | 4096 | Max error message size |
| Default input queue size | 10 | Per-input message buffer |
Identifiers and Data Structures
ID Types
| 类型 | Underlying | Validation |
|---|---|---|
DataflowId | uuid::Uuid | Assigned on dataflow start |
SessionId | uuid::Uuid (v7) | Per CLI session |
BuildId | uuid::Uuid (v7) | Per build operation |
DaemonId | { machine_id: Option<String>, uuid: Uuid (v7) } | Persisted in .daemon-id |
NodeId | String | Validated: [a-zA-Z0-9_.-], non-empty |
DataId | String | Same validation as NodeId |
OperatorId | String | No validation |
DropToken | Uuid (v7) | Per shared-memory message |
Authentication
#![allow(unused)]
fn main() {
pub struct AuthToken(String); // 64 hex chars (32 bytes)
}
- Generated via cryptographically random bytes
- Stored at
<working_dir>/.adora-token - Constant-time comparison to prevent timing attacks
- Applied to all WebSocket routes
Node Status
#![allow(unused)]
fn main() {
pub enum NodeStatus {
Running, // healthy
Restarting, // restart in progress
Degraded, // circuit breaker open (input timeout)
Failed, // terminal failure
}
}
Serialization Summary
| Channel | Format | Notes |
|---|---|---|
| CLI ↔ Coordinator | JSON text frames | Preserves u128 for HLC timestamps |
| Coordinator ↔ Daemon | JSON text frames | Direct string serialization |
| Daemon ↔ Node (TCP) | bincode over length-prefixed frames | 8-byte LE length prefix |
| Daemon ↔ Node (shmem) | bincode via shared memory | Atomic synchronization |
| Daemon ↔ Daemon | bincode over Zenoh | Apache Arrow data format |
| Recording | bincode entries in .adorec | Custom binary container |
Dataflow YAML Specification
Dataflows are defined in YAML files. Each file describes a graph of nodes, their inputs/outputs, and execution parameters.
A JSON Schema is available at the repo root (adora-schema.json) for editor autocompletion and validation.
快速开始
nodes:
- id: sender
path: sender.py
outputs:
- message
- id: receiver
path: receiver.py
inputs:
message: sender/message
Run with adora run dataflow.yml (local mode) or adora up && adora start dataflow.yml (networked mode).
Editor Setup
Add a schema comment at the top of your YAML file for VS Code autocompletion (requires the YAML extension):
# yaml-language-server: $schema=https://raw.githubusercontent.com/dora-rs/adora/main/adora-schema.json
nodes:
- id: my-node
# ... autocompletion works here
Root-Level Fields
| Field | 类型 | 默认 | 描述 |
|---|---|---|---|
nodes | list | required | List of node configurations |
strict_types | bool | false | Treat type warnings as errors in validate and build |
type_rules | list | [] | User-defined type compatibility rules (see Type Annotations) |
health_check_interval | float | 5.0 | Seconds between daemon health check sweeps. For each node with health_check_timeout set, the daemon checks whether the node has communicated within its timeout; if not, the node is killed and its restart_policy is evaluated |
_unstable_deploy | object | -- | Root-level deployment config (see Deployment) |
_unstable_debug | object | -- | Debug options (see Debug) |
Node Configuration
Every node requires an id. All other fields are optional (though most nodes need at least path or operator/operators).
Identity
| Field | 类型 | 描述 |
|---|---|---|
id | string | Required. Unique identifier. Must not contain /. Whitespace is discouraged |
name | string | Human-readable display name (metadata only, used in tooling and logs) |
description | string | Documentation string (metadata only, not used at runtime) |
Source
A node’s executable comes from a local path, a git repository, a module reference, or is implicit (operator/ROS2 nodes).
| Field | 类型 | 描述 |
|---|---|---|
path | string | Path to executable or script. Can also be a URL (legacy) |
module | string | Path to a module definition file (mutually exclusive with path). See Modules Guide |
git | string | Git repo URL. adora build clones it and uses the clone dir as working directory |
branch | string | Branch to checkout (requires git, mutually exclusive with tag/rev) |
tag | string | Tag to checkout (requires git, mutually exclusive with branch/rev) |
rev | string | Commit hash to checkout (requires git, mutually exclusive with branch/tag) |
build | string | Build commands run during adora build. Each line runs separately. pip/pip3 lines use uv when --uv is passed |
args | string | Command-line arguments (space-separated) |
Example with git source:
- id: rust-node
git: https://github.com/dora-rs/adora.git
branch: main
build: cargo build -p example-node --release
path: target/release/example-node
Data I/O
Inputs
Inputs subscribe to another node’s output using the format <node-id>/<output-id>:
inputs:
# Short form
image: camera/frames
tick: adora/timer/millis/100
# Long form with options
sensor_data:
source: sensor/frames
queue_size: 10
queue_policy: drop_oldest
input_timeout: 5.0
# Lossless input (blocks sender when full)
commands:
source: controller/cmd
queue_size: 100
queue_policy: backpressure
| Input option | 类型 | 默认 | 描述 |
|---|---|---|---|
source | string | required | <node-id>/<output-id> or timer path |
queue_size | integer | 10 | Input buffer size |
queue_policy | string | drop_oldest | drop_oldest: drops oldest message when full. backpressure: buffers up to 10x queue_size without dropping (drops with ERROR log at hard cap) |
input_timeout | float | -- | Circuit breaker timeout in seconds. If no message arrives within this period, the daemon closes the input and the node receives an InputClosed event for graceful degradation |
Built-in Timers
定时器是以固定间隔发出 tick 的虚拟节点:
inputs:
tick: adora/timer/millis/100 # 每 100ms
slow: adora/timer/millis/1000 # 每 1s
fast: adora/timer/hz/30 # 30 Hz(约 33ms)
Built-in Log Aggregation
Subscribe to structured log messages from all (or filtered) nodes:
inputs:
all_logs: adora/logs # all nodes, all levels
errors: adora/logs/error # error+ from all nodes
sensor: adora/logs/info/sensor # info+ from specific node
Each message arrives as a JSON-encoded LogMessage string. See Logging for details.
Outputs
A list of output identifiers the node produces:
outputs:
- processed_image
- metadata
运维
Optional type annotations for inputs and outputs. Types are never required – unannotated ports remain fully dynamic.
- id: camera
path: camera.py
outputs:
- image
- depth
output_types:
image: std/media/v1/Image
depth: std/media/v1/Image
- id: detector
path: detect.py
inputs:
image: camera/image
input_types:
image: std/media/v1/Image
outputs:
- bbox
output_types:
bbox: std/vision/v1/BoundingBox
| Field | 类型 | 默认 | 描述 |
|---|---|---|---|
output_types | object | {} | Maps output IDs to type URNs. Keys must match entries in outputs |
input_types | object | {} | Maps input IDs to expected type URNs. Keys must match entries in inputs |
output_metadata | object | {} | Maps output IDs to lists of required metadata keys |
pattern | string | -- | Communication pattern shorthand: service-server, service-client, action-server, action-client |
Type URNs use the format std/<category>/v<version>/<TypeName> and support parameters (e.g. std/media/v1/AudioFrame[sample_type=f32]). See the Type Annotations Guide for the full standard type library, parameterized types, compatibility rules, and user-defined types.
Run adora validate <file> to check type annotations statically. For runtime checking, set ADORA_RUNTIME_TYPE_CHECK=warn or error:
adora validate dataflow.yml
ADORA_RUNTIME_TYPE_CHECK=warn adora run dataflow.yml
Types also appear on adora graph edge labels when annotated.
Module Parameters
When using module:, pass configuration values via params::
- id: fast_pipeline
module: modules/transform.module.yml
inputs:
data: sender/value
params:
speed: "2.0"
mode: turbo
Inside the module, params are available as $PARAM_<UPPERCASE_KEY> in args: and as environment variables. See the Modules Guide for full documentation.
Environment
env:
MY_VAR: "value" # string
DEBUG: true # boolean
PORT: 8080 # integer
RATE: 1.5 # float
FROM_HOST:
__adora_env: HOST_VAR # read from host environment at runtime
Environment variables apply to both build commands and node execution. Values support $VAR expansion syntax.
日志
| Field | 类型 | 默认 | 描述 |
|---|---|---|---|
send_stdout_as | string | -- | Route raw stdout/stderr lines as a data output. Each line is sent as a separate Arrow message |
send_logs_as | string | -- | Route structured log entries as a data output. Each entry is a JSON string with fields: timestamp, level, node_id, message, target, fields |
min_log_level | string | -- | Suppress logs below this level from file output, coordinator forwarding, and send_logs_as. Levels from most to least verbose: stdout (all output including raw stdout), trace, debug, info, warn, error |
max_log_size | string | -- | Rotate log file at this size (e.g. "50MB", "1GB") |
max_rotated_files | integer | 5 | Number of rotated log files to keep |
Example:
- id: sensor
path: ./sensor
min_log_level: info
send_stdout_as: raw_output
send_logs_as: log_entries
max_log_size: "100MB"
max_rotated_files: 3
outputs:
- data
- raw_output
- log_entries
When using send_stdout_as or send_logs_as, include the output name in the outputs list so downstream nodes can subscribe to it.
For a complete guide to all logging features, see Logging.
容错
| Field | 类型 | 默认 | 描述 |
|---|---|---|---|
restart_policy | string | never | never, on-failure, or always |
max_restarts | integer | 0 | Max restart attempts. 0 = unlimited |
restart_delay | float | -- | Initial backoff in seconds. Doubles each attempt |
max_restart_delay | float | -- | Cap for exponential backoff |
restart_window | float | -- | Time window for counting restarts. The counter resets after this many seconds since the first restart in the current window. Enables “N restarts per M seconds” semantics with max_restarts |
health_check_timeout | float | -- | If the node does not communicate with the daemon (send outputs, subscribe, etc.) for this many seconds, the daemon kills the process and evaluates the restart_policy |
Restart policies:
never(default): no automatic restarton-failure: restart only on non-zero exit codealways: restart on any exit, except when stopped by user or all inputs closed with success
Example with exponential backoff:
- id: sensor
path: ./sensor
restart_policy: on-failure
max_restarts: 5
restart_delay: 1.0 # 1s, 2s, 4s, 8s, 16s
max_restart_delay: 30.0 # capped at 30s
restart_window: 300.0 # 5 restarts per 5 minutes
health_check_timeout: 30.0
Deployment
使用 _unstable_deploy 将节点分配到特定机器:
- id: camera-driver
_unstable_deploy:
machine: robot-arm
path: ./target/debug/camera
outputs:
- frames
- id: ml-inference
_unstable_deploy:
machine: gpu-server
labels:
gpu: "true"
distribute: scp
path: ./target/debug/inference
inputs:
frames: camera-driver/frames
| Deploy field | 类型 | 默认 | 描述 |
|---|---|---|---|
machine | string | -- | Target machine/daemon ID. The coordinator routes the node to the daemon registered with this ID |
working_dir | string | -- | Working directory on the target machine |
labels | object | -- | Key-value labels for scheduling. The coordinator matches these against labels reported by each daemon at registration |
distribute | string | local | How built binaries reach the target daemon: local – each daemon builds from source independently; scp – CLI pushes the built binary via SSH/SCP before spawn; http – daemon pulls the binary from the coordinator’s HTTP artifact store |
当节点位于不同机器时,通信自动从共享内存切换到 Zenoh 发布/订阅。
算子节点
Operators run in-process inside a shared runtime (no separate process). Use operator for a single operator or operators for multiple.
Single Operator
The id field is optional for single operators (defaults to the node id):
- id: detector
operator:
python: detect.py
build: pip install -r requirements.txt
inputs:
image: camera/frames
outputs:
- bbox
Multiple Operators
Each operator in operators requires a unique id:
- id: runtime-node
operators:
- id: preprocessor
shared-library: ../../target/debug/libpreprocess
inputs:
raw: sensor/data
outputs:
- processed
- id: analyzer
shared-library: ../../target/debug/libanalyze
inputs:
data: runtime-node/preprocessor/processed
outputs:
- result
Operator Source Types
| Field | 描述 |
|---|---|
python | Python script path, or {source: "script.py", conda_env: "myenv"} |
shared-library | Path to a shared library (.so/.dylib/.dll) |
Operators also support inputs, outputs, build, send_stdout_as, send_logs_as, min_log_level, max_log_size, and max_rotated_files with the same semantics as node-level fields.
ROS2 桥接
Declare a node as a ROS2 bridge to automatically convert between ROS2 DDS messages and Adora’s Arrow format. No custom code needed.
Single Topic
- id: camera_bridge
ros2:
topic: /camera/image_raw
message_type: sensor_msgs/Image
direction: subscribe
outputs:
- image
Multiple Topics
- id: robot_bridge
ros2:
topics:
- topic: /camera/image_raw
message_type: sensor_msgs/Image
direction: subscribe
output: image
- topic: /cmd_vel
message_type: geometry_msgs/Twist
direction: publish
input: velocity
qos:
reliable: true
inputs:
velocity: planner/cmd_vel
outputs:
- image
服务桥接
- id: add_service
ros2:
service: /add_two_ints
service_type: example_interfaces/AddTwoInts
role: 服务端
inputs:
request: client_node/request
outputs:
- response
动作桥接
- id: nav_action
ros2:
action: /navigate
action_type: nav2_msgs/NavigateToPose
role: 客户端
inputs:
goal: planner/goal
outputs:
- feedback
- result
QoS Configuration
QoS can be set at the bridge level (applies to all topics) or per-topic:
| QoS field | 类型 | 默认 | 描述 |
|---|---|---|---|
reliable | bool | false | Reliable vs best-effort transport |
durability | string | volatile | volatile or transient_local |
liveliness | string | automatic | automatic, manual_by_participant, manual_by_topic |
lease_duration | float | infinity | Lease duration in seconds |
max_blocking_time | float | -- | Max blocking time for reliable transport |
keep_last | integer | 1 | History depth (KeepLast policy) |
keep_all | bool | false | Use KeepAll history instead of KeepLast |
Other ROS2 Fields
| Field | 类型 | 默认 | 描述 |
|---|---|---|---|
namespace | string | / | ROS2 namespace |
node_name | string | node id | ROS2 node name |
Debug
_unstable_debug:
publish_all_messages_to_zenoh: true
Required for adora topic echo, adora topic hz, and adora topic info commands.
通信模式
Adora supports four communication patterns built on top of the dataflow:
- Topic (default): pub/sub dataflow
- Service: request/reply via
request_idmetadata - Action: goal/feedback/result via
goal_id/goal_statusmetadata, with cancellation support - Streaming: session/segment/chunk via
session_id/segment_id/seq/fin/flushmetadata, with queue flush for interruption
See Communication Patterns for details and examples.
Full Example
health_check_interval: 10.0
_unstable_debug:
publish_all_messages_to_zenoh: true
nodes:
- id: webcam
operator:
python: webcam.py
inputs:
tick: adora/timer/millis/100
outputs:
- image
- id: detector
operator:
python: detect.py
build: pip install ultralytics
inputs:
image: webcam/image
outputs:
- bbox
- id: plotter
operator:
python: plot.py
inputs:
image: webcam/image
bbox: detector/bbox
- id: logger
path: ./logger
inputs:
bbox: detector/bbox
send_stdout_as: logs
min_log_level: info
restart_policy: on-failure
max_restarts: 3
outputs:
- logs
运维
Optional type annotations on dataflow inputs and outputs. Types are never required – unannotated ports remain fully dynamic. Type checking runs at build time and validate time (no runtime overhead by default).
快速开始
nodes:
- id: camera
path: camera.py
outputs:
- image
output_types:
image: std/media/v1/Image
- id: detector
path: detect.py
inputs:
image: camera/image
input_types:
image: std/media/v1/Image
outputs:
- bbox
output_types:
bbox: std/vision/v1/BoundingBox
Validate with:
adora validate dataflow.yml
# Fail with non-zero exit code on warnings (for CI)
adora validate --strict-types dataflow.yml
# Type checks also run during build
adora build dataflow.yml --strict-types
You can also set strict_types: true at the top level of the YAML to enable strict mode without the CLI flag:
strict_types: true
nodes:
# ...
Type URN Format
Type URNs follow the pattern std/<category>/v<version>/<TypeName>:
std/core/v1/Float32
std/media/v1/Image
std/vision/v1/BoundingBox
Parameterized Types
Some struct types accept parameters to distinguish variants:
std/media/v1/AudioFrame[sample_type=f32]
std/media/v1/AudioFrame[sample_type=f32,channels=2]
Matching rules:
- Same base + same params -> compatible
- Same base + one side unparameterized -> compatible (wildcard)
- Same base + different param values -> mismatch
# These are compatible (wildcard):
output_types:
audio: std/media/v1/AudioFrame[sample_type=f32]
input_types:
audio: std/media/v1/AudioFrame
# These are a mismatch:
output_types:
audio: std/media/v1/AudioFrame[sample_type=f32]
input_types:
audio: std/media/v1/AudioFrame[sample_type=i16]
Standard Type Library
std/core/v1
| 类型 | Arrow 类型 | 描述 |
|---|---|---|
Float32 | Float32 | 32-bit float |
Float64 | Float64 | 64-bit float |
Int32 | Int32 | 32-bit signed integer |
Int64 | Int64 | 64-bit signed integer |
UInt8 | UInt8 | 8-bit unsigned integer |
UInt32 | UInt32 | 32-bit unsigned integer |
UInt64 | UInt64 | 64-bit unsigned integer |
String | Utf8 | UTF-8 string |
Bytes | LargeBinary | Raw bytes (universal sink – any type is compatible) |
Bool | Boolean | Boolean |
std/math/v1
| 类型 | Arrow 类型 | 字段 | 描述 |
|---|---|---|---|
Vector3 | Struct | x, y, z (Float64) | 3D vector |
Quaternion | Struct | x, y, z, w (Float64) | Quaternion |
Pose | Struct | position, orientation | 6-DOF pose |
Transform | Struct | translation, rotation | Coordinate transform |
std/control/v1
| 类型 | Arrow 类型 | 描述 |
|---|---|---|
Twist | Struct | Linear and angular velocity |
JointState | Struct | Joint positions, velocities, efforts |
Odometry | Struct | Pose + Twist in a reference frame |
std/media/v1
| 类型 | Arrow 类型 | Parameters | 描述 |
|---|---|---|---|
Image | Struct | encoding | Raw image (width, height, encoding, data) |
CompressedImage | LargeBinary | format | JPEG/PNG compressed image |
PointCloud | Struct | point_type | 3D point cloud |
AudioFrame | Struct | sample_type (default: f32) | Audio samples |
std/vision/v1
| 类型 | Arrow 类型 | 描述 |
|---|---|---|
BoundingBox | Struct | 2D bounding box with confidence and label |
Detection | Struct | Object detection result (list of BoundingBox) |
Segmentation | Struct | Pixel-level segmentation mask |
验证规则
adora validate and adora build check:
- Key existence:
output_typeskeys must appear inoutputs,input_typeskeys must appear ininputs - URN resolution: All type URNs must exist in the standard or user-defined type library. Typos get “did you mean?” suggestions.
- Edge compatibility: Connected edges must have compatible types (exact match, implicit widening, or user-defined rules)
- Timer auto-typing: Timer inputs (
adora/timer/*) are automatically typed asstd/core/v1/UInt64 - Type inference: When only the upstream side annotates a type, it is inferred on the downstream input and reported
- Parameterized types: Parameter mismatches are detected (see above)
- Metadata patterns:
output_metadatakeys andpatternshorthands are validated (see below) - Schema compatibility: Struct types are checked at the field level – missing fields or wrong field types are flagged
All checks produce warnings (non-fatal by default). Use --strict-types to treat warnings as errors for CI pipelines.
Type warnings:
- node "camera": output_types key "framez" not found in outputs list
- node "detector": unknown type "std/vision/v1/BoundingBx" on output "bbox"
(did you mean "std/vision/v1/BoundingBox"?)
- node "detector": type mismatch on input "image": upstream camera/image
declares "std/core/v1/Bytes", but expected "std/media/v1/Image"
Inferred types:
inferred std/core/v1/Float64 on processor/reading (from sensor/reading)
Type Compatibility Rules
Beyond exact matching, the type checker supports implicit widening conversions:
| From | To |
|---|---|
UInt8 | UInt32 |
UInt32 | UInt64 |
Int32 | Int64 |
Float32 | Float64 |
| Any type | Bytes (universal sink) |
Widening is transitive up to depth 3 (e.g. UInt8 -> UInt32 -> UInt64 works, but chains of 4+ do not).
User-Defined Compatibility Rules
Add custom rules in the dataflow YAML:
type_rules:
- from: myproject/SensorV1
to: myproject/SensorV2
nodes:
# ...
Metadata Patterns
Nodes that implement communication patterns (services, actions) can declare required metadata keys on their outputs.
Explicit metadata
- id: 服务端
path: server.py
outputs:
- response
output_metadata:
response: [request_id]
Pattern shorthand
Use the pattern field to auto-imply required metadata keys:
- id: 服务端
path: server.py
pattern: service-server
outputs:
- response
| 模式 | Required metadata keys |
|---|---|
service-server | request_id |
service-client | request_id |
action-server | goal_id, goal_status |
action-client | goal_id |
User-Defined Types
Projects can define custom types in a types/ directory next to the dataflow. The directory structure determines the URN prefix:
project/
dataflow.yml
types/
myproject/
sensors/
v1.yml # URN prefix: myproject/sensors/v1
Type YAML files use the same format as the standard library:
types:
MySensor:
arrow: Struct
description: Custom sensor reading
fields:
- name: temperature
type: Float32
- name: humidity
type: Float32
This creates the URN myproject/sensors/v1/MySensor.
The std/ prefix is reserved and cannot be used for user types.
User types are loaded automatically by adora validate and adora build when a types/ directory exists.
Runtime Type Checking
In addition to static validation, Adora supports optional runtime type checking on send_output(). When enabled, the actual Arrow data type is compared against the declared output_types at send time.
Enable via environment variable:
# Warn on mismatches (log and continue)
ADORA_RUNTIME_TYPE_CHECK=warn adora run dataflow.yml
# Error on mismatches (node returns error)
ADORA_RUNTIME_TYPE_CHECK=error adora run dataflow.yml
Valid values: 1, warn, true (warn mode), error (error mode). Unset or any other value disables checking (zero overhead).
Scope:
- Validates
output_typeson the sender side (send_output()calls).input_typesare checked statically byadora validatebut not enforced at runtime - Covers all languages that send Arrow arrays (Rust, Python, C++ Arrow path)
- Raw byte sends (
send_output_bytes, C nodes) are untyped and skip checking - Complex types (Struct-based: Image, Vector3, etc.) are skipped – only primitive types, String, Bytes, and Bool are validated at runtime
Graph Visualization
When outputs have type annotations, adora graph shows the type on edge labels:
adora graph dataflow.yml --open
Edges display as output_name [TypeName] (e.g. image [Image]).
Operators
Operators support the same output_types, input_types, output_metadata, and pattern fields:
- id: runtime-node
operators:
- id: preprocessor
python: preprocess.py
inputs:
raw: sensor/data
input_types:
raw: std/core/v1/Bytes
outputs:
- processed
output_types:
processed: std/media/v1/Image
Modules (Reusable Sub-Dataflows)
Modules let you define reusable sub-graphs of nodes in separate YAML files and compose them into larger dataflows. Modules are expanded at compile time – the runtime never sees them.
快速开始
Module file (modules/transform_module.yml):
module:
name: transform_pipeline
inputs: [raw_data]
outputs: [filtered]
nodes:
- id: doubler
path: doubler.py
inputs:
data: _mod/raw_data
outputs:
- doubled
- id: filter
path: filter_even.py
inputs:
data: doubler/doubled
outputs:
- filtered
Dataflow file (dataflow.yml):
nodes:
- id: sender
path: sender.py
outputs:
- value
- id: pipeline
module: modules/transform_module.yml
inputs:
raw_data: sender/value
- id: receiver
path: receiver.py
inputs:
filtered: pipeline/filtered
After expansion, pipeline becomes two nodes: pipeline.doubler and pipeline.filter, with all wiring resolved automatically.
Module Definition File
A module file has two sections:
module: header
| Field | 类型 | Required | 描述 |
|---|---|---|---|
name | string | yes | Module name (metadata only) |
inputs | list | no | Required input port names |
inputs_optional | list | no | Optional input ports (silently skipped if not wired) |
outputs | list | no | Output port names exposed to the parent dataflow |
nodes: list
Standard node definitions, with one special syntax: _mod/port_name references a module input port. When expanded, _mod/port_name is replaced with whatever the parent wired to that port.
module:
name: my_module
inputs: [camera_feed]
outputs: [detections]
nodes:
- id: detector
path: detect.py
inputs:
image: _mod/camera_feed # resolved to parent's wiring
outputs:
- detections
Module-level build
Modules can have a top-level build: command that runs before any inner node builds:
module:
name: ml_pipeline
inputs: [image]
outputs: [result]
build: pip install -r requirements.txt
nodes:
- id: model
path: model.py
inputs:
image: _mod/image
outputs:
- result
Using Modules
Reference a module in a dataflow node using the module: field instead of path::
- id: nav_stack
module: modules/navigation.module.yml
inputs:
goal_pose: localization/goal
The module node’s inputs: map wires parent outputs to module input ports. External nodes reference module outputs as <module_id>/<output_name> (e.g., nav_stack/cmd_vel).
Parameters
Pass configuration values to modules via params::
- id: fast_pipeline
module: modules/transform_module.yml
inputs:
raw_data: sender/value
params:
speed: "2.0"
mode: turbo
Inside the module, reference params in args: using $PARAM_<UPPERCASE_KEY>:
nodes:
- id: processor
path: processor.py
args: --speed $PARAM_SPEED --mode $PARAM_MODE
inputs:
data: _mod/raw_data
outputs:
- result
Parameters are also injected as environment variables (PARAM_SPEED, PARAM_MODE) into every node inside the module.
Expansion Rules
- Load the module YAML file and validate its header
- Prefix all internal node IDs with
{module_id}.(e.g.,nav_stack.planner) - Replace
_mod/port_namereferences with the actual sources from the parent’s input map - Rewrite internal cross-references (e.g.,
planner/pathbecomesnav_stack.planner/path) - Map module-declared outputs to internal node outputs, so
nav_stack/cmd_velresolves tonav_stack.controller/cmd_vel - Replace the module node with the expanded flat nodes
- Substitute
params:values inargs:fields and inject as env vars
Use adora expand to see the result:
adora expand dataflow.yml
Nested Modules
Modules can reference other modules. The expansion is recursive with a depth limit of 8 levels:
# outer_module.yml
module:
name: outer
inputs: [data]
outputs: [result]
nodes:
- id: inner
module: inner_module.yml
inputs:
raw: _mod/data
- id: postprocess
path: postprocess.py
inputs:
data: inner/processed
outputs:
- result
After expansion, node IDs are fully qualified: outer.inner.some_node.
Optional Inputs
Declare inputs as optional when a module should work with or without certain connections:
module:
name: flexible_processor
inputs: [data]
inputs_optional: [config]
outputs: [result]
nodes:
- id: processor
path: processor.py
inputs:
data: _mod/data
config: _mod/config # silently dropped if not wired
outputs:
- result
When the parent doesn’t wire config, the input is simply omitted from the expanded node.
Visualization
adora graph renders module boundaries as Mermaid subgraphs, making it easy to see which nodes came from which module:
adora graph dataflow.yml --open
Validation
Validate a standalone module file without a full dataflow:
adora expand --module modules/transform_module.yml
This checks:
- Valid YAML structure
- Module header is present with
name,inputs,outputs - All
_mod/references correspond to declared inputs or optional inputs - No duplicate node IDs
- Internal wiring is consistent
安全
- Path confinement: Module file paths must resolve within the dataflow’s base directory. Absolute paths and directory traversal (
../) outside the base are rejected. - File size limit: Module files are capped at 1 MB.
- Depth limit: Recursive nesting is capped at 8 levels.
- Param key validation: Parameter keys must be alphanumeric with underscores only.
示例
See examples/module-dataflow/ for a complete working example with a sender, transform module (doubler + filter), and receiver.
adora run examples/module-dataflow/dataflow.yml
通信模式
Adora is a dataflow framework based on pub/sub message passing. On top of basic topics, the framework supports service (request/reply), action (goal/feedback/result), and streaming (session/segment/chunk) patterns using well-known metadata keys. No changes to the daemon, coordinator, or YAML syntax are required – the patterns are implemented as conventions at the node API level.
1. 主题(发布/订阅)
默认模式。一个节点在输出上发布数据,订阅该输出的任何节点都会接收到它。
nodes:
- id: 发布者
outputs:
- data
- id: 订阅者
inputs:
data: publisher/data
适用场景:流式传感器数据、周期性状态、即发即忘事件。
2. 服务(请求/应答)
客户端发送请求并期望收到恰好一个响应,通过 request_id 元数据键进行关联。
约定的元数据键
| Key | Constant | 描述 |
|---|---|---|
request_id | adora_node_api::REQUEST_ID | 用于关联请求和响应的 UUID v7 |
YAML
nodes:
- id: 客户端
inputs:
tick: adora/timer/millis/500
response: server/response
outputs:
- request
- id: 服务端
inputs:
request: client/request
outputs:
- response
节点 API 辅助函数
#![allow(unused)]
fn main() {
// Client: send request with auto-generated request_id
let rid = node.send_service_request("request".into(), params, data)?;
// Server: pass through metadata.parameters (includes request_id)
node.send_service_response("response".into(), metadata.parameters, result)?;
}
服务端必须将传入请求的元数据参数中的 request_id 透传到响应中。客户端使用该键将响应与请求进行匹配。
示例:examples/service-example/
3. 动作(目标/反馈/结果)
客户端发送一个目标并接收周期性的反馈以及最终结果。Action 支持取消操作。
约定的元数据键
| Key | Constant | 描述 |
|---|---|---|
goal_id | adora_node_api::GOAL_ID | 用于标识目标的 UUID v7 |
goal_status | adora_node_api::GOAL_STATUS | 目标的最终状态 |
目标状态值:
| 值 | Constant | Meaning |
|---|---|---|
succeeded | GOAL_STATUS_SUCCEEDED | 目标成功完成 |
aborted | GOAL_STATUS_ABORTED | 目标被服务端中止 |
canceled | GOAL_STATUS_CANCELED | 目标被客户端取消 |
YAML
nodes:
- id: 客户端
inputs:
tick: adora/timer/millis/2000
feedback: server/feedback
result: server/result
outputs:
- goal
- cancel
- id: 服务端
inputs:
goal: client/goal
cancel: client/cancel
outputs:
- feedback
- result
取消模式
客户端在 cancel 输出上发送带有 goal_id 元数据的消息。服务端在处理步骤之间检查取消请求,并发送 goal_status = "canceled" 的结果。
示例:examples/action-example/
4. Streaming (session/segment/chunk)
For real-time pipelines (voice, video, sensor streams) where a user can interrupt mid-stream and queued data must be discarded.
约定的元数据键
| Key | 类型 | Constant | 描述 |
|---|---|---|---|
session_id | String | SESSION_ID | Identifies the conversation/session |
segment_id | Integer | SEGMENT_ID | Logical unit within a session (e.g. one utterance) |
seq | Integer | SEQ | Chunk sequence number within a segment |
fin | Bool | FIN | true on the last chunk of a segment |
flush | Bool | FLUSH | true to discard older queued messages on this input |
YAML
nodes:
- id: asr
inputs:
mic: mic-source/audio
outputs:
- text
- id: llm
inputs:
text: asr/text
outputs:
- tokens
- id: tts
inputs:
tokens: llm/tokens
outputs:
- audio
节点 API
#![allow(unused)]
fn main() {
use adora_node_api::{StreamSegment, AdoraNode};
let mut seg = StreamSegment::new();
// Send chunks with auto-incrementing seq (e.g. inside an ASR node)
node.send_stream_chunk("text".into(), &mut seg, false, chunk_data)?;
// Mark final chunk of a segment
node.send_stream_chunk("text".into(), &mut seg, true, last_chunk)?;
// On user interruption: flush downstream queues and start a new segment.
// The prior segment ends without a fin=true signal -- old data is discarded.
let flush_params = seg.flush();
node.send_output("text".into(), flush_params, empty_data)?;
}
Queue flush behavior
When a message arrives with flush: true in its metadata, the receiver’s input queue is cleared of all older messages before the flush message is delivered. This enables instant interruption in voice pipelines – when the user speaks over TTS output, the ASR node sends a new segment with flush: true, and the TTS node immediately discards any queued audio chunks from the previous response.
Note: flush discards all queued messages on the input regardless of session_id. Do not multiplex independent sessions on a single input when using flush.
Python
# Streaming metadata is a plain dict
params = {
"session_id": session_id,
"segment_id": 1,
"seq": 0,
"fin": False,
"flush": True, # flush older queued messages
}
node.send_output("text", data, metadata={"parameters": params})
5. Choosing a pattern
| 需要响应? | Long-running? | Cancelable? | Real-time stream? | 模式 |
|---|---|---|---|---|
| 否 | - | - | 否 | Topic |
| 是 | 否 | 否 | 否 | Service |
| 是 | 是 | Optional | 否 | Action |
| 否 | 是 | Via flush | 是 | Streaming |
6. Important details
goal_status匹配区分大小写。 请始终使用精确的小写值:"succeeded"、"aborted"、"canceled"。ROS2 桥接对无法识别的值默认使用Aborted。
7. Python compatibility
Python 节点使用相同的元数据约定。参数是键为字符串的普通字典:
import uuid
# Service client (uuid7 for time-ordered IDs, matching Rust API)
params = {"request_id": str(uuid.uuid7())}
node.send_output("request", data, metadata={"parameters": params})
# Service server -- pass through parameters
node.send_output("response", result, metadata=event["metadata"])
注意:
uuid.uuid7()需要 Python 3.13+。在旧版本中,请使用uuid_utils包或uuid.uuid4()(随机 v4 也可用于关联,但会丢失时间排序特性)。
Rust API 参考
本文档介绍用于构建 Adora 数据流组件的两个主要 Rust crate:
adora-node-api– 用于独立节点可执行文件adora-operator-api– 用于由 Adora 运行时管理的进程内算子
节点 API (adora-node-api)
添加到你的 Cargo.toml:
[dependencies]
adora-node-api = { workspace = true }
AdoraNode
用于发送输出和获取节点信息的主要结构体。通过以下初始化函数之一获取。
初始化
#![allow(unused)]
fn main() {
// 推荐:自动检测环境(守护进程、测试或交互模式)。
pub fn init_from_env() -> NodeResult<(Self, EventStream)>
// 与 init_from_env 相同,但出错时不回退到交互模式。
pub fn init_from_env_force() -> NodeResult<(Self, EventStream)>
// 用于动态节点:通过节点 ID 连接到守护进程。
pub fn init_from_node_id(node_id: NodeId) -> NodeResult<(Self, EventStream)>
// 先尝试 init_from_env;回退到 init_from_node_id。
pub fn init_flexible(node_id: NodeId) -> NodeResult<(Self, EventStream)>
// 独立交互模式(在终端提示输入)。
pub fn init_interactive() -> NodeResult<(Self, EventStream)>
// 使用合成输入/输出的集成测试模式。
pub fn init_testing(
input: TestingInput,
output: TestingOutput,
options: TestingOptions,
) -> NodeResult<(Self, EventStream)>
}
init_from_env 是推荐的入口点。它按顺序检查:
- 由
setup_integration_testing设置的线程局部测试状态 ADORA_NODE_CONFIG环境变量(由守护进程设置)ADORA_TEST_WITH_INPUTS环境变量(基于文件的集成测试)- 交互终端回退(仅当 stdin 为 TTY 时)
发送输出
所有发送方法会静默忽略未在数据流 YAML 中声明的输出 ID。
#![allow(unused)]
fn main() {
// 发送 Arrow 数组。在有利时将数据复制到共享内存。
pub fn send_output(
&mut self,
output_id: DataId,
parameters: MetadataParameters,
data: impl Array,
) -> NodeResult<()>
// 发送原始字节。在有利时复制到共享内存。
pub fn send_output_bytes(
&mut self,
output_id: DataId,
parameters: MetadataParameters,
data_len: usize,
data: &[u8],
) -> NodeResult<()>
// 通过闭包发送原始字节以实现零拷贝写入。
pub fn send_output_raw<F>(
&mut self,
output_id: DataId,
parameters: MetadataParameters,
data_len: usize,
data: F,
) -> NodeResult<()>
where
F: FnOnce(&mut [u8])
// 发送带有显式 Arrow 类型信息的原始字节。
pub fn send_typed_output<F>(
&mut self,
output_id: DataId,
type_info: ArrowTypeInfo,
parameters: MetadataParameters,
data_len: usize,
data: F,
) -> NodeResult<()>
where
F: FnOnce(&mut [u8])
// 发送带有类型信息的预分配 DataSample。
pub fn send_output_sample(
&mut self,
output_id: DataId,
type_info: ArrowTypeInfo,
parameters: MetadataParameters,
sample: Option<DataSample>,
) -> NodeResult<()>
// 将输出 ID 报告为已关闭。不再允许对这些 ID 发送。
pub fn close_outputs(&mut self, outputs_ids: Vec<DataId>) -> NodeResult<()>
}
Service, Action, and Streaming Helpers
Higher-level methods for the communication patterns. These use well-known metadata keys to correlate requests, goals, responses, and streaming segments.
#![allow(unused)]
fn main() {
// 生成唯一的、时间有序的 ID(UUID v7)用于关联。
pub fn new_request_id() -> String
pub fn new_goal_id() -> String // new_request_id 的别名
// 发送服务请求。将 `request_id` 注入参数并返回。
pub fn send_service_request(
&mut self,
output_id: DataId,
parameters: MetadataParameters,
data: impl Array,
) -> NodeResult<String>
// 发送服务响应。send_output 的语义别名。
// 调用者必须传递来自传入请求元数据的 request_id。
pub fn send_service_response(
&mut self,
output_id: DataId,
parameters: MetadataParameters,
data: impl Array,
) -> NodeResult<()>
}
服务示例(客户端发送请求,服务端回复):
#![allow(unused)]
fn main() {
// 客户端:自动生成并注入 request_id
let rid = node.send_service_request("request".into(), params, data)?;
// Server: pass through metadata.parameters (includes request_id)
node.send_service_response("response".into(), metadata.parameters, result)?;
}
动作示例(客户端发送目标,服务端流式传输反馈 + 结果):
#![allow(unused)]
fn main() {
use adora_node_api::{GOAL_ID, GOAL_STATUS, GOAL_STATUS_SUCCEEDED, Parameter};
// 客户端:生成 goal_id,附加到参数
let goal_id = AdoraNode::new_goal_id();
params.insert(GOAL_ID.to_string(), Parameter::String(goal_id));
node.send_output("goal".into(), params, data)?;
// 服务端:提取 goal_id,发送带 goal_status 的反馈/结果
let gid = get_string_param(&metadata.parameters, GOAL_ID);
}
Streaming example (real-time voice/video pipeline with interruption):
#![allow(unused)]
fn main() {
use adora_node_api::StreamSegment;
// Create a streaming segment builder (auto-generates session_id)
let mut seg = StreamSegment::new();
// Send chunks with auto-incrementing seq
node.send_stream_chunk("text".into(), &mut seg, false, chunk_data)?;
// Mark final chunk of a segment
node.send_stream_chunk("text".into(), &mut seg, true, last_chunk)?;
// On user interruption: flush downstream queues and start a new segment
let flush_params = seg.flush();
node.send_output("text".into(), flush_params, empty_data)?;
}
See patterns.md for the full guide and examples/service-example and examples/action-example for working code.
数据分配
#![allow(unused)]
fn main() {
// 分配给定大小的 DataSample。
// 对 >= ZERO_COPY_THRESHOLD (4096 字节) 的数据使用共享内存。
pub fn allocate_data_sample(&mut self, data_len: usize) -> NodeResult<DataSample>
}
节点信息
#![allow(unused)]
fn main() {
// 数据流 YAML 中的节点 ID。
pub fn id(&self) -> &NodeId
// 本次数据流运行的唯一标识符。
pub fn dataflow_id(&self) -> &DataflowId
// 此节点的输入/输出配置。
pub fn node_config(&self) -> &NodeRunConfig
// 如果此节点在之前退出或故障后被重启则为 true。
pub fn is_restart(&self) -> bool
// 此节点被重启的次数(首次运行为 0)。
pub fn restart_count(&self) -> u32
// 解析后的数据流 YAML 描述符。
pub fn dataflow_descriptor(&self) -> NodeResult<&Descriptor>
}
日志
Rust nodes have two ways to emit structured logs. Both produce identical structured log entries in the daemon.
Option 1: Node API (recommended for most cases)
All log methods emit structured JSONL to stdout, which the daemon parses automatically. Works with min_log_level filtering, send_logs_as routing, and adora/logs subscribers.
#![allow(unused)]
fn main() {
// 通用结构化日志。级别:"error"、"warn"、"info"、"debug"、"trace"。
pub fn log(&self, level: &str, message: &str, target: Option<&str>)
// 带有附加键值字段的结构化日志。
pub fn log_with_fields(
&self,
level: &str,
message: &str,
target: Option<&str>,
fields: Option<&BTreeMap<String, String>>,
)
// 便捷方法(无 target 参数)。
pub fn log_error(&self, message: &str)
pub fn log_warn(&self, message: &str)
pub fn log_info(&self, message: &str)
pub fn log_debug(&self, message: &str)
pub fn log_trace(&self, message: &str)
}
Option 2: Rust tracing crate
When adora’s tracing subscriber is initialized (via init_tracing() or the default feature), tracing::info!() etc. output structured JSON to stdout that the daemon parses identically:
#![allow(unused)]
fn main() {
tracing::info!("Sensor started");
tracing::warn!(sensor_id = "temp-01", "High temperature");
}
Use tracing when you want ecosystem integration (spans, instrumentation, OpenTelemetry). Use node.log_*() when you want explicit control or structured fields as BTreeMap.
| 方法 | Structured? | Fields? | OpenTelemetry? | 最适用于 |
|---|---|---|---|---|
node.log_info(msg) | 是 | 否 | 否 | Quick one-liner |
node.log_with_fields(...) | 是 | Yes (BTreeMap) | 否 | Structured key-value context |
tracing::info!(key = val, msg) | 是 | Yes (spans) | 是 | Ecosystem integration, OTel |
println!() | No (stdout level) | 否 | 否 | Quick debugging |
EventStream
此节点传入事件的异步迭代器。实现了 futures::Stream trait。
收到 Stop 事件后,事件流会自行关闭。节点应在流结束后退出。
#![allow(unused)]
fn main() {
// 阻塞直到下一个事件到达。流关闭时返回 None。
// 使用内部 EventScheduler,可能为公平性重新排序事件。
pub fn recv(&mut self) -> Option<Event>
// 带超时的阻塞。超时时返回 Event::Error。
pub fn recv_timeout(&mut self, dur: Duration) -> Option<Event>
// 带 EventScheduler 重排序的异步接收。
pub async fn recv_async(&mut self) -> Option<Event>
// 带超时的异步接收。超时时返回 Event::Error。
pub async fn recv_async_timeout(&mut self, dur: Duration) -> Option<Event>
// 非阻塞接收。无可用数据时返回 TryRecvError::Empty。
pub fn try_recv(&mut self) -> Result<Event, TryRecvError>
// 非阻塞地排空所有缓冲事件。
// 无可用数据时返回 Some(Vec::new());流关闭时返回 None。
pub fn drain(&mut self) -> Option<Vec<Event>>
// 如果调度器或接收器中没有缓冲事件则为 true。
pub fn is_empty(&self) -> bool
// Returns and resets accumulated drop counts per input ID.
// For `drop_oldest` inputs, drops happen at `queue_size`.
// For `backpressure` inputs, drops happen at 10x `queue_size` (hard safety cap).
pub fn drain_drop_counts(&mut self) -> HashMap<DataId, u64>
}
EventStream 还实现了 futures::Stream<Item = Event>,因此可以与 StreamExt::next() 和其他组合器一起使用。与 recv/recv_async 不同,Stream 实现不使用 EventScheduler,保留事件的时间顺序。
Event
表示传入事件。此枚举为 #[non_exhaustive]——忽略未知变体以保持向前兼容。
#![allow(unused)]
fn main() {
#[non_exhaustive]
pub enum Event {
// 从另一个节点接收到输入。
Input {
id: DataId, // YAML 中的输入 ID(非发送者的输出 ID)
metadata: Metadata, // 时间戳和类型信息
data: ArrowData, // Apache Arrow 数据
},
// 映射到此输入的发送者已退出;不会再有数据到达。
InputClosed { id: DataId },
// 先前关闭的输入已恢复(例如,上游节点在超时后恢复)。
InputRecovered { id: DataId },
// 上游节点已重启。适用于重置缓存或状态。
NodeRestarted { id: NodeId },
// 事件流即将关闭。原因见 StopCause。
Stop(StopCause),
// 指示节点重新加载算子(运行时内部使用)。
Reload { operator_id: Option<OperatorId> },
// 意外的内部错误。记录日志用于调试。
Error(String),
}
}
StopCause
#![allow(unused)]
fn main() {
#[non_exhaustive]
pub enum StopCause {
// 通过 `adora stop` 或 Ctrl-C 显式停止。请尽快退出,否则将被终止。
Manual,
// 所有输入已关闭(上游节点已退出)。仅在节点有输入时发送。
AllInputsClosed,
}
}
辅助类型
DataSample
适合作为输出消息发送的数据区域。对 >= ZERO_COPY_THRESHOLD 的数据使用共享内存以实现零拷贝传输。
实现了 Deref<Target = [u8]> 和 DerefMut,用于读写底层字节。
Metadata 和 MetadataParameters
#![allow(unused)]
fn main() {
// 附加到每个输入事件的完整元数据。
pub struct Metadata {
// 包含时间戳、Arrow 类型信息和用户自定义参数。
}
// 发送输出时附加的用户控制的元数据字段。
// BTreeMap<String, Parameter> 的类型别名。
// 默认为空。传递输入的 metadata.parameters 以转发元数据。
pub type MetadataParameters = BTreeMap<String, Parameter>;
// 单个元数据参数值。
pub enum Parameter {
Bool(bool), Integer(i64), Float(f64), String(String),
ListInt(Vec<i64>), ListFloat(Vec<f64>), ListString(Vec<String>),
Timestamp(DateTime<Utc>),
}
// Extract typed parameters, returning None if missing or wrong type.
pub fn get_string_param<'a>(params: &'a MetadataParameters, key: &str) -> Option<&'a str>
pub fn get_integer_param(params: &MetadataParameters, key: &str) -> Option<i64>
pub fn get_bool_param(params: &MetadataParameters, key: &str) -> Option<bool>
}
Well-known metadata keys (for communication patterns):
| Constant | 值 | 使用方 |
|---|---|---|
REQUEST_ID | "request_id" | 服务请求/响应关联 |
GOAL_ID | "goal_id" | 动作目标标识 |
GOAL_STATUS | "goal_status" | 动作结果状态 |
GOAL_STATUS_SUCCEEDED | "succeeded" | 目标成功完成 |
GOAL_STATUS_ABORTED | "aborted" | 目标被服务端中止 |
GOAL_STATUS_CANCELED | "canceled" | 目标被客户端取消 |
SESSION_ID | "session_id" | Streaming session identifier |
SEGMENT_ID | "segment_id" | Streaming segment within a session |
SEQ | "seq" | Streaming chunk sequence number |
FIN | "fin" | Last chunk of a streaming segment |
FLUSH | "flush" | Discard older queued messages on input |
所有常量均从 adora_node_api 重新导出。
标识类型
#![allow(unused)]
fn main() {
// 运行中数据流实例的唯一标识符(UUID v4)。
pub struct DataflowId(/* ... */);
// 数据流 YAML 中定义的节点标识符。
pub struct NodeId(/* ... */);
// 数据流 YAML 中定义的输入/输出标识符。
pub struct DataId(/* ... */);
}
错误类型
#![allow(unused)]
fn main() {
#[derive(Debug, Error)]
pub enum NodeError {
Init(String), // 配置解析、环境变量、守护进程握手
Connection(String), // 守护进程连接丢失
Output(String), // 发送或关闭失败
Data(String), // 分配或描述符解析
Internal(eyre::Report), // 意外错误的兜底
}
pub type NodeResult<T> = Result<T, NodeError>;
}
TryRecvError
#![allow(unused)]
fn main() {
pub enum TryRecvError {
Empty, // 当前没有可用事件
Closed, // 事件流已关闭
}
}
ZERO_COPY_THRESHOLD
#![allow(unused)]
fn main() {
pub const ZERO_COPY_THRESHOLD: usize = 4096;
}
小于此阈值的消息通过 TCP 发送。等于或超过此大小的消息使用共享内存进行零拷贝传输。
ArrowData
#![allow(unused)]
fn main() {
// arrow::array::ArrayRef 的包装器。实现了到内部 ArrayRef 的 Deref。
pub struct ArrowData(pub arrow::array::ArrayRef);
}
来自 Event::Input 的数据以 ArrowData 形式到达。使用 TryFrom 转换或 Arrow API 提取类型化的值。
InputTracker
用于跟踪输入健康状态和缓存每个输入最后接收值的辅助工具。在上游节点超时时用于优雅降级。
#![allow(unused)]
fn main() {
pub struct InputTracker { /* ... */ }
impl InputTracker {
pub fn new() -> Self
// 从事件更新状态。如果事件相关则返回 true。
pub fn process_event(&mut self, event: &Event) -> bool
// 输入的当前状态(Healthy 或 Closed),如果被追踪的话。
pub fn state(&self, id: &DataId) -> Option<InputState>
// 如果输入当前已关闭则为 true。
pub fn is_closed(&self, id: &DataId) -> bool
// 输入最后接收到的值。即使关闭后仍可用。
pub fn last_value(&self, id: &DataId) -> Option<&ArrowData>
// 所有当前处于 Closed 状态的输入。
pub fn closed_inputs(&self) -> Vec<&DataId>
// 如果任何被追踪的输入已关闭则为 true。
pub fn any_closed(&self) -> bool
}
pub enum InputState {
Healthy, // 正常接收数据
Closed, // 上游退出或超时
}
}
集成测试
integration_testing 模块提供了无需运行守护进程即可测试节点的工具。
setup_integration_testing
设置线程局部状态,使同一线程上下一次调用 AdoraNode::init_from_env 时以测试模式初始化。
#![allow(unused)]
fn main() {
pub fn setup_integration_testing(
input: TestingInput,
output: TestingOutput,
options: TestingOptions,
)
}
TestingInput
#![allow(unused)]
fn main() {
pub enum TestingInput {
// 从 JSON 文件加载事件(必须反序列化为 IntegrationTestInput)。
FromJsonFile(PathBuf),
// 直接提供事件。
Input(IntegrationTestInput),
}
}
TestingOutput
#![allow(unused)]
fn main() {
pub enum TestingOutput {
// 将输出写入 JSONL 文件(创建或覆盖)。
ToFile(PathBuf),
// 将输出作为 JSONL 写入任意 writer。
ToWriter(Box<dyn std::io::Write + Send>),
// 将每个输出作为 JSON 对象发送到 flume 通道。
ToChannel(flume::Sender<serde_json::Map<String, serde_json::Value>>),
}
}
TestingOptions
#![allow(unused)]
fn main() {
#[derive(Debug, Clone, Default)]
pub struct TestingOptions {
// 跳过输出中的时间偏移以进行确定性比较。
pub skip_output_time_offsets: bool,
}
}
环境变量测试
使用 init_from_env 的节点也支持通过环境变量进行基于文件的测试:
| 变量 | 描述 |
|---|---|
ADORA_TEST_WITH_INPUTS | JSON 输入文件的路径(IntegrationTestInput 格式) |
ADORA_TEST_WRITE_OUTPUTS_TO | 输出 JSONL 文件的路径(默认:输入文件旁的 outputs.jsonl) |
ADORA_TEST_NO_OUTPUT_TIME_OFFSET | 如果设置,省略时间偏移以获得确定性输出 |
算子 API (adora-operator-api)
算子是由 Adora 运行时管理的进程内组件。它们被编译为共享库(.so/.dylib/.dll)并由运行时加载。
添加到你的 Cargo.toml:
[dependencies]
adora-operator-api = { workspace = true }
[lib]
crate-type = ["cdylib"]
AdoraOperator Trait
#![allow(unused)]
fn main() {
pub trait AdoraOperator: Default {
fn on_event(
&mut self,
event: &Event,
output_sender: &mut AdoraOutputSender,
) -> Result<AdoraStatus, String>;
}
}
实现此 trait 以定义算子的行为。运行时对每个传入事件调用 on_event。返回 AdoraStatus 以控制执行流程。
Event(算子)
算子的 Event 枚举比节点的 Event 更简单,使用 &str 作为 ID。
#![allow(unused)]
fn main() {
#[non_exhaustive]
pub enum Event<'a> {
// 收到一个输入。
Input { id: &'a str, data: ArrowData },
// 将输入数据解析为 Arrow 数组失败。
InputParseError { id: &'a str, error: String },
// 输入被发送者关闭。
InputClosed { id: &'a str },
// 算子应停止。
Stop,
}
}
AdoraOutputSender
#![allow(unused)]
fn main() {
pub struct AdoraOutputSender<'a>(/* ... */);
impl AdoraOutputSender<'_> {
// 发送输出。`id` 是数据流 YAML 中的输出 ID。
pub fn send(&mut self, id: String, data: impl Array) -> Result<(), String>
}
}
AdoraStatus
从 on_event 返回以控制算子生命周期。
#![allow(unused)]
fn main() {
pub enum AdoraStatus {
Continue, // 继续运行,等待下一个事件
Stop, // 停止此算子
StopAll, // 停止整个数据流
}
}
register_operator! 宏
生成 Adora 运行时加载和调用算子所需的 FFI 入口点。
#![allow(unused)]
fn main() {
use adora_operator_api::register_operator;
register_operator!(MyOperator);
}
每个 crate 必须在顶层精确调用一次,传入实现了 AdoraOperator 的类型。
快速开始示例:节点
一个接收 tick 输入并发送随机数作为输出的最小节点。
use adora_node_api::{AdoraNode, Event, IntoArrow, adora_core::config::DataId};
fn main() -> eyre::Result<()> {
let (mut node, mut events) = AdoraNode::init_from_env()?;
let output = DataId::from("random".to_owned());
while let Some(event) = events.recv() {
match event {
Event::Input { id, metadata, data } => {
if id.as_str() == "tick" {
let value: u64 = fastrand::u64(..);
node.send_output(
output.clone(),
metadata.parameters,
value.into_arrow(),
)?;
}
}
Event::Stop(_) => {}
_ => {}
}
}
Ok(())
}
对应的数据流 YAML:
nodes:
- id: timer
path: adora/timer/millis/100
outputs:
- tick
- id: my-node
path: ./target/debug/my-node
inputs:
tick: timer/tick
outputs:
- random
- id: sink
path: ./target/debug/sink
inputs:
data: my-node/random
快速开始示例:算子
一个计数 tick 并转发格式化消息的最小算子。
#![allow(unused)]
#![warn(unsafe_op_in_unsafe_fn)]
fn main() {
use adora_operator_api::{
AdoraOperator, AdoraOutputSender, AdoraStatus, Event, IntoArrow, register_operator,
};
register_operator!(MyOperator);
#[derive(Debug, Default)]
struct MyOperator {
ticks: usize,
}
impl AdoraOperator for MyOperator {
fn on_event(
&mut self,
event: &Event,
output_sender: &mut AdoraOutputSender,
) -> Result<AdoraStatus, String> {
match event {
Event::Input { id, data } => match *id {
"tick" => {
self.ticks += 1;
let msg = format!("tick count: {}", self.ticks);
output_sender.send("status".into(), msg.into_arrow())?;
}
other => eprintln!("ignoring unexpected input {other}"),
},
Event::InputClosed { id } => {
if *id == "tick" {
return Ok(AdoraStatus::Stop);
}
}
Event::Stop => {}
other => {
eprintln!("received unknown event {other:?}");
}
}
Ok(AdoraStatus::Continue)
}
}
}
对应的数据流 YAML:
nodes:
- id: timer
path: adora/timer/millis/500
outputs:
- tick
- id: runtime-node
operator:
shared_library: ./target/debug/libmy_operator
inputs:
tick: timer/tick
outputs:
- status
Python API 参考
本文档涵盖用于构建 adora 节点、算子和数据流的 Python API。安装方式:
pip install adora-rs
目录
节点 API
from adora import Node
Node 类是自定义节点的主要接口。它连接到运行中的数据流,接收输入事件并发送输出。
Node 类
__init__(node_id=None)
创建新节点并连接到运行中的数据流。
# Standard: node ID is read from environment variables set by the daemon
node = Node()
# Dynamic: connect to a running dataflow by explicit node ID
node = Node(node_id="my-dynamic-node")
Parameters:
node_id(str,可选)—— 动态节点的显式节点 ID。省略时,节点从 adora 守护进程设置的环境变量中读取身份。
异常: 如果节点无法连接到数据流,则抛出 RuntimeError。
next(timeout=None)
从事件流中获取下一个事件。阻塞直到有事件可用或超时过期。
event = node.next() # block indefinitely
event = node.next(timeout=2.0) # block up to 2 seconds
Parameters:
timeout(float,可选)—— 最大等待时间(秒)。
返回: dict —— 一个事件字典,如果所有发送者已被释放或超时过期则为 None。
drain()
非阻塞地获取所有缓冲事件。
events = node.drain()
for event in events:
print(event["type"])
返回: list[dict] —— 事件字典列表。如果没有缓冲事件则返回空列表。
try_recv()
非阻塞接收。如果有可用的缓冲事件则返回。
event = node.try_recv()
if event is not None:
print(event["type"])
返回: dict | None —— 一个事件字典,如果没有缓冲事件则为 None。
recv_async(timeout=None)
异步接收。配合 asyncio 使用。
event = await node.recv_async()
event = await node.recv_async(timeout=5.0)
Parameters:
timeout(float,可选)—— 最大等待时间(秒)。超时时返回错误。
返回: dict | None —— 一个事件字典,如果所有发送者已被释放则为 None。
注意: 此方法为实验性质。PyO3 异步(Rust-Python FFI)集成仍在开发中。
is_empty()
检查事件流中是否有任何缓冲事件。
if not node.is_empty():
event = node.try_recv()
返回: bool
send_output(output_id, data, metadata=None)
在输出通道上发送数据。
import pyarrow as pa
# Send raw bytes
node.send_output("status", b"OK")
# Send an Apache Arrow array (zero-copy capable)
node.send_output("values", pa.array([1, 2, 3]))
# Send with metadata
node.send_output("image", pa.array(pixels), {"camera_id": "front"})
Parameters:
output_id(str)—— 数据流 YAML 中声明的输出名称。data(bytes | pyarrow.Array)—— 载荷。对简单数据使用bytes,对零拷贝共享内存传输使用pyarrow.Array。metadata(dict,可选)—— 附加到消息的键值对。支持的值类型:bool、int、float、str、list[int]、list[float]、list[str]、datetime.datetime。
异常: 如果 data 既不是 bytes 也不是 pyarrow.Array,则抛出 RuntimeError。
Service, action, and streaming patterns
Python nodes use the same metadata key conventions as Rust for communication patterns. Parameters are plain dicts with string keys.
约定的元数据键:
| Key | 描述 |
|---|---|
"request_id" | 服务请求/响应关联(UUID v7) |
"goal_id" | 动作目标标识(UUID v7) |
"goal_status" | 动作结果状态:"succeeded"、"aborted" 或 "canceled" |
"session_id" | Streaming session identifier |
"segment_id" | Streaming segment within a session (integer) |
"seq" | Streaming chunk sequence number (integer) |
"fin" | Last chunk of a streaming segment (bool) |
"flush" | Discard older queued messages on input (bool) |
服务客户端示例:
import uuid
# Send a request with a unique request_id
request_id = str(uuid.uuid7()) # Python 3.13+; use uuid_utils or uuid.uuid4() on older versions
node.send_output("request", data, {"request_id": request_id})
服务服务端示例:
# Pass through the metadata (includes request_id) from the incoming request
node.send_output("response", result, event["metadata"])
动作客户端示例:
goal_id = str(uuid.uuid7())
node.send_output("goal", data, {"goal_id": goal_id})
Streaming example (flush downstream queues on user interruption):
params = {
"session_id": session_id,
"segment_id": 1,
"seq": 0,
"fin": False,
"flush": True,
}
node.send_output("text", data, metadata={"parameters": params})
See patterns.md for the full guide.
日志
Python nodes can log using either Python’s built-in logging module (recommended) or the explicit node API.
Python logging module (auto-bridged):
When Node() is created, it automatically installs a handler that routes Python’s logging module through the adora daemon. No configuration needed:
import logging
from adora import Node
node = Node() # Installs the logging bridge
logging.info("Sensor initialized") # -> structured "info" log entry
logging.warning("High temperature") # -> structured "warn" log entry
logging.debug("Raw bytes: %s", data) # -> structured "debug" log entry
These log entries are captured with full metadata (level, message, file path, line number) and work with min_log_level filtering, send_logs_as routing, and adora/logs subscribers.
Note: Do not call
logging.basicConfig()before creatingNode(). The constructor sets up the bridge; callingbasicConfig()first may install a conflicting handler.
Explicit node API:
log(level, message, target=None, fields=None)
Emit a structured log message with optional target and key-value fields.
node.log("info", "Processing frame", target="vision")
node.log("error", "Sensor timeout", fields={"sensor": "lidar", "retry": "3"})
Parameters:
level(str)—— 日志级别:"error"、"warn"、"info"、"debug"或"trace"。message(str)—— 日志消息。target(str,可选)—— 目标模块或子系统名称。fields(dict[str, str],可选)—— 结构化键值上下文字段。
Works with the daemon’s min_log_level filtering, send_logs_as routing, and adora/logs subscribers.
log_error(message), log_warn(message), log_info(message), log_debug(message), log_trace(message)
Convenience methods for common log levels:
node.log_error("Connection failed")
node.log_warn("Temperature elevated")
node.log_info("Sensor initialized")
node.log_debug("Raw bytes received")
node.log_trace("Entering loop iteration")
Each is equivalent to node.log(level, message).
When to use which:
| 方法 | Structured? | Fields? | 最适用于 |
|---|---|---|---|
logging.info() | 是 | 否 | General-purpose logging |
node.log("info", msg, fields={...}) | 是 | 是 | Structured context (sensor_id, etc.) |
node.log_info(msg) | 是 | 否 | Quick one-liner |
print() | 否 | 否 | Legacy code, quick debugging |
dataflow_descriptor()
以 Python 字典形式返回完整的数据流描述符(解析后的数据流 YAML)。
descriptor = node.dataflow_descriptor()
print(descriptor["nodes"])
返回: dict
node_config()
从数据流描述符返回此节点的配置块。
config = node.node_config()
model_path = config.get("model", "default.pt")
返回: dict
dataflow_id()
返回运行中数据流的唯一标识符。
print(node.dataflow_id()) # e.g. "a1b2c3d4-..."
返回: str
is_restart()
检查此节点是否在之前的退出或故障后被重启。用于决定是恢复保存的状态还是重新开始。
if node.is_restart():
restore_checkpoint()
返回: bool
restart_count()
返回此节点被重启的次数。首次运行时返回 0,第一次重启后返回 1,以此类推。
print(f"Restart #{node.restart_count()}")
返回: int
merge_external_events(subscription)
将 ROS2 订阅流合并到节点的主事件循环中。调用此方法后,ROS2 消息以 kind 设置为 "external" 的事件形式到达。
from adora import Node, Ros2Context, Ros2Node, Ros2NodeOptions, Ros2Topic
node = Node()
ros2_context = Ros2Context()
ros2_node = ros2_context.new_node("listener", Ros2NodeOptions())
topic = Ros2Topic("/chatter", "std_msgs/String", ros2_node)
subscription = ros2_node.create_subscription(topic)
node.merge_external_events(subscription)
for event in node:
if event["kind"] == "external":
print("ROS2:", event["value"])
elif event["type"] == "INPUT":
print("Adora:", event["id"])
Parameters:
subscription(adora.Ros2Subscription)—— 通过 adora ROS2 桥接创建的 ROS2 订阅。
迭代支持
Node 类实现了 __iter__ 和 __next__,因此可以直接迭代:
for event in node:
match event["type"]:
case "INPUT":
process(event["value"])
case "STOP":
break
迭代器在每次迭代时无超时调用 next()。当事件流关闭时产生 None,从而终止循环。
事件字典
事件以普通 Python 字典形式返回。结构取决于事件类型。
INPUT
从另一个节点收到输入消息。
{
"type": "INPUT",
"id": "camera_image", # input ID as declared in the dataflow YAML
"kind": "adora", # "adora" for dataflow events, "external" for ROS2
"value": <pyarrow.Array>, # the payload as an Apache Arrow array
"metadata": {
"timestamp": datetime, # UTC-aware datetime.datetime
"open_telemetry_context": "...", # tracing context (if enabled)
... # any user-supplied metadata
},
}
访问数据:
values = event["value"].to_pylist() # convert to Python list
array = event["value"].to_numpy() # convert to NumPy array
INPUT_CLOSED
输入通道已关闭(上游节点已完成)。
{
"type": "INPUT_CLOSED",
"id": "camera_image",
"kind": "adora",
}
STOP
数据流正在关闭。
{
"type": "STOP",
"id": "MANUAL" | "ALL_INPUTS_CLOSED", # stop cause
"kind": "adora",
}
ERROR
运行时发生错误。
{
"type": "ERROR",
"error": "description of the error",
"kind": "adora",
}
外部(ROS2)
使用 merge_external_events 时,ROS2 消息以如下形式到达:
{
"kind": "external",
"value": <pyarrow.Array>, # the ROS2 message as an Arrow array
}
AdoraStatus 枚举
用作算子 on_event 方法的返回值以控制事件循环。
from adora import AdoraStatus
| 值 | Meaning |
|---|---|
AdoraStatus.CONTINUE | 继续处理事件(值 0) |
AdoraStatus.STOP | 停止此算子(值 1) |
AdoraStatus.STOP_ALL | 停止整个数据流(值 2) |
算子 API
算子在 adora 运行时进程内运行(无单独的操作系统进程)。它们被定义为名为 Operator 的 Python 类,具有 on_event 方法。
Operator 类(用户定义)
创建一个包含 Operator 类的 Python 文件:
from adora import AdoraStatus
class Operator:
def __init__(self):
# Initialize state here
self.count = 0
def on_event(self, adora_event, send_output) -> AdoraStatus:
if adora_event["type"] == "INPUT":
self.count += 1
# Process the input and optionally send output
send_output("result", b"processed", adora_event["metadata"])
return AdoraStatus.CONTINUE
Methods:
__init__(self)—— 算子加载时调用一次。在此初始化任何状态或模型。on_event(self, adora_event, send_output) -> AdoraStatus—— 对每个传入事件调用。必须返回AdoraStatus值。
on_event 的参数:
adora_event(dict)—— 一个事件字典。send_output(callable)—— 发送输出数据的回调(见下文)。
运行时还会在算子实例上设置 self.dataflow_descriptor,值为解析后的数据流 YAML 字典。
send_output 回调
send_output 回调传递给 on_event,用于从算子发送数据。
send_output(output_id, data, metadata=None)
Parameters:
output_id(str)—— 数据流 YAML 中声明的输出名称。data(bytes | pyarrow.Array)—— 载荷。metadata(dict,可选)—— 要附加的元数据。传递adora_event["metadata"]以传播追踪上下文。
Example:
import pyarrow as pa
from adora import AdoraStatus
class Operator:
def on_event(self, adora_event, send_output) -> AdoraStatus:
if adora_event["type"] == "INPUT":
result = pa.array([42], type=pa.int64())
send_output("output", result, adora_event["metadata"])
return AdoraStatus.CONTINUE
DataflowBuilder
from adora.builder import DataflowBuilder, Node, Operator, Output
在 Python 中以编程方式构建数据流 YAML。
DataflowBuilder 类
__init__(name="adora-dataflow")
创建新的数据流构建器。
flow = DataflowBuilder("my-robot")
Parameters:
name(str,可选)—— 数据流名称。默认为"adora-dataflow"。
add_node(id, **kwargs) -> Node
向数据流添加节点。返回 Node 对象以供进一步配置。
sender = flow.add_node("sender")
Parameters:
id(str)—— 唯一节点标识符。**kwargs—— 传递到 YAML 的额外节点配置。
返回: Node(构建器)
to_yaml(path=None) -> str | None
生成数据流的 YAML 表示。如果提供了 path,则写入文件并返回 None。否则返回 YAML 字符串。
# Write to file
flow.to_yaml("dataflow.yml")
# Get as string
yaml_str = flow.to_yaml()
Parameters:
path(str,可选)—— 写入 YAML 的文件路径。
返回: str | None
上下文管理器
DataflowBuilder 支持 with 语句:
with DataflowBuilder("my-flow") as flow:
flow.add_node("sender").path("sender.py")
flow.to_yaml("dataflow.yml")
Node 类(构建器)
由 DataflowBuilder.add_node() 返回。所有 setter 方法返回 self 以支持链式调用。
path(path) -> Node
设置节点可执行文件或脚本的路径。
node.path("my_node.py")
args(args) -> Node
设置节点的命令行参数。
node.args("--verbose --port 8080")
env(env) -> Node
设置节点的环境变量。
node.env({"MODEL_PATH": "/models/yolo.pt"})
build(command) -> Node
设置节点的构建命令(启动前运行)。
node.build("pip install -r requirements.txt")
git(url, branch=None, tag=None, rev=None) -> Node
将 Git 仓库设置为节点的源。
node.git("https://github.com/org/repo.git", branch="main")
add_operator(operator) -> Node
将 Operator 附加到此节点。
op = Operator("detector", python="object_detection.py")
node.add_operator(op)
add_output(output_id) -> Output
在此节点上声明一个输出,并返回 Output 引用以用作输入源。
output = sender.add_output("data")
add_input(input_id, source, queue_size=None, queue_policy=None) -> Node
将此节点订阅到另一个节点的输出。
# Using an Output object
output = sender.add_output("data")
receiver.add_input("data", output)
# Using a string reference
receiver.add_input("tick", "adora/timer/millis/100")
# With a custom queue size
receiver.add_input("images", camera_output, queue_size=2)
# Lossless input (blocks sender when full)
receiver.add_input("commands", cmd_output, queue_size=100, queue_policy="backpressure")
Parameters:
input_id(str)—— 此节点上的输入名称。source(str | Output)—— 字符串("node_id/output_id")或Output对象。queue_size(int,可选)—— 此输入的最大缓冲消息数。queue_policy(str, optional) –"drop_oldest"(default) or"backpressure"(buffers up to 10xqueue_sizebefore dropping).
to_dict() -> dict
返回节点的字典表示,用于 YAML 序列化。
Output 类(构建器)
由 Node.add_output() 返回。表示节点输出的引用,用作 add_input() 中的源。
output = sender.add_output("data")
receiver.add_input("sensor_data", output)
str(output) # "sender/data"
Operator 类(构建器)
定义用于嵌入节点 YAML 配置中的算子。
__init__(id, name=None, description=None, build=None, python=None, shared_library=None, send_stdout_as=None)
op = Operator(
id="detector",
python="object_detection.py",
send_stdout_as="detection_text",
)
Parameters:
id(str)—— 唯一算子标识符。name(str,可选)—— 显示名称。description(str,可选)—— 可读的描述。build(str,可选)—— 加载前运行的构建命令。python(str,可选)—— Python 算子文件的路径。shared_library(str,可选)—— 共享库算子的路径。send_stdout_as(str,可选)—— 将算子的 stdout 作为具有此 ID 的输出路由。
to_dict() -> dict
返回用于 YAML 序列化的字典表示。
CUDA 模块
from adora.cuda import torch_to_ipc_buffer, ipc_buffer_to_ipc_handle, open_ipc_handle
通过 CUDA IPC 实现节点间零拷贝 GPU 张量共享的实用工具。需要支持 CUDA 的 PyTorch 和 Numba。
torch_to_ipc_buffer(tensor) -> tuple[pyarrow.Array, dict]
将 PyTorch CUDA 张量转换为包含 CUDA IPC 句柄的 Arrow 数组和元数据字典。通过数据流发送两者以无需复制即可共享 GPU 内存。
import torch
import pyarrow as pa
from adora import Node
from adora.cuda import torch_to_ipc_buffer
node = Node()
tensor = torch.randn(1024, 768, device="cuda")
ipc_buffer, metadata = torch_to_ipc_buffer(tensor)
node.send_output("gpu_data", ipc_buffer, metadata)
Parameters:
tensor(torch.Tensor)—— CUDA 张量。
返回: tuple[pyarrow.Array, dict] —— IPC 句柄(int8 Arrow 数组),以及包含形状、步长、数据类型、大小、偏移和来源信息的元数据。
ipc_buffer_to_ipc_handle(handle_buffer, metadata) -> IpcHandle
从接收到的 Arrow 缓冲区和元数据重建 CUDA IPC 句柄。
from adora.cuda import ipc_buffer_to_ipc_handle
event = node.next()
ipc_handle = ipc_buffer_to_ipc_handle(event["value"], event["metadata"])
Parameters:
handle_buffer(pyarrow.Array)—— 来自event["value"]的 Arrow 数组。metadata(dict)—— 来自event["metadata"]的元数据。
返回: numba.cuda.cudadrv.driver.IpcHandle
open_ipc_handle(ipc_handle, metadata) -> ContextManager[torch.Tensor]
打开 CUDA IPC 句柄并产生 PyTorch 张量。作为上下文管理器使用以确保正确清理。
from adora.cuda import ipc_buffer_to_ipc_handle, open_ipc_handle
event = node.next()
ipc_handle = ipc_buffer_to_ipc_handle(event["value"], event["metadata"])
with open_ipc_handle(ipc_handle, event["metadata"]) as tensor:
result = tensor * 2 # use the GPU tensor directly
Parameters:
ipc_handle(IpcHandle)—— 来自ipc_buffer_to_ipc_handle的句柄。metadata(dict)—— 包含形状、步长和数据类型信息的元数据字典。
返回: 产生 CUDA 上 torch.Tensor 的上下文管理器。
快速开始示例
一个接收图像、处理并发送结果的完整节点:
#!/usr/bin/env python3
"""示例节点:接收消息、转换并发送输出。"""
import logging
import pyarrow as pa
from adora import Node
def main():
node = Node()
for event in node:
if event["type"] == "INPUT":
input_id = event["id"]
if input_id == "message":
values = event["value"].to_pylist()
number = values[0]
# Create a struct array with multiple fields
result = pa.StructArray.from_arrays(
[
pa.array([number * 2]),
pa.array([f"Message #{number}"]),
],
names=["doubled", "description"],
)
node.send_output("transformed", result)
logging.info("Transformed message %d", number)
elif event["type"] == "STOP":
logging.info("Node stopping")
break
if __name__ == "__main__":
main()
运行方式:
adora run dataflow.yml
DataflowBuilder 示例
以编程方式构建数据流,而非手动编写 YAML:
#!/usr/bin/env python3
"""构建一个简单的 sender -> receiver 数据流。"""
from adora.builder import DataflowBuilder, Operator
flow = DataflowBuilder("example-flow")
# Add a timer-driven sender node
sender = flow.add_node("sender")
sender.path("sender.py")
tick_output = sender.add_output("message")
# Add a receiver that subscribes to the sender
receiver = flow.add_node("receiver")
receiver.path("receiver.py")
receiver.add_input("message", tick_output)
# Add a node with a timer input
timed_node = flow.add_node("periodic")
timed_node.path("periodic.py")
timed_node.add_input("tick", "adora/timer/millis/100")
# Add a node with an operator
runtime_node = flow.add_node("runtime-node")
op = Operator("detector", python="object_detection.py")
runtime_node.add_operator(op)
runtime_node.add_input("image", "camera/image")
# Write or print the YAML
flow.to_yaml("dataflow.yml")
print(flow.to_yaml())
C API 参考
本文档涵盖 Adora 框架提供的两个 C API:用于独立 C 进程的节点 API 和用于 Adora 运行时加载的共享库算子的算子 API。
目录
节点 API (adora-node-api-c)
头文件:apis/c/node/node_api.h Crate:adora-node-api-c(构建为 staticlib)
节点 API 供作为外部进程参与 Adora 数据流的独立 C 可执行文件使用。守护进程生成进程并设置节点在初始化期间读取的环境变量。
初始化
init_adora_context_from_env
void *init_adora_context_from_env();
从守护进程设置的环境变量初始化 Adora 节点上下文。成功时返回指向上下文的不透明指针,失败时返回 NULL。
返回的指针必须传递给所有期望上下文参数的后续节点 API 调用。节点完成后,使用 free_adora_context 释放。
free_adora_context
void free_adora_context(void *adora_context);
释放先前由 init_adora_context_from_env 创建的上下文。每个上下文必须恰好释放一次。释放后不得再次使用该指针。
事件循环
adora_next_event
void *adora_next_event(void *adora_context);
阻塞直到此节点有可用的下一个事件。返回指向事件的不透明指针,当所有事件流关闭时返回 NULL(表示节点应退出)。
返回的指针不能直接解引用。使用 read_adora_* 函数提取事件类型和载荷。完成后使用 free_adora_event 释放事件。
free_adora_event
void free_adora_event(void *adora_event);
释放先前由 adora_next_event 返回的事件。每个事件必须恰好释放一次。释放后,事件指针和所有派生指针(来自 read_adora_input_id、read_adora_input_data)都将失效。
事件检查
read_adora_event_type
enum AdoraEventType read_adora_event_type(void *adora_event);
返回给定事件的类型。可能的值请参见 AdoraEventType。
read_adora_input_id
void read_adora_input_id(void *adora_event, char **out_ptr, size_t *out_len);
从 AdoraEventType_Input 事件读取输入 ID。将字符串起始指针写入 *out_ptr,字节长度写入 *out_len。字符串是有效的 UTF-8 但不以 null 结尾;使用 out_len 确定其边界。
如果事件不是输入事件,则设置 *out_ptr = NULL 和 *out_len = 0。
返回的指针借用自事件。调用 free_adora_event 后将失效。
read_adora_input_data
void read_adora_input_data(void *adora_event, char **out_ptr, size_t *out_len);
从 AdoraEventType_Input 事件读取原始数据字节。将数据起始指针写入 *out_ptr,字节长度写入 *out_len。
如果事件不是输入事件或输入不携带数据,则设置 *out_ptr = NULL 和 *out_len = 0。
目前仅支持 UInt8 Arrow 数组。其他 Arrow 数据类型会导致运行时 panic。未来版本将使用 Arrow C Data Interface 以支持所有类型。
返回的指针借用自事件。调用 free_adora_event 后将失效。
read_adora_input_timestamp
unsigned long long read_adora_input_timestamp(void *adora_event);
以 uint64 值形式返回输入事件元数据中的混合逻辑时钟时间戳。如果事件不是输入事件则返回 0。
Output
adora_send_output
int adora_send_output(
void *adora_context,
const char *id_ptr,
size_t id_len,
const char *data_ptr,
size_t data_len
);
向所有下游订阅者发送输出数据。输出 ID(id_ptr/id_len)必须是有效的 UTF-8 字符串,与数据流 YAML 中节点声明的某个输出匹配。数据(data_ptr/data_len)作为原始字节(UInt8 Arrow 数组)发送。
成功返回 0,错误返回 -1。错误通过 tracing 记录。
如果任何指针参数为 NULL,则立即返回 -1。
日志
adora_log
int adora_log(
void *adora_context,
const char *level_ptr,
size_t level_len,
const char *msg_ptr,
size_t msg_len
);
通过 Adora 日志管道发送结构化日志消息。level 和 msg 都必须是有效的 UTF-8 字符串。
有效的日志级别:"error"、"warn"、"info"、"debug"、"trace"。
成功返回 0,错误返回 -1。如果任何指针参数为 NULL,则立即返回 -1。
Enums
AdoraEventType
enum AdoraEventType {
AdoraEventType_Stop, // 请求优雅关闭
AdoraEventType_Input, // 有新输入数据可用
AdoraEventType_InputClosed, // 输入流已关闭
AdoraEventType_Error, // 发生错误
AdoraEventType_Unknown, // 无法识别的事件类型
};
算子 API (adora-operator-api-c)
头文件:apis/c/operator/operator_api.h、apis/c/operator/operator_types.h Crate:adora-operator-api-c
算子 API 供加载到 Adora 运行时进程中的共享库(.so/.dylib/.dll)使用。与节点不同,算子没有自己的 main 函数。它们导出三个函数,由运行时在适当的生命周期点调用。
operator_types.h 头文件由 safer-ffi 自动生成,定义了所有 C 兼容的结构体和枚举类型。
生命周期函数
adora_init_operator
AdoraInitResult_t adora_init_operator(void);
运行时加载算子时调用一次。分配并初始化所有算子状态,然后通过 operator_context 字段返回。运行时在每次后续调用中传回此指针。
成功时返回 .result.error = NULL 的 AdoraInitResult_t。
adora_drop_operator
AdoraResult_t adora_drop_operator(void *operator_context);
算子被卸载时调用一次。释放与 operator_context 关联的所有资源。
成功时返回 .error = NULL 的 AdoraResult_t。
事件处理
adora_on_event
OnEventResult_t adora_on_event(
RawEvent_t *event,
const SendOutput_t *send_output,
void *operator_context
);
每当此算子有事件到达时由运行时调用。检查 event 字段以确定事件类型:
| Field | Meaning |
|---|---|
event->input != NULL | 有新输入可用 |
event->stop == true | 请求优雅关闭 |
event->error.ptr != NULL | 发生错误(UTF-8 字符串位于 error.ptr/error.len) |
event->input_closed.ptr != NULL | 输入流已关闭(输入 ID 位于 input_closed.ptr/input_closed.len) |
使用 send_output 向下游节点发送数据(见 adora_send_operator_output)。返回带有适当 AdoraStatus_t 的 OnEventResult_t 以控制算子生命周期。
输入读取
adora_read_input_id
char *adora_read_input_id(const Input_t *input);
返回新分配的以 null 结尾的字符串,包含输入 ID。调用者必须使用 adora_free_input_id 释放。
adora_read_data
Vec_uint8_t adora_read_data(Input_t *input);
将输入数据作为字节数组读取。从输入中消费底层 Arrow 数组(每个事件只能读取一次数据)。如果输入没有数据或数据已被消费,则返回 .ptr = NULL 的 Vec_uint8_t。
调用者必须使用 adora_free_data 释放返回的数据。
输出发送
adora_send_operator_output
AdoraResult_t adora_send_operator_output(
const SendOutput_t *send_output,
const char *id,
const uint8_t *data_ptr,
size_t data_len
);
向下游订阅者发送输出数据。id 必须是以 null 结尾的字符串,与算子声明的某个输出匹配。数据(data_ptr/data_len)在内部被转换为 UInt8 Arrow 数组。
成功时返回 .error = NULL 的 AdoraResult_t。
内存管理
算子 API 分配的内存必须由调用者使用相应的函数释放:
| 分配来源 | 释放函数 |
|---|---|
adora_read_input_id | adora_free_input_id |
adora_read_data | adora_free_data |
void adora_free_input_id(char *input_id);
void adora_free_data(Vec_uint8_t data);
不调用这些函数会导致内存泄漏。不要对这些分配使用 free()——它们由 Rust 运行时分配,必须通过 API 释放。
Structs
Vec_uint8_t
typedef struct Vec_uint8 {
uint8_t *ptr;
size_t len;
size_t cap;
} Vec_uint8_t;
Rust 分配的字节向量。从 ptr 开始访问 len 个字节。不要修改 cap。使用 adora_free_data 释放。
AdoraResult_t
typedef struct AdoraResult {
Vec_uint8_t *error; // 成功时为 NULL,失败时指向错误字符串
} AdoraResult_t;
通用结果类型。NULL 错误指针表示成功。非 NULL 时,错误指针包含 UTF-8 错误消息。
AdoraInitResult_t
typedef struct AdoraInitResult {
AdoraResult_t result;
void *operator_context; // 算子状态的不透明指针
} AdoraInitResult_t;
由 adora_init_operator 返回。成功时 result.error 为 NULL,operator_context 持有算子状态指针。
OnEventResult_t
typedef struct OnEventResult {
AdoraResult_t result;
AdoraStatus_t status;
} OnEventResult_t;
由 adora_on_event 返回。包含错误/成功结果和控制算子生命周期的状态码。
RawEvent_t
typedef struct RawEvent {
Input_t *input; // 输入事件时为非 NULL
Vec_uint8_t input_closed; // 输入流关闭时为非空
bool stop; // 请求关闭时为 true
Vec_uint8_t error; // 错误时为非空
} RawEvent_t;
表示传递给算子的事件。多个字段可能同时被设置;按优先级顺序检查它们。
Input_t
typedef struct Input Input_t; // 不透明
表示输入事件数据的不透明类型。使用 adora_read_input_id 和 adora_read_data 提取其内容。
Output_t
typedef struct Output Output_t; // 不透明
由 adora_send_operator_output 内部使用的不透明类型。不由用户代码直接创建。
SendOutput_t
typedef struct SendOutput {
ArcDynFn1_AdoraResult_Output_t send_output;
} SendOutput_t;
传递给 adora_on_event 的回调句柄。将其传递给 adora_send_operator_output 以发送数据。不要将其存储在当前 adora_on_event 调用的范围之外。
Metadata_t
typedef struct Metadata {
Vec_uint8_t open_telemetry_context;
} Metadata_t;
包含 OpenTelemetry 追踪上下文字符串的事件元数据。
算子枚举
AdoraStatus_t
enum AdoraStatus {
ADORA_STATUS_CONTINUE = 0, // 继续运行
ADORA_STATUS_STOP = 1, // 停止此算子
ADORA_STATUS_STOP_ALL = 2, // 停止整个数据流
};
typedef uint8_t AdoraStatus_t;
在 OnEventResult_t 中返回,用于在处理事件后控制算子生命周期。
节点示例
一个接收定时器 tick 并发送输出消息的完整 C 节点:
#include <stdio.h>
#include <string.h>
#include "node_api.h"
int main() {
void *ctx = init_adora_context_from_env();
if (ctx == NULL) {
fprintf(stderr, "failed to init adora context\n");
return 1;
}
for (int i = 0; i < 100; i++) {
void *event = adora_next_event(ctx);
if (event == NULL)
break; // 所有流已关闭
enum AdoraEventType ty = read_adora_event_type(event);
if (ty == AdoraEventType_Input) {
char *id;
size_t id_len;
read_adora_input_id(event, &id, &id_len);
// 发送响应
char out_id[] = "message";
char out_data[64];
int out_len = snprintf(out_data, sizeof(out_data),
"iteration %d", i);
adora_send_output(ctx, out_id, strlen(out_id),
out_data, out_len);
} else if (ty == AdoraEventType_Stop) {
free_adora_event(event);
break;
}
free_adora_event(event);
}
free_adora_context(ctx);
return 0;
}
节点的数据流 YAML:
nodes:
- id: c_node
path: build/c_node
inputs:
timer: adora/timer/millis/100
outputs:
- message
算子示例
一个读取输入、维护状态并发送输出的完整 C 算子:
#include "operator_api.h"
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
AdoraInitResult_t adora_init_operator(void) {
// 分配算子状态(一个简单的计数器)
int *counter = (int *)calloc(1, sizeof(int));
AdoraInitResult_t result = {.operator_context = counter};
return result;
}
AdoraResult_t adora_drop_operator(void *operator_context) {
free(operator_context);
AdoraResult_t result = {.error = NULL};
return result;
}
OnEventResult_t adora_on_event(
RawEvent_t *event,
const SendOutput_t *send_output,
void *operator_context)
{
OnEventResult_t result = {.status = ADORA_STATUS_CONTINUE};
int *counter = (int *)operator_context;
if (event->input != NULL) {
char *id = adora_read_input_id(event->input);
Vec_uint8_t data = adora_read_data(event->input);
if (data.ptr != NULL) {
*counter += 1;
printf("received input '%s', counter: %d\n", id, *counter);
// 将计数器值作为字符串发送
char buf[64];
int len = snprintf(buf, sizeof(buf), "count=%d", *counter);
result.result = adora_send_operator_output(
send_output, "counter", (uint8_t *)buf, len);
adora_free_data(data);
}
adora_free_input_id(id);
}
if (event->stop) {
result.status = ADORA_STATUS_STOP;
}
return result;
}
算子的数据流 YAML:
nodes:
- id: runtime-node
operators:
- id: c_operator
shared-library: build/operator
inputs:
data: source_node/output
outputs:
- counter
构建和链接
节点(静态库)
C 节点链接 adora-node-api-c,它构建为静态库。
步骤 1:构建静态库
cargo build -p adora-node-api-c --release
这会生成 target/release/libadora_node_api_c.a(Windows 上为 .lib)。
步骤 2:编译和链接
clang node.c -ladora_node_api_c -L ../../target/release -o build/c_node <FLAGS>
平台特定的链接器标志:
| Platform | Flags |
|---|---|
| Linux | -lm -lrt -ldl -pthread |
| macOS | -framework CoreServices -framework Security -lSystem -lresolv -lpthread -lc -lm |
| Windows | -ladvapi32 -luserenv -lkernel32 -lws2_32 -lbcrypt -lncrypt -lschannel -lntdll -liphlpapi -lcfgmgr32 -lcredui -lcrypt32 -lcryptnet -lfwpuclnt -lgdi32 -lmsimg32 -lmswsock -lole32 -lopengl32 -lsecur32 -lshell32 -lsynchronization -luser32 -lwinspool -Wl,-nodefaultlib:libcmt -D_DLL -lmsvcrt |
在 Windows 上,为输出文件添加 .exe 扩展名。
算子(共享库)
C 算子被编译为共享库,由 Adora 运行时在启动时加载。
步骤 1:编译为目标文件
clang -c operator.c -o build/operator.o -fdeclspec -fPIC
Windows 上省略 -fPIC。
步骤 2:链接为共享库
# Linux
clang -shared build/operator.o -o build/liboperator.so
# macOS
clang -shared build/operator.o -o build/liboperator.dylib
# Windows
clang -shared build/operator.o -o build/operator.dll
步骤 3:在数据流 YAML 中引用
operators:
- id: c_operator
shared-library: build/operator # 不含 lib 前缀或扩展名
inputs:
data: source/output
outputs:
- result
shared-library 路径省略平台特定的前缀(lib)和扩展名(.so/.dylib/.dll)。运行时为当前平台解析正确的文件。
头文件路径
节点 API 头文件位于 apis/c/node/node_api.h。算子 API 头文件位于 apis/c/operator/operator_api.h 和 apis/c/operator/operator_types.h。相应调整你的头文件路径:
# Node
clang -I path/to/adora/apis/c/node node.c ...
# Operator
clang -I path/to/adora/apis/c/operator operator.c ...
C++ 兼容性
两组头文件都包含 extern "C" 保护(算子头文件中)或使用 C 兼容的声明(节点头文件中),因此可以直接从 C++ 源文件包含。
C++ API 参考
Adora 通过 CXX(Rust-C++ 互操作)为独立节点和进程内算子提供 C++ 绑定。CXX 桥接从 Rust 定义生成类型安全的 C++ 头文件——无需原始 FFI 或手动 extern "C" 声明。
两个 crate 提供 C++ 接口:
| Crate | 库 | 用例 |
|---|---|---|
adora-node-api-cxx | libadora_node_api_cxx.a | 独立节点可执行文件 |
adora-operator-api-cxx | libadora_operator_api_cxx.a | 由运行时加载的共享库算子 |
生成的头文件:adora-node-api.h 和 adora-operator-api.h。
节点 API(adora-node-api-cxx)
初始化
#include "adora-node-api.h"
// 从 Adora 守护进程设置的环境变量初始化节点。
// 返回包含事件流和输出发送器的 AdoraNode 结构体。
// 失败时抛出异常。
AdoraNode init_adora_node();
AdoraNode
由 init_adora_node() 返回。在节点的生命周期内拥有事件流和输出发送器。
struct AdoraNode {
rust::Box<Events> events; // 事件流(阻塞接收器)
rust::Box<OutputSender> send_output; // 输出发送器
};
Events
暴露给 C++ 的不透明 Rust 类型。提供对节点传入事件的阻塞迭代。
// 成员函数——直接在 boxed 对象上调用。
rust::Box<AdoraEvent> Events::next();
// 自由函数形式——等价于 events->next()。
rust::Box<AdoraEvent> next_event(rust::Box<Events>& events);
两种形式都会阻塞直到下一个事件到达,并返回一个拥有的 AdoraEvent。
AdoraEvent
不透明 Rust 类型。使用 event_type() 检查其类型,然后使用 event_as_input() 或 event_as_arrow_input() 进行向下转换。
// 确定事件类型。
AdoraEventType event_type(const rust::Box<AdoraEvent>& event);
// 向下转换为原始字节输入。如果事件不是 Input 则抛出异常。
AdoraInput event_as_input(rust::Box<AdoraEvent> event);
// 向下转换为 Arrow FFI 输入(写入 Arrow C Data Interface 结构体)。
// out_array 和 out_schema 必须指向有效的 ArrowArray / ArrowSchema 结构体。
// 成功时返回 error 为空的 AdoraResult。
AdoraResult event_as_arrow_input(
rust::Box<AdoraEvent> event,
uint8_t* out_array,
uint8_t* out_schema);
// 与上面相同,但还返回输入 ID 和元数据。
ArrowInputInfo event_as_arrow_input_with_info(
rust::Box<AdoraEvent> event,
uint8_t* out_array,
uint8_t* out_schema);
AdoraEventType
enum class AdoraEventType : uint8_t {
Stop, // 请求优雅关闭
Input, // 输入上有新数据到达
InputClosed, // 单个输入已关闭
Error, // 发生错误
Unknown, // 无法识别的事件变体
AllInputsClosed, // 所有输入已关闭(流已结束)
};
AdoraInput
由 event_as_input() 返回。包含原始字节。
struct AdoraInput {
rust::String id; // 输入标识符(如 "tick"、"image")
rust::Vec<uint8_t> data; // 原始载荷字节
};
ArrowInputInfo
由 event_as_arrow_input_with_info() 返回。包含输入 ID、元数据和错误字符串。
struct ArrowInputInfo {
rust::String id; // 输入标识符
rust::Box<Metadata> metadata; // 附加的元数据
rust::String error; // 成功时为空
};
AdoraResult
由输出发送函数返回。检查 error 字段——为空表示成功。
struct AdoraResult {
rust::String error; // 成功时为空字符串
};
OutputSender
不透明 Rust 类型。所有方法以 rust::Box<OutputSender>& 作为第一个参数(来自 AdoraNode::send_output 的发送器)。
send_output
在命名输出上发送原始字节。
AdoraResult send_output(
rust::Box<OutputSender>& sender,
rust::String id,
rust::Slice<const uint8_t> data);
send_output_with_metadata
发送带有附加元数据的原始字节。
AdoraResult send_output_with_metadata(
rust::Box<OutputSender>& sender,
rust::String id,
rust::Slice<const uint8_t> data,
rust::Box<Metadata> metadata);
send_arrow_output
通过 C Data Interface 发送 Arrow 数组。指针必须引用有效的 ArrowArray 和 ArrowSchema 结构体。成功时 Arrow 数据的所有权转移到 Rust。
AdoraResult send_arrow_output(
rust::Box<OutputSender>& sender,
rust::String id,
uint8_t* array_ptr,
uint8_t* schema_ptr);
// 带元数据的重载(通过 cxx_name 属性使用相同的 C++ 名称)。
AdoraResult send_arrow_output(
rust::Box<OutputSender>& sender,
rust::String id,
uint8_t* array_ptr,
uint8_t* schema_ptr,
rust::Box<Metadata> metadata);
log_message
通过 Adora 日志系统发送日志消息。
AdoraResult log_message(
const rust::Box<OutputSender>& sender,
rust::String level, // 如 "info"、"warn"、"error"
rust::String message);
元数据
用于向输出附加类型化键值对的不透明 Rust 类型。
Construction
rust::Box<Metadata> new_metadata();
Reading
uint64_t Metadata::timestamp() const;
bool Metadata::get_bool(const rust::Str key) const; // 缺失或类型错误时抛出异常
int64_t Metadata::get_int(const rust::Str key) const;
double Metadata::get_float(const rust::Str key) const;
rust::String Metadata::get_str(const rust::Str key) const;
rust::Vec<int64_t> Metadata::get_list_int(const rust::Str key) const;
rust::Vec<double> Metadata::get_list_float(const rust::Str key) const;
rust::Vec<rust::String> Metadata::get_list_string(const rust::Str key) const;
int64_t Metadata::get_timestamp(const rust::Str key) const; // 自纪元以来的纳秒数
rust::String Metadata::get_json(const rust::Str key) const; // 单个值作为 JSON 字符串
Writing
所有 setter 在失败时抛出异常。
void Metadata::set_bool(const rust::Str key, bool value);
void Metadata::set_int(const rust::Str key, int64_t value);
void Metadata::set_float(const rust::Str key, double value);
void Metadata::set_string(const rust::Str key, rust::String value);
void Metadata::set_list_int(const rust::Str key, rust::Vec<int64_t> value);
void Metadata::set_list_float(const rust::Str key, rust::Vec<double> value);
void Metadata::set_list_string(const rust::Str key, rust::Vec<rust::String> value);
void Metadata::set_timestamp(const rust::Str key, int64_t nanos); // 自纪元以来的纳秒数
Introspection
MetadataValueType Metadata::type(const rust::Str key) const; // 键缺失时抛出异常
rust::String Metadata::to_json() const; // 完整元数据作为 JSON
rust::Vec<rust::String> Metadata::list_keys() const;
MetadataValueType
enum class MetadataValueType : uint8_t {
Bool,
Integer,
Float,
String,
ListInt,
ListFloat,
ListString,
Timestamp,
};
Service, Action, and Streaming Patterns
C++ nodes can implement communication patterns using the metadata API. The well-known metadata keys are:
| Key | 描述 |
|---|---|
"request_id" | 服务请求/响应关联(UUID v7) |
"goal_id" | 动作目标标识(UUID v7) |
"goal_status" | 动作结果状态:"succeeded"、"aborted" 或 "canceled" |
"session_id" | Streaming session identifier |
"segment_id" | Streaming segment within a session (integer) |
"seq" | Streaming chunk sequence number (integer) |
"fin" | Last chunk of a streaming segment (bool) |
"flush" | Discard older queued messages on input (bool) |
// 服务服务端:传递输入元数据中的 request_id
auto input_metadata = event_as_arrow_input_with_info(event);
send_output_with_metadata(sender, "response", result, std::move(input_metadata.metadata));
// 动作服务端:在结果上设置 goal_id 和 goal_status
auto meta = new_metadata();
meta->set_string("goal_id", goal_id);
meta->set_string("goal_status", "succeeded");
send_output_with_metadata(sender, "result", result_data, std::move(meta));
CombinedEvents(ROS2 集成)
使用可选的 ros2-bridge 特性时,节点事件和 ROS2 订阅事件可以合并为单个流。
// 将 Adora 事件转换为合并流。
CombinedEvents adora_events_into_combined(rust::Box<Events> events);
// 创建空的合并流(用于仅 ROS2 的节点)。
CombinedEvents empty_combined_events();
CombinedEvents 结构体
struct CombinedEvents {
rust::Box<MergedEvents> events;
CombinedEvent next(); // 阻塞——返回下一个合并事件
};
CombinedEvent 结构体
struct CombinedEvent {
rust::Box<MergedAdoraEvent> event;
bool is_adora() const; // 如果这是标准 Adora 事件则为 true
};
// 将合并事件向下转换为 AdoraEvent。如果不是 Adora 事件则抛出异常。
rust::Box<AdoraEvent> downcast_adora(CombinedEvent event);
ROS2 subscriptions add their own events to the merged stream. Use subscription->matches(event) and subscription->downcast(event) to handle ROS2-specific events (see the ROS2 Bridge docs).
算子 API(adora-operator-api-cxx)
算子是由 Adora 运行时加载的共享库。C++ 端实现两个由 CXX 桥接调用的函数。
必需的 C++ 接口
你必须提供头文件 operator.h 和实现文件。头文件声明一个 Operator 类和两个自由函数:
// operator.h
#pragma once
#include <memory>
#include "adora-operator-api.h"
class Operator {
public:
Operator();
// 添加算子需要的任何状态。
};
std::unique_ptr<Operator> new_operator();
AdoraOnInputResult on_input(
Operator& op,
rust::Str id,
rust::Slice<const uint8_t> data,
OutputSender& output_sender);
new_operator()—— 启动时调用一次;返回算子实例。on_input()—— 对每个输入事件调用;处理数据并可选地发送输出。
OutputSender(算子)
在 on_input() 内可用。在命名输出上发送数据。
AdoraSendOutputResult send_output(
OutputSender& sender,
rust::Str id,
rust::Slice<const uint8_t> data);
结果类型
struct AdoraOnInputResult {
rust::String error; // 成功时为空
bool stop; // 为 true 时请求优雅关闭
};
struct AdoraSendOutputResult {
rust::String error; // 成功时为空
};
快速开始:节点示例
一个接收定时器 tick 并发送计数器的最小节点。
#include "adora-node-api.h"
#include <iostream>
#include <vector>
int main() {
auto adora_node = init_adora_node();
unsigned char counter = 0;
for (;;) {
auto event = next_event(adora_node.events);
auto ty = event_type(event);
if (ty == AdoraEventType::AllInputsClosed) {
break;
}
if (ty == AdoraEventType::Stop) {
break;
}
if (ty == AdoraEventType::Input) {
auto input = event_as_input(std::move(event));
counter += 1;
std::cout << "Input: " << std::string(input.id)
<< " counter=" << (int)counter << std::endl;
std::vector<unsigned char> out{counter};
rust::Slice<const uint8_t> slice{out.data(), out.size()};
auto result = send_output(adora_node.send_output, "counter", slice);
if (!result.error.empty()) {
std::cerr << "Send error: " << std::string(result.error) << std::endl;
return 1;
}
}
}
return 0;
}
数据流 YAML:
nodes:
- id: cxx-node
path: build/my_node
inputs:
tick: adora/timer/millis/300
outputs:
- counter
快速开始:Arrow 节点示例
一个通过 C Data Interface 接收和发送 Arrow 数组的节点,带有元数据。
#include "adora-node-api.h"
#include <arrow/api.h>
#include <arrow/c/bridge.h>
#include <iostream>
int main() {
auto adora_node = init_adora_node();
for (int i = 0; i < 10; i++) {
auto event = adora_node.events->next();
auto ty = event_type(event);
if (ty == AdoraEventType::AllInputsClosed || ty == AdoraEventType::Stop) {
break;
}
if (ty == AdoraEventType::Input) {
// 接收带元数据的 Arrow 输入
struct ArrowArray c_array;
struct ArrowSchema c_schema;
auto info = event_as_arrow_input_with_info(
std::move(event),
reinterpret_cast<uint8_t*>(&c_array),
reinterpret_cast<uint8_t*>(&c_schema));
if (!info.error.empty()) {
std::cerr << std::string(info.error) << std::endl;
continue;
}
std::cout << "Input: " << std::string(info.id)
<< " ts=" << info.metadata->timestamp() << std::endl;
auto imported = arrow::ImportArray(&c_array, &c_schema);
auto array = imported.ValueOrDie();
std::cout << "Arrow: " << array->ToString() << std::endl;
// 构建输出 Arrow 数组
arrow::Int32Builder builder;
builder.Append(i * 10);
std::shared_ptr<arrow::Array> out_array;
builder.Finish(&out_array);
// 导出并带元数据发送
struct ArrowArray out_c_array;
struct ArrowSchema out_c_schema;
arrow::ExportArray(*out_array, &out_c_array, &out_c_schema);
auto meta = new_metadata();
meta->set_string("source", "cpp-arrow-node");
meta->set_int("iteration", i);
auto result = send_arrow_output(
adora_node.send_output, "counter",
reinterpret_cast<uint8_t*>(&out_c_array),
reinterpret_cast<uint8_t*>(&out_c_schema),
std::move(meta));
if (!result.error.empty()) {
std::cerr << "Send error: " << std::string(result.error) << std::endl;
}
}
}
return 0;
}
快速开始:算子示例
一个最小的算子共享库。
// operator.cc
#include "operator.h"
#include <iostream>
#include <vector>
Operator::Operator() {}
std::unique_ptr<Operator> new_operator() {
return std::make_unique<Operator>();
}
AdoraOnInputResult on_input(
Operator& op,
rust::Str id,
rust::Slice<const uint8_t> data,
OutputSender& output_sender)
{
op.counter += 1;
std::vector<unsigned char> out{op.counter};
rust::Slice<const uint8_t> slice{out.data(), out.size()};
auto send_result = send_output(output_sender, rust::Str("status"), slice);
return AdoraOnInputResult{send_result.error, false};
}
数据流 YAML:
nodes:
- id: runtime-node
operators:
- id: my-operator
shared-library: build/my_operator
inputs:
data: some-node/output
outputs:
- status
构建集成(CMake)
推荐的构建方式是使用 CMake 配合 DoraTargets.cmake 辅助脚本(见 examples/cmake-dataflow/)。
项目结构
my-project/
CMakeLists.txt
DoraTargets.cmake # copied from examples/cmake-dataflow/
node/main.cc
operator/operator.h
operator/operator.cc
dataflow.yml
CMakeLists.txt
cmake_minimum_required(VERSION 3.21)
project(my-dataflow LANGUAGES C CXX)
set(CMAKE_CXX_STANDARD 20)
set(CMAKE_CXX_FLAGS "-fPIC")
include(DoraTargets.cmake)
link_directories(${adora_link_dirs})
# Standalone node (executable)
add_executable(my_node node/main.cc ${node_bridge})
add_dependencies(my_node Adora_cxx)
target_include_directories(my_node PRIVATE ${adora_cxx_include_dir})
target_link_libraries(my_node adora_node_api_cxx)
# Operator (shared library)
add_library(my_operator SHARED
operator/operator.cc ${operator_bridge})
add_dependencies(my_operator Adora_cxx)
target_include_directories(my_operator PRIVATE
${adora_cxx_include_dir} ${adora_c_include_dir}
${CMAKE_CURRENT_SOURCE_DIR}/operator)
target_link_libraries(my_operator adora_operator_api_cxx)
install(TARGETS my_node DESTINATION ${CMAKE_CURRENT_SOURCE_DIR}/bin)
install(TARGETS my_operator DESTINATION ${CMAKE_CURRENT_SOURCE_DIR}/lib)
DoraTargets.cmake 提供的内容
| 变量 | 描述 |
|---|---|
adora_cxx_include_dir | 生成的 CXX 头文件路径(adora-node-api.h、adora-operator-api.h) |
adora_c_include_dir | C API 头文件路径(用于混合 C/C++ 项目) |
adora_link_dirs | libadora_node_api_cxx.a / libadora_operator_api_cxx.a 的库搜索路径 |
node_bridge | 为节点生成的 CXX 桥接源文件(node_bridge.cc) |
operator_bridge | 为算子生成的 CXX 桥接源文件(operator_bridge.cc) |
Adora_cxx | 构建 CXX crate 的 CMake 目标依赖 |
构建步骤
# Option A: Build against local Adora source
mkdir build && cd build
cmake .. -DDORA_ROOT_DIR=/path/to/adora
cmake --build .
# Option B: Build against Adora from GitHub (cloned automatically)
mkdir build && cd build
cmake ..
cmake --build .
要求
- C++20 编译器
- Rust 工具链(用于通过 Cargo 构建 Adora 静态库)
- CMake 3.21+
- Arrow 集成需要:Apache Arrow C++ 库
CXX 桥接注意事项
- 所有 Rust 不透明类型(
Events、OutputSender、AdoraEvent、Metadata、MergedEvents、MergedAdoraEvent)通过rust::Box<T>访问。 rust::String、rust::Vec<T>和rust::Slice<const T>是 CXX 桥接类型,与对应的 C++ 标准库类型互操作。参见 CXX 类型参考。- 在 Rust 中返回
Result<T>的函数在错误路径上抛出 C++ 异常。 - Arrow FFI 函数(
event_as_arrow_input、send_arrow_output)在 Rust 侧是unsafe的。调用者必须传递转换为uint8_t*的有效ArrowArray/ArrowSchema结构体指针。 - 节点库是静态归档(
staticlib)。使用-ladora_node_api_cxx将其链接到你的可执行文件。 - 算子库也是静态归档。使用
-ladora_operator_api_cxx将其链接到你的共享库。
Adora CLI 参考
Adora(AI-Dora,面向数据流的机器人架构)是一个 100% Rust 框架,用于构建实时机器人和 AI 应用。本文档从终端用户和开发者两个角度介绍 adora CLI。
目录
- 快速开始
- Installation
- 核心概念
- 数据流描述符
- 命令参考
- 环境变量
- 架构指南
- 编写节点
- 编写算子
- Distributed Deployments – see also Distributed Deployment Guide for cluster management, scheduling, and operations
- Troubleshooting
- 调试与可观测性 – 独立指南,涵盖录制/回放、主题检查、日志分析和资源监控
- API References: Rust | Python | C | C++
快速开始
# Create a new project
adora new my-robot --kind dataflow --lang rust
# Run locally (no coordinator/daemon needed)
adora run dataflow.yml
# Or use coordinator/daemon for production
adora up
adora start dataflow.yml --attach
# Ctrl-C to stop
adora down
安装
From crates.io (recommended)
cargo install adora-cli
从源码安装
cargo install --path binaries/cli --locked
验证
adora --version
adora status
核心概念
数据流
数据流是由类型化数据通道连接的节点有向图。节点产生输出,其他节点将其作为输入消费。框架负责数据路由、序列化(Apache Arrow)和生命周期管理。
执行模式
| 模式 | 命令 | 基础设施 | 用例 |
|---|---|---|---|
| 本地 | adora run | 无 | 开发、测试、单机 |
| 分布式 | adora up + adora start | 协调器 + 守护进程 | 生产、多机 |
组件角色
CLI --> Coordinator --> Daemon(s) --> Nodes / Operators
(control plane) (per machine) (user code)
- CLI:用户界面。发送命令、显示日志。
- 协调器:跨机器编排数据流生命周期。
- 守护进程:生成节点进程、管理 IPC、收集指标。
- 节点:产生和消费 Arrow 数据的独立进程。
- 算子:在共享运行时内运行的进程内代码(比节点更低延迟)。
数据格式
所有数据以 Apache Arrow 列式数组的形式在系统中流转。这使得同机节点间零拷贝共享内存传输和零序列化开销成为可能。
数据流描述符
数据流在 YAML 文件中定义。以下是完整的 schema:
最小示例
nodes:
- id: sender
path: sender.py
outputs:
- message
- id: receiver
path: receiver.py
inputs:
message: sender/message
完整模式
# Dataflow-level settings
health_check_interval: 5.0 # health check sweep interval in seconds (default: 5.0)
nodes:
- id: my-node # 唯一标识符(必填)
name: "My Node" # 人类可读名称(可选)
description: "..." # 描述(可选)
# --- Source (pick one) ---
path: ./target/debug/my-node # 本地可执行文件
# path: https://example.com/node.zip # 从 URL 下载
# git: https://github.com/org/repo.git # 从 git 构建
# branch: main # git 分支(与 tag/rev 互斥)
# tag: v1.0 # git 标签
# rev: abc123 # git 提交哈希
# --- Build ---
build: cargo build -p my-node # 构建用的 shell 命令(可选)
# --- Inputs ---
inputs:
# Short form: source_node/output_id
tick: adora/timer/millis/100
data: other-node/output
# Long form with options
sensor_data:
source: sensor/frames
queue_size: 10 # input buffer size (default: 10)
queue_policy: drop_oldest # or "backpressure" (buffers up to 10x queue_size)
input_timeout: 5.0 # circuit breaker timeout in seconds
# --- Outputs ---
outputs:
- processed
- status
# --- Environment ---
env:
MY_VAR: "value"
FROM_ENV:
__adora_env: HOST_VAR # 从宿主环境读取
args: "--verbose" # 命令行参数
# --- Fault tolerance ---
restart_policy: on-failure # never(默认)| on-failure | always
max_restarts: 5 # 0 = unlimited
restart_delay: 1.0 # initial backoff in seconds
max_restart_delay: 30.0 # backoff cap in seconds
restart_window: 300.0 # reset counter after N seconds
health_check_timeout: 30.0 # kill if no activity for N seconds
# --- Logging ---
min_log_level: info # 源级别过滤(守护进程端)
send_stdout_as: raw_output # 将原始标准输出路由为数据输出
send_logs_as: log_entries # 将结构化日志路由为数据输出
max_log_size: "50MB" # 达到此大小时轮转日志文件
max_rotated_files: 5 # number of rotated files to keep (1-100)
# --- Deployment ---
_unstable_deploy:
machine: A # 目标机器/守护进程 ID
# 调试设置
_unstable_debug:
publish_all_messages_to_zenoh: true # required for topic echo/hz/info
内置定时器节点
定时器是以固定间隔发出 tick 的虚拟节点:
inputs:
tick: adora/timer/millis/100 # 每 100ms
slow: adora/timer/millis/1000 # 每 1s
fast: adora/timer/hz/30 # 30 Hz(约 33ms)
算子节点
算子在共享运行时中进程内运行(无独立进程):
nodes:
# Single operator (shorthand)
- id: detector
operator:
python: detect.py
build: pip install -r requirements.txt
inputs:
image: camera/frames
outputs:
- bbox
# Multiple operators sharing a runtime
- id: runtime-node
operators:
- id: preprocessor
shared-library: ../../target/debug/libpreprocess
inputs:
raw: sensor/data
outputs:
- processed
- id: analyzer
shared-library: ../../target/debug/libanalyze
inputs:
data: runtime-node/preprocessor/processed
outputs:
- result
分布式部署
使用 _unstable_deploy 将节点分配到特定机器:
nodes:
- id: camera-driver
_unstable_deploy:
machine: robot-arm
path: ./target/debug/camera
outputs:
- frames
- id: ml-inference
_unstable_deploy:
machine: gpu-server
path: ./target/debug/inference
inputs:
frames: camera-driver/frames
outputs:
- predictions
当节点位于不同机器时,通信自动从共享内存切换到 Zenoh 发布/订阅。
命令参考
生命周期命令
adora run
在本地运行数据流,无需协调器或守护进程。适合开发和测试。
adora run <PATH> [OPTIONS]
| 参数/标志 | 默认 | 描述 |
|---|---|---|
<PATH> | 必需 | 数据流描述符 YAML 的路径 |
--stop-after <DURATION> | 在指定时间后自动停止(例如 30s、5m) | |
--uv | false | 使用 uv 进行 Python 节点管理 |
--debug | false | 启用调试主题(等同于 publish_all_messages_to_zenoh: true) |
--allow-shell-nodes | false | 启用基于 shell 的节点执行 |
--log-level <LEVEL> | stdout | 最低显示级别:error|warn|info|debug|trace|stdout |
--log-format <FORMAT> | pretty | 输出格式:pretty|json|compact |
--log-filter <FILTER> | 按节点级别覆盖:"node1=debug,node2=warn" |
Examples:
# Basic run
adora run dataflow.yml
# Stop after 10 seconds, only show warnings
adora run dataflow.yml --stop-after 10s --log-level warn
# Python dataflow with uv
adora run dataflow.yml --uv
# Debug one node, silence others
adora run dataflow.yml --log-level warn --log-filter "sensor=debug"
# JSON output for CI pipelines
adora run dataflow.yml --log-format json --stop-after 30s 2>test.json
adora up
在本地模式下启动协调器和守护进程。
adora up
以后台进程方式启动 adora coordinator 和 adora daemon。等待两者就绪后返回。幂等操作:如果已在运行,则不执行任何操作。
adora down(别名:adora destroy)
拆卸协调器和守护进程。首先停止所有运行中的数据流。
adora down [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
--coordinator-addr <IP> | 127.0.0.1 | 协调器地址 |
--coordinator-port <PORT> | 6013 | 协调器端口 |
adora build
运行数据流描述符中定义的构建命令。
adora build <PATH> [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<PATH> | 必需 | 数据流描述符路径 |
--uv | false | 使用 uv 构建 Python |
--local | false | 强制本地构建(跳过协调器) |
--strict-types | false | Treat type warnings as errors (non-zero exit code) |
Type checking: After expanding modules, build runs the same type checks as validate. Warnings are printed by default; use --strict-types (or set strict_types: true in the YAML) to fail the build on type mismatches. User-defined types in a types/ directory next to the dataflow are loaded automatically.
**构建策略:**如果节点有 _unstable_deploy 部分且协调器可达,构建将分发到目标机器。否则在本地构建。
**Git 源:**带有 git: 字段的节点在构建前会被克隆/更新。构建命令从 git 仓库根目录运行。
adora start
在运行中的协调器上启动数据流。
adora start <PATH> [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<PATH> | 必需 | 数据流描述符路径 |
--name <NAME>, -n | 为数据流指定名称 | |
--attach | auto | 附加到日志流并等待完成 |
--detach | auto | 启动后立即返回 |
--debug | false | 启用调试主题(等同于 publish_all_messages_to_zenoh: true) |
--hot-reload | false | 监视 Python 文件并在变更时重新加载 |
--uv | false | 使用 uv 管理 Python 节点 |
--coordinator-addr <IP> | 127.0.0.1 | 协调器地址 |
--coordinator-port <PORT> | 6013 | 协调器端口 |
如果既未指定 --attach 也未指定 --detach:在 TTY 中运行时附加,否则分离。
**附加模式:**流式输出日志,优雅处理 Ctrl-C(第一次 = 停止,第二次 = 强制终止)。
**热重载:**监视 Python 算子源文件。文件变更时,向协调器发送重载请求,协调器将其传播到守护进程。
adora stop
停止运行中的数据流。
adora stop [UUID_OR_NAME] [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
[UUID_OR_NAME] | interactive | 数据流 UUID 或名称 |
--name <NAME>, -n | 替代名称指定方式 | |
--grace-duration <DURATION> | 优雅关闭超时时间 | |
--force, -f | false | 立即终止 |
--coordinator-addr <IP> | 127.0.0.1 | 协调器地址 |
--coordinator-port <PORT> | 6013 | 协调器端口 |
如果未提供标识符且在 TTY 中运行,将显示交互式选择器。
**停止序列:**发送 Event::Stop -> 等待优雅关闭时间 -> SIGTERM -> 强制终止。
adora restart
重启运行中的数据流(停止 + 使用存储的描述符重新启动)。无需 YAML 路径 – 协调器保留了原始描述符。
adora restart [UUID] [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
[UUID] | 数据流 UUID | |
--name <NAME>, -n | 按名称而非 UUID 重启 | |
--grace-duration <DURATION> | 停止阶段的优雅关闭超时时间 | |
--force, -f | false | 重启前强制终止 |
--coordinator-addr <IP> | 127.0.0.1 | 协调器地址 |
--coordinator-port <PORT> | 6013 | 协调器端口 |
Examples:
# Restart by name
adora restart --name my-app
# Restart by UUID with forced stop
adora restart a1b2c3d4-... --force
adora record
将数据流消息录制到 .adorec 文件以供离线回放。完整工作流请参阅调试指南。
adora record <DATAFLOW_YAML> [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<DATAFLOW_YAML> | 必需 | 数据流描述符路径 |
-o, --output <PATH> | recording_{timestamp}.adorec | 输出文件路径 |
--topics <TOPICS> | all | 逗号分隔的 node/output 主题用于录制 |
--proxy | false | 通过 WebSocket 流式传输而非在目标机器上录制 |
--output-yaml <PATH> | 写入修改后的 YAML 但不运行(干运行) |
默认模式向数据流注入录制节点。--proxy 模式需要正在运行的数据流和 publish_all_messages_to_zenoh: true。
adora replay
通过将源节点替换为回放节点来回放录制的 .adorec 文件。完整工作流请参阅调试指南。
adora replay <FILE> [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<FILE> | 必需 | .adorec 录制文件路径 |
--speed <FLOAT> | 1.0 | 回放速度(0 = 最大速度) |
--loop | false | 循环播放录制 |
--replace <NODE_IDS> | 所有已录制的 | 逗号分隔的要替换的节点 |
--output-yaml <PATH> | 写入修改后的 YAML 但不运行(干运行) |
监控命令
adora list(别名:adora ps)
列出运行中的数据流及指标。
adora list [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
--format <FMT>, -f | table | 输出格式:table|json |
--status <STATUS> | 过滤:running|finished|failed | |
--name <PATTERN> | 按名称过滤(不区分大小写的子串匹配) | |
--sort-by <FIELD> | 排序:cpu|memory | |
--quiet, -q | false | 仅打印 UUID |
--coordinator-addr <IP> | 127.0.0.1 | 协调器地址 |
--coordinator-port <PORT> | 6013 | 协调器端口 |
输出列: UUID、Name、Status、Nodes、CPU、Memory
adora logs
显示和跟踪数据流与节点的日志。
adora logs [UUID_OR_NAME] [NODE] [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
[UUID_OR_NAME] | 数据流 UUID 或名称 | |
[NODE] | 节点名称(除非使用 --all-nodes,否则必填) | |
--all-nodes | false | 按时间戳合并所有节点的日志 |
--tail <N> | all | 显示最后 N 行 |
--follow, -f | false | 流式输出新日志条目 |
--local | false | 从本地 out/ 目录读取 |
--since <DURATION> | 显示指定时间之后的日志 | |
--until <DURATION> | 显示指定时间之前的日志 | |
--level <LEVEL> | stdout | 最低日志级别 |
--log-format <FORMAT> | pretty | 输出格式 |
--log-filter <FILTER> | 按节点级别覆盖 | |
--grep <PATTERN> | 不区分大小写的文本搜索 | |
--coordinator-addr <IP> | 127.0.0.1 | 协调器地址 |
--coordinator-port <PORT> | 6013 | 协调器端口 |
**过滤流水线:**读取/解析 -> 时间过滤 -> Grep -> Tail -> 显示
Examples:
# Follow all nodes live
adora logs my-dataflow --all-nodes --follow
# Last 50 errors from a specific node
adora logs my-dataflow sensor --level error --tail 50
# Search logs from last 5 minutes
adora logs my-dataflow --all-nodes --since 5m --grep "timeout"
# Read local files (no coordinator needed)
adora logs --local --all-nodes --tail 100
# Post-mortem analysis: errors in time window
adora logs --local sensor --since 1h --until 30m --level error
时间格式: 30(秒)、30s、5m、1h、2d
adora inspect top(别名:adora top)
节点资源使用的实时 TUI 监控器(类似 top)。
adora inspect top [OPTIONS]
adora top [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
--refresh-interval <SECONDS> | 2 | 更新间隔(最小值:1) |
--once | false | 打印单次 JSON 快照并退出(用于脚本/CI) |
--coordinator-addr <IP> | 127.0.0.1 | 协调器地址 |
--coordinator-port <PORT> | 6013 | 协调器端口 |
需要交互式终端(除非使用 --once)。
| Key | 动作 |
|---|---|
q / Esc | Quit |
Up / k | 选择上一个节点 |
Down / j | 选择下一个节点 |
n | 按节点名称排序 |
c | 按 CPU 排序 |
m | 按内存排序 |
r | 强制刷新 |
列: NODE、STATUS、DATAFLOW、PID、CPU%、MEMORY (MB)、RESTARTS、QUEUE、NET TX、NET RX、I/O READ (MB/s)、I/O WRITE (MB/s)
- STATUS:Running、Restarting、Degraded(输入中断)或 Failed
- RESTARTS:每个节点的当前重启次数
- QUEUE:节点输入队列中的待处理消息
- NET TX/RX:通过 Zenoh 跨守护进程发送/接收的累计网络字节数
CPU 值为单核百分比(多核情况下可超过 100%)。指标来自守护进程,因此适用于分布式部署。
脚本示例:
# JSON snapshot for CI/monitoring pipelines
adora top --once | jq '.[].cpu_usage'
adora topic list
列出运行中数据流的所有主题(输出)。
adora topic list [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
-d <DATAFLOW>, --dataflow | interactive | 数据流 UUID 或名称 |
--format <FMT> | table | 输出格式:table|json |
adora topic echo
订阅主题并实时显示消息。
adora topic echo [OPTIONS] [DATA...]
| 标志 | 默认 | 描述 |
|---|---|---|
-d <DATAFLOW>, --dataflow | 必需 | 数据流 UUID 或名称 |
[DATA...] | 所有输出 | 要回显的主题(例如 node1/output) |
--format <FMT> | table | 输出格式:table|json |
需要在描述符中设置 _unstable_debug.publish_all_messages_to_zenoh: true。
adora topic hz
使用 TUI 仪表盘测量主题发布频率。
adora topic hz [OPTIONS] [DATA...]
| 标志 | 默认 | 描述 |
|---|---|---|
-d <DATAFLOW>, --dataflow | 必需 | 数据流 UUID 或名称 |
[DATA...] | 所有输出 | 要测量的主题 |
--window <SECONDS> | 10 | 滑动窗口(最小值:1) |
**需要交互式终端。**显示:Avg (ms)、Avg (Hz)、Min (ms)、Max (ms)、Std (ms),以及所选主题的速率火花图和直方图。
adora topic info
显示单个主题的详细元数据。
adora topic info [OPTIONS] DATA
| 标志 | 默认 | 描述 |
|---|---|---|
-d <DATAFLOW>, --dataflow | 必需 | 数据流 UUID 或名称 |
DATA | 必需 | 单个主题(例如 camera/image) |
--duration <SECONDS> | 5 | 采集持续时间(最小值:1) |
订阅主题指定的持续时间并报告:类型(Arrow schema)、发布者、订阅者、消息计数、带宽。
adora node
管理和检查数据流节点。
adora node list
adora node list [OPTIONS]
列出运行中数据流的节点及其状态、CPU、内存和重启次数。
列: NODE、STATUS、PID、CPU%、MEMORY (MB)、RESTARTS、DATAFLOW
adora node info
Show detailed information about a specific node including status, inputs, outputs, and metrics.
adora node info <NODE> [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<NODE> | 必需 | Node ID to inspect |
-d <DATAFLOW>, --dataflow | interactive | 数据流 UUID 或名称 |
-f <FORMAT>, --format | table | 输出格式:table|json |
adora node restart
Restart a single node within a running dataflow. The daemon stops the node process and respawns it.
adora node restart <NODE> [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<NODE> | 必需 | Node ID to restart |
-d <DATAFLOW>, --dataflow | interactive | 数据流 UUID 或名称 |
--grace <DURATION> | Grace period before force-killing the node |
adora node stop
Stop a single node within a running dataflow without stopping the entire dataflow.
adora node stop <NODE> [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<NODE> | 必需 | Node ID to stop |
-d <DATAFLOW>, --dataflow | interactive | 数据流 UUID 或名称 |
--grace <DURATION> | Grace period before force-killing the node |
adora topic pub
Publish JSON data to a topic in a running dataflow. Requires publish_all_messages_to_zenoh: true.
adora topic pub <TOPIC> [DATA] [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<TOPIC> | 必需 | Topic to publish to (format: node_id/output_id) |
[DATA] | JSON data to publish (required unless --file) | |
--file <PATH> | Read data from a JSON file instead of command line | |
--count <N> | 1 | Number of messages to publish |
-d <DATAFLOW>, --dataflow | 必需 | 数据流 UUID 或名称 |
Examples:
# Publish a single value
adora topic pub -d my-app sensor/threshold '[42]'
# Publish from file, 10 times
adora topic pub -d my-app sensor/config --file config.json --count 10
adora param
Manage runtime parameters for nodes. Parameters are persisted in the coordinator store and optionally forwarded to running nodes.
adora param list
List all runtime parameters for a node.
adora param list <NODE> [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<NODE> | 必需 | 节点 ID |
-d <DATAFLOW>, --dataflow | interactive | 数据流 UUID 或名称 |
--format <FMT> | table | 输出格式:table|json |
adora param get
Get a single runtime parameter value.
adora param get <NODE> <KEY> [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<NODE> | 必需 | 节点 ID |
<KEY> | 必需 | Parameter key |
-d <DATAFLOW>, --dataflow | interactive | 数据流 UUID 或名称 |
adora param set
Set a runtime parameter. The value is JSON. The parameter is stored in the coordinator and forwarded to the node if it is running.
adora param set <NODE> <KEY> <VALUE> [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<NODE> | 必需 | 节点 ID |
<KEY> | 必需 | Parameter key (max 256 bytes) |
<VALUE> | 必需 | Parameter value as JSON (max 64KB serialized) |
-d <DATAFLOW>, --dataflow | interactive | 数据流 UUID 或名称 |
Examples:
# Set a numeric parameter
adora param set -d my-app sensor threshold 42
# Set a string parameter
adora param set -d my-app camera resolution '"1080p"'
# Set a complex parameter
adora param set -d my-app detector config '{"confidence": 0.8, "nms": 0.5}'
adora param delete
Delete a runtime parameter.
adora param delete <NODE> <KEY> [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<NODE> | 必需 | 节点 ID |
<KEY> | 必需 | Parameter key |
-d <DATAFLOW>, --dataflow | interactive | 数据流 UUID 或名称 |
adora doctor
Diagnose environment, coordinator/daemon connectivity, and optionally validate a dataflow YAML.
adora doctor [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
--dataflow <PATH> | Path to a dataflow YAML to validate |
Checks performed:
- Coordinator reachability
- Daemon connectivity
- Active dataflow status
- Dataflow YAML validation (if
--dataflowprovided)
Examples:
# Basic health check
adora doctor
# Check environment + validate a dataflow
adora doctor --dataflow dataflow.yml
adora trace list
列出协调器捕获的最近追踪。协调器在内存中捕获 adora_coordinator 和 adora_core crate 的 span(最多 4096 个 span)。无需外部追踪基础设施。
adora trace list [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
--coordinator-addr <IP> | 127.0.0.1 | 协调器地址 |
--coordinator-port <PORT> | 6013 | 协调器端口 |
输出列: TRACE ID(前 12 个字符)、ROOT SPAN、SPANS、STARTED、DURATION
Example:
adora trace list
TRACE ID ROOT SPAN SPANS STARTED DURATION
a1b2c3d4e5f6 spawn_dataflow 12 2026-03-01 10:30:05 1.234s
f8e7d6c5b4a3 build_dataflow 5 2026-03-01 10:29:58 0.500s
adora trace view
以缩进树形式查看特定追踪的 span。支持追踪 ID 的前缀匹配。
adora trace view <TRACE_ID> [OPTIONS]
| 参数/标志 | 默认 | 描述 |
|---|---|---|
<TRACE_ID> | 必需 | 完整追踪 ID 或唯一前缀 |
--coordinator-addr <IP> | 127.0.0.1 | 协调器地址 |
--coordinator-port <PORT> | 6013 | 协调器端口 |
Example:
adora trace view a1b2c3d4
spawn_dataflow [INFO 1.234s] {build_id="abc", session_id="def"}
build_dataflow [INFO 0.500s]
download_node [DEBUG 0.200s] {url="..."}
start_inner [INFO 0.734s]
spawn_node [INFO 0.100s] {node_id="camera"}
spawn_node [INFO 0.080s] {node_id="detector"}
追踪 ID 支持前缀匹配:如果前缀唯一标识一个追踪,则自动解析。如果有歧义,系统会提示您使用更长的前缀。
设置命令
adora status(别名:adora check)
检查系统健康状态和连接性。
adora status [OPTIONS]
报告协调器连接状态、守护进程状态和活跃数据流数量。
adora new
从模板生成新的项目或节点。
adora new <NAME> [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<NAME> | 必需 | 项目或节点名称 |
--kind <KIND> | dataflow | dataflow|node |
--lang <LANG> | rust | rust|python|c|cxx |
adora expand
Expand module references in a dataflow and print the resulting flat YAML. Useful for debugging module composition.
adora expand <PATH> [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<PATH> | 必需 | Dataflow descriptor (or module file with --module) |
--module | false | Validate a standalone module file instead of a full dataflow |
Examples:
# Expand a dataflow with modules
adora expand dataflow.yml
# Validate a module file
adora expand --module modules/navigation.module.yml
See the Modules Guide for full documentation on module composition.
adora graph
以图形方式可视化数据流。
adora graph <PATH> [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<PATH> | 必需 | 数据流描述符路径 |
--mermaid | false | 输出 Mermaid 图表文本 |
--open | false | 在浏览器中打开 HTML |
Without --mermaid, generates an interactive HTML file using mermaid.js. When outputs have type annotations, edge labels include the type name (e.g. image [Image]).
# Generate HTML
adora graph dataflow.yml --open
# Generate Mermaid for GitHub markdown
adora graph dataflow.yml --mermaid
adora validate
Validate a dataflow YAML file and check type annotations.
adora validate <PATH> [OPTIONS]
| 标志 | 默认 | 描述 |
|---|---|---|
<PATH> | 必需 | 数据流描述符路径 |
--strict-types | false | Treat warnings as errors (non-zero exit code for CI) |
Checks:
- Key existence:
output_types/input_typeskeys exist in the correspondingoutputs/inputslists - URN resolution: All type URNs resolve in the standard or user-defined type library
- Edge compatibility: Connected edges have compatible types (exact match, widening, or user-defined rules)
- Parameterized types: Parameter mismatches (e.g.
AudioFrame[sample_type=f32]vsAudioFrame[sample_type=i16]) - Timer auto-typing: Timer inputs are automatically typed as
std/core/v1/UInt64 - Type inference: When only upstream annotates a type, it is inferred on the downstream input
- Metadata patterns:
output_metadatakeys andpatternshorthands are validated - Schema compatibility: Struct types are checked at the field level (missing/wrong fields)
User-defined types in a types/ directory next to the dataflow are loaded automatically.
# Validate with warnings
adora validate dataflow.yml
# Strict mode for CI (exit 1 on warnings)
adora validate --strict-types dataflow.yml
See the Type Annotations Guide for the full type library and usage details.
实用命令
adora completion
生成 shell 补全脚本。
adora completion [SHELL]
省略时自动检测 shell。支持:bash、zsh、fish、elvish、powershell。
# Bash
eval "$(adora completion bash)"
echo 'eval "$(adora completion bash)"' >> ~/.bashrc
# Zsh
eval "$(adora completion zsh)"
echo 'eval "$(adora completion zsh)"' >> ~/.zshrc
# Fish
adora completion fish > ~/.config/fish/completions/adora.fish
adora system
系统管理命令。
adora system status [OPTIONS]
目前提供 status 作为子命令(等同于 adora status)。
自管理命令
adora self update
检查并安装 CLI 更新。
adora self update [--check-only]
从 GitHub releases(dora-rs/adora)下载。
adora self uninstall
从系统中移除 CLI。
adora self uninstall [--force]
不使用 --force 时,会提示确认(需要 TTY)。依次尝试 uv pip uninstall、pip uninstall,然后二进制自删除。
环境变量
所有环境变量作为备选值。CLI 标志始终优先。
| 变量 | 默认 | 命令 | 描述 |
|---|---|---|---|
ADORA_COORDINATOR_ADDR | 127.0.0.1 | 所有协调器命令 | 协调器 IP 地址 |
ADORA_COORDINATOR_PORT | 6013 | 所有协调器命令 | 协调器 WebSocket 端口 |
ADORA_LOG_LEVEL | stdout | run、logs | 默认最低日志级别 |
ADORA_LOG_FORMAT | pretty | run、logs | 默认输出格式 |
ADORA_LOG_FILTER | run、logs | 默认的按节点级别覆盖 | |
ADORA_ALLOW_SHELL_NODES | run | 启用 shell 节点执行 | |
ADORA_RUNTIME_TYPE_CHECK | run, start | Runtime type checking: warn (log mismatches) or error (fail on mismatch). See Type Annotations |
# Set defaults for a development session
export ADORA_COORDINATOR_ADDR=192.168.1.10
export ADORA_LOG_LEVEL=info
export ADORA_LOG_FORMAT=compact
架构指南
本节面向希望了解框架内部机制、扩展框架或调试问题的开发者。
通信栈
┌─────────────────────────────────────┐
│ CLI (adora) │
│ WebSocket (JSON request/reply) │
└─────────────┬───────────────────────┘
│
┌─────────────▼───────────────────────┐
│ Coordinator │
│ WebSocket control + daemon mgmt │
│ State: InMemoryStore | RedbStore │
└──┬──────────────────────────────┬───┘
│ │
┌────────────▼──────────┐ ┌─────────────▼──────────┐
│ Daemon A │ │ Daemon B │
│ (machine: robot) │ │ (machine: gpu-server) │
│ │ │ │
│ ┌─────┐ ┌─────┐ │ │ ┌──────┐ ┌───────┐ │
│ │Node1│ │Node2│ │ │ │Node3 │ │Node4 │ │
│ └──┬──┘ └──┬──┘ │ │ └──┬───┘ └───┬───┘ │
│ │shmem │shmem │ │ │shmem │shmem │
│ └────┬────┘ │ │ └─────┬─────┘ │
└──────────┼────────────┘ └───────────┼────────────┘
│ │
└──────── Zenoh pub/sub ────────┘
(cross-machine)
协议层
| 层级 | Transport | Format | Use |
|---|---|---|---|
| CLI <-> 协调器 | WebSocket | JSON(ControlRequest/Reply) | 命令、日志流 |
| 协调器 <-> 守护进程 | WebSocket | JSON(DaemonCoordinatorEvent) | 节点生命周期、指标 |
| 守护进程 <-> 节点(小消息) | TCP / Unix socket | 自定义二进制 | 控制消息、小数据 |
| 守护进程 <-> 节点(大消息) | 共享内存 | 零拷贝 Arrow | 数据消息 > 4KB |
| 守护进程 <-> 守护进程 | Zenoh 发布/订阅 | Arrow + 元数据 | 跨机器数据路由 |
协调器内部机制
协调器是一个事件驱动的异步服务器:
Event Sources:
- CLI WebSocket connections (ControlRequest)
- Daemon WebSocket connections (DaemonEvent)
- Heartbeat timer (3s interval)
- External events (for embedding)
Event Loop:
merge_all(cli_events, daemon_events, heartbeat, external)
-> handle_event()
-> update state
-> persist to store (if redb)
-> send replies
关键类型:
#![allow(unused)]
fn main() {
// State
RunningDataflow { uuid, name, descriptor, daemons, node_metrics, ... }
RunningBuild { build_id, errors, log_subscribers, pending_results, ... }
DaemonConnection { sender, pending_replies, last_heartbeat }
// Store trait
trait CoordinatorStore: Send + Sync {
fn put_dataflow(&self, record: &DataflowRecord) -> Result<()>;
fn get_dataflow(&self, uuid: &Uuid) -> Result<Option<DataflowRecord>>;
fn list_dataflows(&self) -> Result<Vec<DataflowRecord>>;
// ... daemon and build methods
}
}
存储后端:
memory(默认):内存存储,重启后丢失。redb:持久化到磁盘(~/.adora/coordinator.redb)。崩溃后可恢复。需要redb-backendfeature。
adora coordinator --store redb
adora coordinator --store redb:/custom/path.redb
守护进程内部机制
守护进程管理单台机器上的节点进程:
Per Node:
1. Build (if build command specified)
2. Spawn process with ADORA_NODE_CONFIG env var
3. Node registers via TCP/shmem handshake
4. Route inputs/outputs between nodes
5. Collect metrics (CPU, memory, I/O)
6. Handle restart policy on exit
7. Forward logs to coordinator
Communication:
- Shared memory for messages > 4KB (zero-copy)
- TCP for control messages and small data
- flume channels for internal event routing
指标采集:
#![allow(unused)]
fn main() {
struct NodeMetrics {
pid: u32,
cpu_usage: f32, // 单核百分比
memory_mb: f64,
disk_read_mb_s: Option<f64>,
disk_write_mb_s: Option<f64>,
status: NodeStatus, // Running | Restarting | Degraded | Failed
restart_count: u32,
pending_messages: u64,
}
}
消息类型
所有组件间消息定义在 libraries/message/ 中:
#![allow(unused)]
fn main() {
// 节点标识
struct NodeId(String); // [a-zA-Z0-9_.-]
struct DataId(String); // 相同验证
type DataflowId = uuid::Uuid;
// 数据元数据
struct Metadata {
timestamp: uhlc::Timestamp, // 混合逻辑时钟
type_info: ArrowTypeInfo, // Arrow schema
parameters: MetadataParameters, // 自定义键值对
}
// 节点事件(守护进程 -> 节点)
enum NodeEvent {
Stop,
Reload { operator_id },
Input { id, metadata, data },
InputClosed { id },
InputRecovered { id },
NodeRestarted { id },
AllInputsClosed,
}
}
时间戳
Adora 使用统一混合逻辑时钟(UHLC)实现分布式因果关系。每条消息携带一个 uhlc::Timestamp,无需同步时钟即可在跨机器间保持因果顺序。
零拷贝共享内存
对于大消息(> 4KB),守护进程使用共享内存区域:
- 发送节点向守护进程请求共享内存槽位
- 守护进程分配区域并返回 ID
- 发送方将 Arrow 数据直接写入共享内存
- 守护进程通知接收节点区域 ID
- 接收方直接从共享内存读取(零拷贝)
- 接收方完成后发送释放令牌
对于大数据载荷,这比 ROS2 实现了 10-17 倍的延迟降低。
编写节点
Rust 节点
use adora_node_api::{AdoraNode, Event, IntoArrow};
use adora_core::config::DataId;
fn main() -> eyre::Result<()> {
let (mut node, mut events) = AdoraNode::init_from_env()?;
let output = DataId::from("result".to_owned());
while let Some(event) = events.recv() {
match event {
Event::Input { id, metadata, data } => {
// 处理输入数据(Arrow 数组)
let result: u64 = 42;
node.send_output(
output.clone(),
metadata.parameters,
result.into_arrow(),
)?;
}
Event::Stop(_) => break,
Event::InputClosed { id } => {
eprintln!("input {id} closed");
}
Event::InputRecovered { id } => {
eprintln!("input {id} recovered");
}
_ => {}
}
}
Ok(())
}
Cargo.toml:
[dependencies]
adora-node-api = { workspace = true }
eyre = "0.6"
Python 节点
import pyarrow as pa
from adora import Node
node = Node()
for event in node:
if event["type"] == "INPUT":
# event["value"] is a PyArrow array
values = event["value"].to_pylist()
result = pa.array([sum(values)])
node.send_output("result", result)
elif event["type"] == "STOP":
break
C 节点
#include "node_api.h"
int main() {
void *ctx = init_adora_context_from_env();
// ... 使用 adora_next_event / adora_send_output 的事件循环
free_adora_context(ctx);
return 0;
}
节点日志
节点可以发出结构化日志:
Rust:
#![allow(unused)]
fn main() {
// 通过 tracing(推荐)
tracing::info!("processing frame {}", frame_id);
// 通过节点 API
node.log_info("processing complete");
node.log_with_fields("info", "reading", None, Some(&fields));
}
Python:
import logging
logging.info("processing frame %d", frame_id)
# Or via node API
node.log("info", "processing complete")
编写算子
算子在共享运行时内以进程内方式运行,避免了进程启动开销。
Rust 算子
#![allow(unused)]
fn main() {
use adora_operator_api::{register_operator, AdoraOperator, AdoraOutputSender, AdoraStatus, Event};
#[register_operator]
#[derive(Default)]
pub struct MyOperator {
counter: u32,
}
impl AdoraOperator for MyOperator {
fn on_event(
&mut self,
event: &Event,
output_sender: &mut AdoraOutputSender,
) -> Result<AdoraStatus, String> {
match event {
Event::Input { id, data } => {
self.counter += 1;
output_sender.send(
"count".to_string(),
arrow::array::UInt32Array::from(vec![self.counter]),
)?;
Ok(AdoraStatus::Continue)
}
Event::Stop => Ok(AdoraStatus::Stop),
_ => Ok(AdoraStatus::Continue),
}
}
}
}
Cargo.toml:
[lib]
crate-type = ["cdylib"]
[dependencies]
adora-operator-api = { workspace = true }
arrow = "53"
Python 算子
nodes:
- id: my-node
operator:
python: my_operator.py
inputs:
data: source/output
outputs:
- result
# my_operator.py
class Operator:
def __init__(self):
self.counter = 0
def on_event(self, event, send_output):
if event["type"] == "INPUT":
self.counter += 1
send_output("result", pa.array([self.counter]))
分布式部署
设置
# Machine A (coordinator + daemon)
adora up
# Machine B (daemon only, pointing to coordinator on Machine A)
adora daemon --interface 0.0.0.0 --coordinator-addr 192.168.1.10 --machine-id B
# Machine C (same)
adora daemon --interface 0.0.0.0 --coordinator-addr 192.168.1.10 --machine-id C
带机器分配的数据流
nodes:
- id: camera
_unstable_deploy:
machine: robot
path: ./camera-driver
outputs:
- frames
- id: inference
_unstable_deploy:
machine: gpu-server
path: ./ml-model
inputs:
frames: camera/frames
outputs:
- predictions
- id: actuator
_unstable_deploy:
machine: robot
path: ./actuator-driver
inputs:
commands: inference/predictions
构建和启动
# From any machine with coordinator access
adora build dataflow.yml # distributed build on target machines
adora start dataflow.yml --name my-robot --attach
监控
# Resource usage across all machines
adora top
# Logs from any node regardless of machine
adora logs my-robot inference --follow
# List all dataflows
adora list
协调器持久化
在生产环境中,使用 redb 存储后端以使协调器在重启后存续:
adora coordinator --store redb
状态持久化到 ~/.adora/coordinator.redb。重启时,过期的数据流会被标记为失败,协调器恢复正常运行。
For managed cluster deployments (cluster.yml, SSH-based lifecycle, label scheduling, systemd services, rolling upgrades), see the Distributed Deployment Guide.
故障排除
关于涵盖录制/回放工作流、主题检查、资源监控和端到端调试场景的综合调试指南,请参阅调试与可观测性指南。
常见问题
“Could not connect to adora-coordinator”
- 先运行
adora up,或检查ADORA_COORDINATOR_ADDR/ADORA_COORDINATOR_PORT - 使用
adora status验证
“publish_all_messages_to_zenoh not enabled”
-
使用
--debug标志:adora start dataflow.yml --debug或adora run dataflow.yml --debug -
或在数据流 YAML 中添加:
_unstable_debug: publish_all_messages_to_zenoh: true -
topic echo、topic hz、topic info需要此设置
“adora top requires an interactive terminal”
- 这些 TUI 命令需要真实终端(非管道输出)
- 同样适用于
topic hz
节点未接收到输入
- 检查输出名称是否匹配:
source_node/output_id - 验证源节点在其
outputs:数组中列出了该输出 - 使用
adora topic list检查可用主题
日志未显示
- 检查
--log-level设置(默认stdout显示所有内容) - 检查 YAML 中的
min_log_level(在源端过滤) - 分布式环境下:验证协调器/守护进程的连接性
使用 git 源构建失败
- 验证
git:URL 是否可访问 - 检查
branch、tag或rev是否存在 - 构建命令从 git 仓库根目录运行,而非数据流目录
调试工作流
# 1. Full environment diagnosis
adora doctor --dataflow dataflow.yml
# 2. Start with verbose logging and debug topics
adora run dataflow.yml --log-level trace --debug
# 3. Inspect a specific node
adora node info -d my-dataflow problem-node
# 4. Monitor specific node logs
adora logs my-dataflow problem-node --follow --level debug
# 5. Check resource usage
adora top
# 6. Inspect topic data
adora topic echo -d my-dataflow problem-node/output
# 7. Publish test data to a topic
adora topic pub -d my-dataflow problem-node/input '[1, 2, 3]'
# 8. Measure frequencies
adora topic hz -d my-dataflow --window 5
# 9. View/modify runtime parameters
adora param list -d my-dataflow problem-node
adora param set -d my-dataflow problem-node threshold 42
# 10. Restart a misbehaving node without stopping the dataflow
adora node restart -d my-dataflow problem-node
# 11. View coordinator traces (no external infra needed)
adora trace list
adora trace view <trace-id-prefix>
# 12. Visualize dataflow graph
adora graph dataflow.yml --open
日志文件位置
out/
<dataflow-uuid>/
log_<node-id>.jsonl # current log
log_<node-id>.1.jsonl # rotated (previous)
log_<node-id>.2.jsonl # rotated (older)
直接读取:
adora logs --local --all-nodes
adora logs --local <node-name> --tail 50
日志
Adora 为实时机器人和 AI 数据流提供结构化日志系统。日志按节点捕获为结构化 JSONL 文件,转发到协调器进行实时流式传输,并可选择性地通过数据流图作为数据消息路由。
Which Logging Approach Should I Use?
Start here if you’re unsure which approach fits your use case.
| I want to… | Approach | 配置 |
|---|---|---|
| Log from Python | Use Python’s logging module (auto-bridged) | Nothing – just import logging |
| Log from Rust | Use node.log_info() / node.log_error() etc. | Nothing – works out of the box |
| Log from C/C++ | Use adora_log() / log_message() | Nothing – works out of the box |
| Filter noisy nodes | Set min_log_level in YAML | Per-node YAML field |
| Watch all logs in one place | Subscribe to adora/logs virtual input | inputs: logs: adora/logs |
| Process one node’s logs as data | Use send_logs_as on that node | Per-node YAML + wire the output |
| Rotate log files | Set max_log_size in YAML | Per-node YAML field |
| Build a custom log sink | Use adora-log-utils crate | Rust dependency |
| Filter CLI display | Use --log-level / --log-filter flags | CLI flags or env vars |
Language-Specific Quick Start
Python – the simplest path is Python’s built-in logging module:
import logging
from adora import Node
node = Node() # Automatically bridges Python logging -> adora
logging.info("Sensor started") # Captured as structured "info" log
logging.warning("High temp: 42C") # Captured as structured "warn" log
print("raw debug output") # Captured as "stdout" level
When Node() is created, it installs a handler that routes all Python logging calls through Rust’s tracing system. The daemon parses these as structured log entries with level, message, file, and line number. No extra configuration needed.
You can also use the explicit API for structured fields:
node.log_info("Reading acquired")
node.log("info", "Reading acquired", fields={"sensor_id": "temp-01"})
Rust – use the node API convenience methods:
#![allow(unused)]
fn main() {
let (node, mut events) = AdoraNode::init_from_env()?;
// Convenience methods (recommended for most cases)
node.log_info("Sensor started");
node.log_warn("High temperature");
// With structured fields
let mut fields = BTreeMap::new();
fields.insert("sensor_id".into(), "temp-01".into());
node.log_with_fields("info", "Reading acquired", None, Some(&fields));
}
Alternatively, Rust nodes can use the tracing crate. When adora’s tracing subscriber is initialized (via init_tracing()), tracing::info!() etc. output structured JSON to stdout, which the daemon parses automatically:
#![allow(unused)]
fn main() {
// Also works -- parsed as structured logs by the daemon
tracing::info!("Sensor started");
tracing::warn!(sensor_id = "temp-01", "High temperature");
}
Use node.log_*() when you want explicit control over the log format. Use tracing::*!() when you want ecosystem integration (spans, instrumentation, OpenTelemetry). Both produce identical structured log entries in the daemon.
C – use the adora_log() function:
adora_log(ctx, "info", 4, "Sensor started", 14);
C++ – use the log_message() function:
log_message(node.send_output, "info", "Sensor started");
功能一览
| 特性 | 范围 | 配置 |
|---|---|---|
| 日志级别过滤 | CLI 显示 | --log-level、ADORA_LOG_LEVEL |
| 输出格式 | CLI 显示 | --log-format、ADORA_LOG_FORMAT |
| 按节点级别覆盖 | CLI 显示 | --log-filter、ADORA_LOG_FILTER |
| 源级别过滤 | 按节点 YAML | min_log_level |
| 标准输出转数据路由 | 按节点 YAML | send_stdout_as |
| 结构化日志路由 | 按节点 YAML | send_logs_as |
| 日志文件轮转 | 按节点 YAML | max_log_size |
| 轮转文件限制 | 按节点 YAML | max_rotated_files |
| 节点日志 API | Rust/Python/C/C++ 节点 | node.log()、adora_log() 等 |
| 日志工具库 | Rust crate | adora-log-utils |
| Log aggregation | Dataflow input | adora/logs virtual input |
| 时间范围过滤 | adora logs | --since、--until |
| 实时日志流 | adora logs | --follow |
| 文本搜索 | adora logs | --grep |
| 本地日志读取 | adora logs | --local、--all-nodes |
日志文件格式
每个节点在以下路径生成一个 JSONL 文件(每行一个 JSON 对象):
<working_dir>/out/<dataflow_uuid>/log_<node_id>.jsonl
每行具有以下结构:
{
"timestamp": "2024-01-15T10:30:00.123Z",
"level": "info",
"node_id": "sensor",
"message": "Starting sensor...",
"target": "sensor::module",
"fields": { "key": "value" }
}
| Field | 类型 | 描述 |
|---|---|---|
timestamp | string | RFC3339 时间戳,精确到毫秒 |
level | string | "error"、"warn"、"info"、"debug"、"trace" 或 "stdout" |
node_id | string | 节点 ID |
message | string | 日志消息文本 |
target | string? | Rust 模块目标(例如 "sensor::module"),缺失时为 null |
fields | object? | Structured key-value fields from the logging framework. Trust model: fields originate from node stdout and are passed through without sanitization. In mixed-trust environments, log consumers should validate field contents before acting on them |
节点输出如何变为日志条目
守护进程捕获节点进程的每行 stdout/stderr 并尝试将其解析为结构化日志消息(包含 level、message、timestamp 和可选 fields 的 JSON)。解析成功时保留结构化字段。解析失败时,原始行变为 "stdout"-level 条目。
这意味着使用 Rust 的 tracing 或 log crate 并输出 JSON 的节点会自动获得完整的结构化日志。仅使用 println! 的节点则产生 "stdout"-level 条目。
查看日志:adora run
使用 adora run 运行数据流时,所有节点的日志会在终端上实时显示。
Flags
adora run dataflow.yml [OPTIONS]
| 标志 | 默认 | 环境变量 | 描述 |
|---|---|---|---|
--log-level LEVEL | stdout | ADORA_LOG_LEVEL | 最低显示级别 |
--log-format FORMAT | pretty | ADORA_LOG_FORMAT | 输出格式:pretty、json、compact |
--log-filter FILTER | none | ADORA_LOG_FILTER | 按节点级别覆盖 |
日志级别
从最详细到最简洁:
| Level | 描述 |
|---|---|
stdout | 包括节点原始 stdout 在内的所有内容(默认) |
trace | 细粒度诊断消息 |
debug | 开发者级别诊断消息 |
info | 一般信息消息 |
warn | 警告条件 |
error | 仅错误条件 |
设置 --log-level info 会隐藏 stdout、trace 和 debug 消息。stdout 级别是一个特殊的全通级别,放行所有内容。
级别过滤逻辑
级别过滤使用 LogLevelOrStdout::passes():
Message level Filter level Displayed?
───────────── ──────────── ──────────
stdout stdout yes
stdout info no (stdout only passes stdout filter)
info stdout yes (any log level passes stdout filter)
debug info no (debug is more verbose than info)
error info yes (error is less verbose than info)
按节点覆盖
--log-filter 标志允许您为不同节点设置不同级别:
adora run dataflow.yml --log-level info --log-filter "sensor=debug,planner=warn"
这会为所有节点显示 info 及以上级别,但 sensor(显示 debug 及以上)和 planner(显示 warn 及以上)除外。
格式:"node1=level,node2=level"(逗号分隔的 name=level 对)。
输出格式
Pretty(默认)– 彩色、人类可读:
10:30:00 INFO sensor: Starting sensor...
10:30:01 INFO [adora]: spawning node processor
10:30:01 stdout sensor: raw output line
- 本地时区的时间戳(
HH:MM:SS) - 级别着色:ERROR(红色)、WARN(黄色)、INFO(绿色)、DEBUG(蓝色)、TRACE(暗色)、stdout(斜体暗蓝)
- 节点名称加粗并根据名称显示唯一颜色
- 系统消息以
[adora]为前缀 - 生命周期消息(
spawning、node finished、stopping)通过空行进行视觉分隔
Json – 完整的 LogMessage 结构体输出为 JSON,每行一条:
{"build_id":null,"dataflow_id":"abc-123","node_id":"sensor","level":"INFO","message":"Starting...","timestamp":"2024-01-15T10:30:00Z",...}
适用于通过管道传递给 jq 或导入日志聚合系统。
Compact – 精简,无色彩:
10:30:00 INFO sensor: Starting sensor...
适用于 CI/CD 环境和日志文件。
查看日志:adora logs
读取历史日志或从运行中的数据流实时流式传输日志。
基本用法
# Read logs for a specific node (via coordinator)
adora logs <dataflow_uuid> <node_name>
# Read local log files directly
adora logs --local <node_name>
adora logs --local --all-nodes
# Stream live logs
adora logs <dataflow_uuid> <node_name> --follow
adora logs --local <node_name> --follow
Flags
| 标志 | Short | 默认 | 描述 |
|---|---|---|---|
--local | false | 从本地 out/ 目录读取而非从协调器 | |
--all-nodes | false | 合并所有节点的日志,按时间戳排序 | |
--tail N | -n | all | 仅显示最后 N 行 |
--follow | -f | false | 在新日志条目到达时实时流式输出 |
--since DURATION | none | 仅显示指定时间之后的日志 | |
--until DURATION | none | 仅显示指定时间之前的日志 | |
--level LEVEL | stdout | 最低日志级别(环境变量:ADORA_LOG_LEVEL) | |
--grep PATTERN | none | 不区分大小写的文本搜索 | |
--coordinator-addr IP | 127.0.0.1 | 协调器地址 | |
--coordinator-port PORT | default | 协调器控制端口 |
时间过滤
--since 和 --until 接受相对于当前时间的持续时间字符串:
# Logs from the last 5 minutes
adora logs --local sensor --since 5m
# Logs from 1 hour ago to 30 minutes ago
adora logs --local sensor --since 1h --until 30m
# Last 10 errors from the past hour
adora logs --local sensor --since 1h --level error --tail 10
支持的时间格式:30(秒)、30s、5m、1h、2d。
文本搜索
--grep 对以下内容执行不区分大小写的子串匹配:
- 日志消息文本
- 节点 ID
- 模块目标
# Find all timeout-related messages
adora logs --local --all-nodes --grep "timeout"
# Find errors from a specific module
adora logs --local sensor --grep "camera::driver" --level error
过滤流水线
所有过滤器按以下顺序应用:
Read/Parse -> Time Filters -> Grep -> Tail -> Display
在协调器模式下使用 --since、--until 或 --grep 时,CLI 从服务器获取所有日志(忽略服务端的 --tail)并在客户端应用所有过滤器。这确保了组合使用过滤器时结果的正确性。
本地模式 vs 协调器模式
本地模式(--local)直接从当前工作目录的 out/ 目录读取 JSONL 文件。无需运行协调器或守护进程。如果使用 --all-nodes 或未指定节点名称,所有日志文件将合并并按时间戳排序。
协调器模式(默认)通过 WebSocket 连接到运行中的协调器。协调器从守护进程的工作目录读取日志文件并将其回传。适用于本地和分布式部署。
跟踪模式
本地跟踪(--local --follow):每 200ms 轮询日志文件获取新内容。新行被解析、经 --grep 过滤后打印。时间/尾部过滤器仅应用于初始历史输出。
协调器跟踪(--follow):向协调器打开 WebSocket 订阅。协调器实时转发守护进程的日志消息。级别过滤在服务端应用以提高效率。--grep 和 --since 在客户端对流应用。
环境变量
所有环境变量作为备选值 – CLI 标志始终优先。
| 变量 | 使用者 | Values | 描述 |
|---|---|---|---|
ADORA_LOG_LEVEL | adora run、adora logs | error、warn、info、debug、trace、stdout | 默认最低日志级别 |
ADORA_LOG_FORMAT | adora run | pretty、json、compact | 默认输出格式 |
ADORA_LOG_FILTER | adora run | "node1=level,node2=level" | 默认的按节点覆盖 |
ADORA_QUIET | daemon | 任意值 | 抑制日志转发显示(文件写入继续) |
Example:
# Set defaults for a development session
export ADORA_LOG_LEVEL=info
export ADORA_LOG_FORMAT=pretty
export ADORA_LOG_FILTER="sensor=debug"
# These are equivalent:
adora run dataflow.yml
adora run dataflow.yml --log-level info --log-format pretty --log-filter "sensor=debug"
# CLI flag overrides env var:
adora run dataflow.yml --log-level debug # overrides ADORA_LOG_LEVEL=info
YAML 配置
min_log_level
在日志到达日志文件、协调器或 send_logs_as 路由之前,在源端(守护进程端)过滤日志。
nodes:
- id: noisy-sensor
path: ./target/debug/sensor
min_log_level: info # 抑制此节点的 debug/trace/stdout
有效值:error、warn、info、debug、trace、stdout。
设置后,守护进程在解析后立即丢弃低于此级别的日志消息。这减少了磁盘 I/O、网络流量和日志文件大小。过滤使用与 CLI 显示过滤器相同的 passes() 逻辑。
send_stdout_as
将原始 stdout/stderr 行路由为数据流输出消息。
nodes:
- id: legacy-node
path: ./legacy-script.py
send_stdout_as: raw_output
outputs:
- raw_output
- data
- id: log-consumer
inputs:
logs: legacy-node/raw_output
每行 stdout/stderr 作为 Arrow 编码的字符串发送。这对于集成在 stdout 上输出数据的旧节点很有用(例如使用 print() 的 Python 脚本)。
send_stdout_as 和正常日志文件写入同时进行 – stdout 路由不会抑制日志文件。
send_logs_as
将解析的结构化日志条目路由为数据流输出消息。
nodes:
- id: sensor
path: ./target/debug/sensor
send_logs_as: log_entries
outputs:
- data
- log_entries
- id: log-aggregator
inputs:
sensor_logs: sensor/log_entries
与 send_stdout_as 不同,这仅发送成功解析为结构化日志的行(非原始 stdout)。每个条目序列化为完整的 JSON LogMessage 字符串。min_log_level 过滤器在路由前应用 – 被抑制的消息不会发送。
使用此功能在数据流内部构建日志聚合、告警或监控节点。
adora/logs – Automatic Log Aggregation
Subscribe to logs from all nodes with a single input line – no manual wiring needed:
nodes:
- id: sensor
path: sensor.py
inputs:
tick: adora/timer/millis/200
outputs:
- reading
- id: processor
path: processor.py
inputs:
reading: sensor/reading
outputs:
- result
- id: log-viewer
path: log_viewer.py
inputs:
logs: adora/logs # all nodes, all levels
errors: adora/logs/error # only error+ from all nodes
sensor: adora/logs/info/sensor # info+ from one node
The adora/logs virtual input works like adora/timer – the daemon handles subscription internally. Each log message arrives as a JSON-encoded LogMessage string in an Arrow array. To prevent infinite loops, a node never receives its own log messages.
Syntax:
| Input | 描述 |
|---|---|
adora/logs | All logs from all nodes |
adora/logs/<level> | Logs at <level> or above from all nodes |
adora/logs/<level>/<node-id> | Logs at <level> or above from a specific node |
Levels: stdout, error, warn, info, debug, trace.
When to use adora/logs vs send_logs_as:
adora/logs | send_logs_as | |
|---|---|---|
| 范围 | All nodes at once | One node at a time |
| YAML changes | Only the consumer | Each source node |
| Adding a node | Zero wiring changes | Must update consumer |
| 用例 | Dashboard, monitoring | Per-node log processing |
See examples/log-aggregator/ for a complete working example.
max_log_size
启用基于大小的日志文件轮转。
nodes:
- id: sensor
path: ./target/debug/sensor
max_log_size: "50MB"
| 值 | Bytes |
|---|---|
"1KB" 或 "1K" | 1,024 |
"50MB" 或 "50M" | 52,428,800 |
"1GB" 或 "1G" | 1,073,741,824 |
"1000" | 1,000(纯数字 = 字节) |
当活动日志文件超过配置大小时,守护进程会:
- 刷新并关闭当前文件
- 重命名现有轮转文件:
.4.jsonl->.5.jsonl、.3.jsonl->.4.jsonl等 - 重命名当前文件:
log_sensor.jsonl->log_sensor.1.jsonl - 创建新的
log_sensor.jsonl - 删除超出轮转限制的文件(默认 5,可通过
max_rotated_files配置)
命名约定:
log_sensor.jsonl # current (active)
log_sensor.1.jsonl # previous
log_sensor.2.jsonl # older
log_sensor.3.jsonl
log_sensor.4.jsonl
log_sensor.5.jsonl # oldest (deleted on next rotation)
每个节点的最大磁盘使用量:max_log_size * (1 + max_rotated_files)(1 个活动文件 + N 个轮转文件)。
没有 max_log_size 时,日志文件会无限增长。对于长时间运行的数据流,请始终设置此项。
adora logs --local 命令自动读取节点的所有轮转文件并按时间顺序合并(最旧的轮转文件在前,当前文件在后)。
max_rotated_files
控制保留多少个轮转日志文件(默认:5,范围:1-100)。
nodes:
- id: sensor
path: ./target/debug/sensor
max_log_size: "50MB"
max_rotated_files: 10 # keep 10 rotated files instead of 5
当 max_rotated_files: 10 且 max_log_size: "50MB" 时,每个节点最大磁盘使用量为 50MB * 11 = 550MB。较低的值节省磁盘空间;较高的值保留更多历史记录。
运行时节点限制
对于运行时节点(算子),每个运行时只允许每个日志字段有一个:
# OK -- single operator
nodes:
- id: runtime-node
operator:
python: process.py
send_logs_as: logs
min_log_level: info
max_log_size: "100MB"
# ERROR -- 多个算子具有冲突的配置
nodes:
- id: runtime-node
operators:
- id: op1
python: a.py
send_logs_as: logs1
- id: op2
python: b.py
send_logs_as: logs2 # Error: multiple send_logs_as
当运行时中的单个算子设置这些字段时,输出名称以算子 ID 为前缀(例如 op1/logs)。
节点日志 API
节点可以使用节点 API 以编程方式发出结构化日志消息。这等同于将 JSON 格式的日志行写入 stdout – 守护进程以相同方式解析。
Rust
#![allow(unused)]
fn main() {
use adora_node_api::AdoraNode;
use std::collections::BTreeMap;
let (node, mut events) = AdoraNode::init_from_env()?;
// 指定级别字符串和可选目标的通用日志
node.log("info", "sensor initialized", Some("sensor::init"));
// 便捷方法(无 target 参数)
node.log_error("connection failed");
node.log_warn("temperature elevated");
node.log_info("reading acquired");
node.log_debug("raw bytes received");
node.log_trace("entering loop iteration");
// 结构化字段(键值上下文通过 send_logs_as 保留)
let mut fields = BTreeMap::new();
fields.insert("sensor_id".to_string(), "temp-01".to_string());
fields.insert("reading".to_string(), "42.5".to_string());
node.log_with_fields("info", "reading acquired", None, Some(&fields));
}
level 参数接受 "error"、"warn"(或 "warning")、"info"、"debug"、"trace"。未知级别默认为 "info"。字段总量上限为 60 KB,以匹配下游 64 KB 的解析限制。
Python
Python nodes have three ways to log, all producing structured log entries:
from adora import Node
import logging
node = Node()
# Option 1: Python's logging module (recommended -- auto-bridged by Node())
logging.info("sensor initialized")
logging.warning("temperature elevated")
logging.debug("raw bytes: %s", data)
# Option 2: Explicit adora API with level string
node.log("info", "sensor initialized", target="sensor.init")
node.log("info", "reading acquired", fields={"sensor_id": "temp-01", "reading": "42.5"})
# Option 3: Convenience methods
node.log_error("connection failed")
node.log_warn("temperature elevated")
node.log_info("reading acquired")
node.log_debug("raw bytes received")
node.log_trace("entering loop iteration")
# This also works but produces "stdout"-level entries (no structure):
print("raw output")
How the Python logging bridge works: When Node() is created, it installs a custom logging.Handler that routes all Python logging calls through Rust’s tracing system. The daemon parses these as structured log entries with level, message, file path, and line number. This happens automatically – no configuration needed.
| 方法 | Structured? | Fields support? | When to use |
|---|---|---|---|
logging.info() | 是 | No (use extra= for custom formatters) | General-purpose logging |
node.log("info", msg, fields={...}) | 是 | 是 | When you need structured key-value context |
node.log_info(msg) | 是 | 否 | Quick one-liner, same as node.log("info", msg) |
print() | No (stdout level) | 否 | Legacy code, quick debugging |
Common pitfall: Do not call logging.basicConfig() before creating Node(). The node constructor sets up the logging bridge; calling basicConfig() first may install a conflicting handler. If you need custom formatters, configure them after Node() creation.
C
#include "node_api.h"
void *ctx = init_adora_context_from_env();
const char *level = "info";
const char *msg = "sensor initialized";
adora_log(ctx, level, strlen(level), msg, strlen(msg));
C++
// 通过 cxx bridge
auto node = init_adora_node();
log_message(node.send_output, "info", "sensor initialized");
日志工具库(adora-log-utils)
adora-log-utils crate 提供解析、合并、过滤和格式化工具,用于在自定义 sink 节点中处理 LogMessage 条目。在构建通过 send_logs_as 消费日志数据的节点时使用。
API
#![allow(unused)]
fn main() {
use adora_log_utils;
// 从 JSON 解析 LogMessage(从 send_logs_as 接收)
let log = adora_log_utils::parse_log(json_str)?;
// 直接从 Arrow 输入数据解析(事件处理器的便捷方法)
let log = adora_log_utils::parse_log_from_arrow(&data)?;
// 将多个日志流合并为单一时间线
let merged = adora_log_utils::merge_by_timestamp(vec![stream_a, stream_b]);
// 按最低级别过滤
let errors = adora_log_utils::filter_by_level(&logs, &min_level);
// 格式化为 JSON(单行,无尾部换行)
let json = adora_log_utils::format_json(&log);
// 格式化为紧凑单行:"<timestamp> <node> <LEVEL>: <message>"
let compact = adora_log_utils::format_compact(&log);
// 格式化为美观输出:"[<timestamp>][<LEVEL>][<node>] <message>"
let pretty = adora_log_utils::format_pretty(&log);
}
Dependency
添加到 sink 节点的 Cargo.toml:
[dependencies]
adora-log-utils = { workspace = true }
日志 Sink 示例
三个示例 sink 节点演示如何消费通过 send_logs_as 路由的日志并转发到外部目的地。
文件 Sink(examples/log-sink-file/)
将多个节点的日志流合并为单个 JSONL 文件。适用于统一日志收集。
nodes:
- id: sensor
path: sensor.py
send_logs_as: log_entries
inputs:
tick: adora/timer/millis/200
outputs:
- reading
- log_entries
- id: processor
path: processor.py
send_logs_as: log_entries
inputs:
reading: sensor/reading
outputs:
- result
- log_entries
- id: file_sink
path: log-sink-file
inputs:
sensor_logs: sensor/log_entries
processor_logs: processor/log_entries
env:
LOG_FILE: "./combined.jsonl"
文件 sink 从环境变量读取 LOG_FILE(默认 ./combined.jsonl),使用 adora_log_utils::parse_log_from_arrow() 解析每条传入的 Arrow 消息,格式化为 JSON 并追加到文件。
TCP Sink(examples/log-sink-tcp/)
通过 TCP 套接字将日志条目转发到远程日志收集器。适用于缺少本地文件系统且需要将日志流式传输到设备外的嵌入式系统。
nodes:
- id: source
path: source.py
send_logs_as: log_entries
inputs:
tick: adora/timer/millis/500
outputs:
- data
- log_entries
- id: tcp_sink
path: log-sink-tcp
inputs:
logs: source/log_entries
env:
SINK_ADDR: "127.0.0.1:9876"
TCP sink 从环境变量读取 SINK_ADDR(默认 127.0.0.1:9876),启动时连接到服务器,并将每条日志条目作为 JSON 行发送。写入失败时自动重连。
告警路由器(examples/log-sink-alert/)
按严重程度拆分传入的日志条目。所有日志转发到 all_logs 输出;仅 error 和 warn 日志转发到 alerts 输出。这使下游节点能够差异化处理告警(例如触发通知、写入专用文件)。
nodes:
- id: source
path: my_node.py
send_stdout_as: log_entries
inputs:
tick: adora/timer/millis/200
outputs:
- log_entries
- id: alert_router
path: log-sink-alert
inputs:
logs: source/log_entries
outputs:
- all_logs
- alerts
源节点使用 send_stdout_as 将其 stdout 行路由为 Arrow 字符串数据。路由器使用 adora_log_utils::parse_log_from_arrow() 解析每条日志条目,检查级别,并使用 node.send_output() 将数据转发到相应输出。使用节点 API 的节点也可以使用 send_logs_as 来路由 node.log() 的结构化日志。
构建自定义 Sink
要构建自己的 sink 节点,请遵循以下模式:
use adora_node_api::{AdoraNode, Event};
fn main() -> eyre::Result<()> {
let (_node, mut events) = AdoraNode::init_from_env()?;
while let Some(event) = events.recv() {
match event {
Event::Input { data, .. } => {
let log = adora_log_utils::parse_log_from_arrow(&data)?;
// 处理日志条目:写入文件、通过网络发送等
let json = adora_log_utils::format_json(&log);
println!("{json}");
}
Event::Stop(_) => break,
_ => {}
}
}
Ok(())
}
守护进程如何处理日志
理解内部流水线有助于调试和调优。守护进程为每个节点运行一个专用的异步任务,按顺序处理日志行:
Node Process (stdout/stderr)
|
v
[1] Capture: lines buffered in mpsc channel (capacity 100)
|
v
[2] send_stdout_as: raw line -> Arrow data -> dataflow output
|
v
[3] Parse: try JSON structured log, fall back to Stdout-level
|
v
[4] min_log_level filter: drop messages below threshold
|
v
[5] send_logs_as: LogMessage -> JSON -> Arrow data -> dataflow output
|
v
[6] Write JSONL: compact format to log file, track bytes written
|
v
[7] Rotation check: if bytes_written >= max_log_size, rotate files
|
v
[8] Forward: send LogMessage to display channel (unless ADORA_QUIET)
|
v
[9] Sync: fsync log file to disk
关键细节:
- 步骤 2 在解析之前发生,因此
send_stdout_as捕获每一行包括非结构化输出 - 步骤 4 在步骤 5-8 之前发生,因此
min_log_level会抑制所有下游处理的消息 - 步骤 5 仅对成功解析的结构化日志触发(步骤 3 成功路径)
- 步骤 8 发送到 flume 通道(
adora run直接模式)或协调器(分布式模式) - 步骤 9 每次写入后调用
sync_all(),以一定的 I/O 开销为代价确保持久性
结构化日志解析
当节点发出 JSON 格式的日志输出(例如使用 JSON 格式化的 tracing-subscriber)时,守护进程提取:
level:日志严重程度message:日志文本target:模块路径timestamp:日志发出时间fields:任意键值对build_id、dataflow_id、node_id、daemon_id:作为后备从字段中提取
守护进程还会在所有消息上设置 dataflow_id、node_id 和 daemon_id,以确保它们始终存在于日志文件中。
协调器日志流协议
当守护进程在协调器下运行(分布式模式)时,日志转发通过 WebSocket 工作:
- 守护进程 -> 协调器:每条
LogMessage被封装在DaemonEvent::Log(message)中并通过守护进程的 WebSocket 连接发送 - 协调器存储:协调器存储/转发日志
- CLI 订阅:CLI 通过其 WebSocket 连接发送
ControlRequest::LogSubscribe { dataflow_id, level } - 服务端过滤:协调器仅转发
msg_level <= subscription_level的消息。这减少了过滤订阅的网络流量 - CLI 接收:消息作为序列化的
LogMessage结构体到达
--level 标志映射到 log::LevelFilter:
stdout->LevelFilter::Trace(最宽松,接收所有内容)info->LevelFilter::Info(接收 Error、Warn、Info)- etc.
完整 YAML 参考
nodes:
- id: sensor
path: ./target/debug/sensor
outputs:
- data
- raw_output # 用于 send_stdout_as
- log_entries # 用于 send_logs_as
# Source-level log filtering (daemon-side)
min_log_level: info # 抑制 debug/trace/stdout
# Route stdout to dataflow
send_stdout_as: raw_output # 每行 stdout 变为数据消息
# Route structured logs to dataflow
send_logs_as: log_entries # 解析的日志条目变为数据消息
# Log file rotation
max_log_size: "50MB" # 文件超过 50MB 时轮转
max_rotated_files: 5 # keep 5 rotated files (default, range 1-100)
inputs:
tick: adora/timer/millis/100
完整示例
examples/python-logging/ 目录包含一个可运行的三节点流水线,演练了每个日志功能:
sensor (noisy, high-volume) --> processor (structured logs) --> monitor (log aggregator)
数据流配置要点:
nodes:
- id: sensor
path: sensor.py
min_log_level: info # 在源端抑制 debug 噪声
max_log_size: "1KB" # 演示用小值(快速触发轮转)
inputs:
tick: adora/timer/millis/50
outputs:
- reading
- id: processor
path: processor.py
send_logs_as: log_entries # 将结构化日志路由为数据
inputs:
reading: sensor/reading
outputs:
- result
- log_entries
- id: monitor
path: monitor.py
inputs:
logs: processor/log_entries
reading: sensor/reading
每个节点演示的内容:
- sensor – 混合使用
print()(原始 stdout)、logging.info()、logging.debug()和logging.warning()。设置min_log_level: info后,debug 消息在到达日志文件前被守护进程丢弃。设置max_log_size: "1KB"后,几秒钟后日志轮转开始。 - processor – 使用
send_logs_as: log_entries将其结构化日志条目路由为数据流数据。原始print()输出_不_会被路由(仅路由解析后的结构化条目)。 - monitor – 订阅
processor/log_entries并统计警告/错误,演示数据流内日志聚合。
直接模式(adora run – 单进程,适合快速测试):
# Basic run
adora run examples/python-logging/dataflow.yml --stop-after 5s
# Only warnings and above
adora run examples/python-logging/dataflow.yml --log-level warn --stop-after 5s
# Per-node overrides
adora run examples/python-logging/dataflow.yml --log-filter "monitor=debug,sensor=warn" --stop-after 5s
# JSON output for machine parsing
adora run examples/python-logging/dataflow.yml --log-format json --stop-after 3s
# Environment variable control
ADORA_LOG_LEVEL=warn adora run examples/python-logging/dataflow.yml --stop-after 5s
分布式模式(adora up + adora start – 协调器/守护进程架构,多机部署必需):
# Start infrastructure
adora up
# Start attached (live log stream)
adora start examples/python-logging/dataflow.yml --attach
# Or start detached and query logs separately
adora start examples/python-logging/dataflow.yml
adora logs <dataflow-id> sensor --follow # stream one node
adora logs <dataflow-id> sensor --follow --level warn # only warnings
adora logs <dataflow-id> --all-nodes --tail 20 # last 20 lines
adora logs <dataflow-id> processor --grep "error" --since 5m # targeted search
在分布式模式下,日志流经 节点 -> 守护进程 -> 协调器 -> CLI(通过 WebSocket)。协调器缓冲日志消息直到订阅者连接,因此即使延迟附加也不会丢失日志。YAML 级别设置(min_log_level、send_logs_as、max_log_size)工作方式相同,因为它们在守护进程端应用。
adora run | adora start | |
|---|---|---|
| 显示过滤 | --log-level、--log-format、--log-filter | adora logs 的 --level |
| 按节点覆盖 | --log-filter "sensor=debug" | 每个节点单独 adora logs |
| 远程节点 | 否 | 是 |
| 实时流 | 始终附加 | --attach 或 adora logs --follow |
运行后日志分析(两种模式工作方式相同):
# Read all local logs
adora logs --local --all-nodes --tail 20
# Search for warnings in sensor logs
adora logs --local sensor --grep "high temp"
# Check that rotation created multiple files
ls -la out/*/log_sensor*.jsonl
使用场景
1. 调试嘈杂的传感器流水线
摄像头传感器节点用 debug 消息淹没了日志,使得难以看到其他节点的错误。
nodes:
- id: camera
path: ./target/debug/camera
min_log_level: warn # 在源端抑制 info/debug/trace
max_log_size: "10MB" # 限制磁盘使用
- id: detector
path: ./target/debug/detector
- id: planner
path: ./target/debug/planner
# During development: see everything from detector, only warnings from camera
adora run dataflow.yml --log-level debug --log-filter "camera=warn,detector=debug"
# In production: only errors
export ADORA_LOG_LEVEL=error
adora run dataflow.yml
发生了什么:
- 摄像头节点的 debug/info 消息在到达日志文件前被守护进程丢弃(
min_log_level: warn) - CLI 根据
--log-filter进一步过滤显示 - 日志文件在 10MB 时轮转,摄像头节点最多在磁盘上保留 60MB
2. 数据流内日志聚合
构建数据流内的日志监控节点,监视多个节点的错误并发送告警。
nodes:
- id: camera
path: ./target/debug/camera
send_logs_as: logs
outputs:
- frames
- logs
- id: detector
path: ./target/debug/detector
send_logs_as: logs
outputs:
- detections
- logs
- id: log-monitor
path: ./target/debug/log-monitor
inputs:
camera_logs: camera/logs
detector_logs: detector/logs
outputs:
- alerts
日志监控器中的节点端处理(使用 adora-log-utils):
#![allow(unused)]
fn main() {
use adora_node_api::{AdoraNode, Event};
use adora_message::common::{LogLevel, LogLevelOrStdout};
let (mut node, mut events) = AdoraNode::init_from_env()?;
while let Some(event) = events.recv() {
match event {
Event::Input { data, .. } => {
let log = adora_log_utils::parse_log_from_arrow(&data)?;
let is_error = matches!(log.level,
LogLevelOrStdout::LogLevel(LogLevel::Error));
if is_error || log.message.contains("timeout") {
// 向下游发送告警
node.send_output("alerts", /* ... */)?;
}
}
Event::Stop(_) => break,
_ => {}
}
}
}
另请参阅日志 Sink 示例部分获取完整可运行示例。
3. 崩溃后的事后调试
数据流崩溃后,调查最后几分钟发生了什么。
# Find available dataflows
ls out/
# Read the last 50 lines from all nodes around the crash
adora logs --local --all-nodes --tail 50
# Focus on errors in the last 5 minutes
adora logs --local --all-nodes --since 5m --level error
# Search for a specific error pattern
adora logs --local --all-nodes --grep "out of memory"
# Drill into a specific node
adora logs --local detector --since 2m
# Export as JSON for external analysis
adora run dataflow.yml --log-format json 2>logs.json
4. 长时间运行的生产数据流
数据流运行数天或数周。没有日志轮转,磁盘空间会被填满。
nodes:
- id: ingest
path: ./target/debug/ingest
min_log_level: info # 生产环境无 debug 噪声
max_log_size: "100MB" # 每个节点最大约 600MB(100MB * 6)
restart_policy: always
inputs:
tick: adora/timer/millis/1000
outputs:
- data
- id: processor
path: ./target/debug/processor
min_log_level: warn # 仅警告和错误
max_log_size: "50MB"
restart_policy: on-failure
inputs:
data: ingest/data
outputs:
- results
- id: writer
path: ./target/debug/writer
min_log_level: error # 最少日志
max_log_size: "20MB"
inputs:
results: processor/results
磁盘预算:
ingest:最多 600MB(100MB x 6 个文件)processor:最多 300MB(50MB x 6 个文件)writer:最多 120MB(20MB x 6 个文件)- 总计:所有日志最大磁盘使用约 1GB
5. 分布式部署的实时监控
多个守护进程在不同机器上运行,从中央工作站进行监控。
# Start infrastructure (coordinator + local daemon)
adora up
# On remote machines, start a daemon pointing to the coordinator:
# adora daemon --coordinator-addr 192.168.1.10
# Start the dataflow (detached)
adora start dataflow.yml
# Open targeted log streams in separate terminals:
# Terminal 1: all sensor warnings
adora logs <dataflow-id> sensor --follow --level warn
# Terminal 2: processor errors with text search
adora logs <dataflow-id> processor --follow --level error --grep "timeout"
# Terminal 3: all nodes merged
adora logs <dataflow-id> --all-nodes --follow
# Terminal 4: historical + live (errors from the last hour, then stream)
adora logs <dataflow-id> processor --since 1h --level error --follow
# Monitor a remote coordinator from another machine:
adora logs <dataflow-id> sensor --follow --coordinator-addr 192.168.1.10
内部工作原理:
- CLI 连接到协调器(默认
localhost:6013,或--coordinator-addr) - 对于历史日志:请求/应答,过滤在客户端应用(
--since、--grep、--tail) - 使用
--follow时:向协调器打开 WebSocket 订阅 - 协调器在转发前按
--level在服务端过滤(减少网络流量) - CLI 在实时流上客户端应用
--grep和--since - 协调器缓冲日志消息直到订阅者连接,因此后加入的订阅者可以看到近期历史
6. 带结构化日志的 CI/CD 流水线
在 CI 中,使用 JSON 格式获取机器可解析的输出,使用 compact 格式获取可读日志。
# Machine-parseable logs for CI tooling
adora run dataflow.yml --log-format json --stop-after 30s 2>test-logs.json
# Compact logs for CI console output
adora run dataflow.yml --log-format compact --log-level info --stop-after 30s
# Post-run analysis: count errors per node
adora logs --local --all-nodes --level error | wc -l
使用 JSON 格式时,每行都是完整的 LogMessage,可由 jq、日志聚合器或自定义脚本处理:
# Extract error messages with jq
cat test-logs.json | jq -r 'select(.level == "ERROR") | "\(.node_id): \(.message)"'
Performance Considerations
Logging adds I/O overhead proportional to log volume. Here’s how to tune it:
min_log_level is the most impactful setting. It filters at the daemon before any I/O: no log file write, no coordinator forwarding, no send_logs_as routing. A node emitting 1000 debug lines/sec at min_log_level: info generates zero overhead for those lines.
send_logs_as adds a dataflow message per log line. Each parsed log entry is serialized to JSON, converted to Arrow, and sent through the dataflow. For high-volume nodes, this can consume significant bandwidth. Use min_log_level to limit what gets routed.
adora/logs subscribers share a single serialization. The daemon converts each log line to Arrow once and clones the result for each subscriber. The cost scales linearly with subscriber count, not log volume x subscriber count. For most dataflows (1-3 log subscribers), this is negligible.
Log line size is capped at 1 MB. Lines longer than 1 MB from node stdout/stderr are truncated to prevent heap exhaustion. This protects against buggy nodes that dump large binary data to stdout.
Log file rotation is recommended for long-running dataflows. Without max_log_size, log files grow unbounded. A node emitting 100 lines/sec at ~200 bytes/line fills 1 GB in ~14 hours.
Recommended production settings:
nodes:
- id: my-node
path: ./my-node
min_log_level: info # drop debug/trace at source
max_log_size: "50MB" # rotate at 50MB
max_rotated_files: 5 # keep 5 rotated files (300MB max)
最佳实践
**在生产环境中设置 min_log_level。**守护进程端的源级别过滤防止 debug 噪声到达日志文件和网络。这是减少日志量最有效的方式,因为它在任何 I/O 之前进行过滤。
**对于长时间运行的数据流,始终设置 max_log_size。**没有轮转,单个嘈杂的节点就能填满磁盘。从 "50MB"(轮转后每节点总计 300MB)开始,根据存储预算调整。使用 max_rotated_files 调节保留多少历史记录(默认 5,范围 1-100)。
**使用环境变量设置团队默认值。**在 shell 配置文件或 CI 配置中设置 ADORA_LOG_LEVEL 和 ADORA_LOG_FORMAT。个人开发者可以使用 CLI 标志覆盖。
**在开发期间使用 --log-filter。**无需更改 YAML 配置,使用按节点显示覆盖来聚焦正在调试的节点:--log-filter "my-node=debug"。
**使用 send_logs_as 进行运维监控。**构建监控节点来监视错误模式、计算错误率或转发告警。这将监控逻辑保持在数据流图内。使用 adora-log-utils 在自定义 sink 节点中解析和格式化日志条目(参见 examples/log-sink-file/ 和 examples/log-sink-tcp/)。
对于结构化数据,优先使用 send_logs_as 而非 send_stdout_as。send_stdout_as 捕获每行 stdout(包括原始 print),而 send_logs_as 仅捕获带完整元数据的已解析结构化日志条目。
**使用 --local 进行事后调试。**崩溃后,adora logs --local --all-nodes 无需运行中的协调器即可工作,并按时间顺序合并所有节点日志。
**组合 --since 和 --grep 进行针对性调试。**无需滚动数千行,缩小窗口:adora logs --local sensor --since 5m --grep "error"。
**在日志流水线中使用 JSON 格式。**向外部系统(ELK、Grafana Loki、Datadog)导入日志时,使用 --log-format json 进行结构化摄取。
调试与可观测性指南
本指南介绍如何调试、录制、回放和监控 adora 数据流。面向希望了解数据流故障原因、测量性能或离线复现问题的新用户。
目录
- Prerequisites
- 快速调试清单
- 录制与回放
- Node Management
- 主题检查
- Runtime Parameters
- Environment Diagnosis
- 追踪检查
- 资源监控
- 日志分析
- 数据流可视化
- 监控运行中的数据流
- 端到端调试工作流
前提条件
在使用主题检查命令(topic echo、topic hz、topic info)之前,通过以下任一方式启用调试消息发布:
方式 1:CLI 标志(推荐)
adora start dataflow.yml --debug
adora run dataflow.yml --debug
方式 2:YAML 描述符
_unstable_debug:
publish_all_messages_to_zenoh: true
这会告诉守护进程将所有节点间消息发布到 Zenoh,协调器可以通过 WebSocket 将其代理给 CLI 客户端。没有此标志,主题检查命令将返回错误。
The record, replay, logs, list, top, graph, node info/restart/stop, param, and doctor commands do not require this flag. The topic pub command does require it.
快速调试清单
当出现问题时,按以下顺序排查:
# 1. Run full environment diagnosis
adora doctor --dataflow dataflow.yml
# 2. What dataflows are active?
adora list
# 3. Inspect the problem node
adora node info -d my-dataflow problem-node
# 4. Check node resource usage
adora top
# 5. Stream logs from the problem node
adora logs my-dataflow problem-node --follow --level debug
# 6. Is the node producing output?
adora topic echo -d my-dataflow problem-node/output
# 7. Inject test data
adora topic pub -d my-dataflow problem-node/input '[1, 2, 3]'
# 8. Is it publishing at the expected rate?
adora topic hz -d my-dataflow --window 5
# 9. Check/modify runtime parameters
adora param list -d my-dataflow problem-node
adora param set -d my-dataflow problem-node debug_level 2
# 10. Restart a misbehaving node (without stopping the dataflow)
adora node restart -d my-dataflow problem-node
# 11. View coordinator traces (no external infra needed)
adora trace list
adora trace view <trace-id-prefix>
# 12. Visualize the dataflow graph
adora graph dataflow.yml --open
# 13. Record for offline analysis
adora record dataflow.yml -o debug-capture.adorec
录制和回放
录制将实时数据流消息捕获到文件。回放用录制数据替换源节点,让您无需硬件即可复现行为。
录制数据流
# Record all topics (default output: recording_{timestamp}.adorec)
adora record dataflow.yml
# Specify output file
adora record dataflow.yml -o my-capture.adorec
这会向数据流注入一个隐藏的 __adora_record__ 节点,该节点订阅所有节点输出并将其写入 .adorec 文件。录制节点二进制文件(adora-record-node)在首次使用时自动构建。
录制将持续运行,直到按下 Ctrl-C 或数据流停止。
录制特定主题
# Only record camera and lidar
adora record dataflow.yml --topics sensor/image,lidar/points
主题名称使用 node_id/output_id 格式。可用主题可通过 adora topic list -d <dataflow> 查看。
代理录制(远程/无盘)
当目标机器没有本地磁盘或您希望在本地机器上录制时:
# Start the dataflow first (detached)
adora start dataflow.yml --detach
# Record via WebSocket proxy -- data streams through coordinator to CLI
adora record dataflow.yml --proxy -o capture.adorec
# Record specific topics via proxy
adora record dataflow.yml --proxy --topics sensor/image,lidar/points
代理模式工作原理:
- 数据流必须已在运行(
adora start --detach) - CLI 通过 WebSocket 连接到协调器
- 协调器代表 CLI 订阅 Zenoh
- 消息数据通过 WebSocket 二进制帧流式传输到 CLI
- CLI 在本地写入
.adorec文件
这需要在描述符中设置 publish_all_messages_to_zenoh: true。
何时使用 --proxy:
- 无本地磁盘的嵌入式目标
- 希望在工作站上录制的远程机器
- 仅有 WebSocket 连接(无直接 Zenoh 访问)时
何时使用默认模式(不带 --proxy):
- 同一机器或共享文件系统
- 高吞吐场景(无 WebSocket 开销)
- 无需
publish_all_messages_to_zenoh
回放录制
# Replay at original speed
adora replay recording.adorec
# Replay at 2x speed
adora replay recording.adorec --speed 2.0
# Replay as fast as possible (speed 0)
adora replay recording.adorec --speed 0
回放工作原理:
- 读取
.adorec文件头获取原始数据流描述符 - 识别哪些节点产生了录制数据
- 将这些源节点替换为
adora-replay-node实例 - 运行修改后的数据流 – 下游节点接收的回放数据与实时数据完全相同
回放节点二进制文件(adora-replay-node)在首次使用时自动构建。
回放选项
| 标志 | 默认 | 描述 |
|---|---|---|
--speed <FLOAT> | 1.0 | 回放速度倍率。2.0 = 2 倍速、0.5 = 半速、0 = 尽可能快 |
--loop | off | 连续循环播放录制 |
--replace <NODES> | 所有已录制的 | 逗号分隔的要替换的节点列表 |
--output-yaml <PATH> | - | 写入修改后的描述符 YAML 但不运行 |
选择性回放
仅替换特定源节点,保持其他节点运行:
# Only replace the sensor node, keep camera live
adora replay recording.adorec --replace sensor
# Replace sensor and lidar, keep everything else live
adora replay recording.adorec --replace sensor,lidar
当您想用已知输入数据调试特定处理流水线同时保持系统其他部分运行时,这很有用。
干运行(输出 YAML)
录制和回放都支持 --output-yaml 来查看修改后的描述符而不运行:
# See what the record-injected descriptor looks like
adora record dataflow.yml --output-yaml record-modified.yml
# See what the replay-modified descriptor looks like
adora replay recording.adorec --output-yaml replay-modified.yml
录制文件格式
.adorec 格式是一个简单的二进制文件:
┌──────────────────────────────────┐
│ Header (bincode) │
│ version: u32 │
│ start_nanos: u64 │
│ dataflow_id: Uuid │
│ descriptor_yaml: Vec<u8> │
├──────────────────────────────────┤
│ Entry 1 (bincode) │
│ node_id: String │
│ output_id: String │
│ timestamp_offset_nanos: u64 │
│ event_bytes: Vec<u8> │
├──────────────────────────────────┤
│ Entry 2 ... │
├──────────────────────────────────┤
│ ... │
├──────────────────────────────────┤
│ Footer (bincode) │
│ total_messages: u64 │
│ total_bytes: u64 │
└──────────────────────────────────┘
event_bytes 字段包含原始的 Timestamped<InterDaemonEvent> bincode 载荷 – 与守护进程之间的线上传输格式相同。头部中的 descriptor_yaml 存储原始数据流描述符,以便回放时重建数据流。
Node Management
Node Info
Get detailed information about a specific node including its status, inputs, outputs, metrics, and restart count:
adora node info -d my-dataflow camera
# JSON output
adora node info -d my-dataflow camera --format json
Node Restart
Restart a single node without stopping the entire dataflow. Useful for recovering a misbehaving node or picking up configuration changes:
# Restart with default grace period
adora node restart -d my-dataflow camera
# Restart with custom grace period
adora node restart -d my-dataflow camera --grace 10s
The daemon sends a stop event, waits for the grace period, then respawns the node process.
Node Stop
Stop a single node without stopping the entire dataflow:
adora node stop -d my-dataflow camera
# With custom grace period
adora node stop -d my-dataflow camera --grace 5s
主题检查
主题检查命令通过协调器的 WebSocket 代理订阅实时数据流消息。需要 --debug 标志或 publish_all_messages_to_zenoh: true。
列出主题
# List all topics in a running dataflow
adora topic list -d my-dataflow
# JSON output
adora topic list -d my-dataflow --format json
显示每个输出、发布它的节点以及订阅它的节点。此命令从描述符读取,不需要 publish_all_messages_to_zenoh。
回显主题数据
将实时主题数据流式输出到终端:
# Echo a single topic
adora topic echo -d my-dataflow camera_node/image
# Echo multiple topics
adora topic echo -d my-dataflow robot1/pose robot2/vel
# JSON output (useful for piping to jq or other tools)
adora topic echo -d my-dataflow robot1/pose --format json
# Echo all topics
adora topic echo -d my-dataflow
每行显示主题名称、Arrow 数据内容和元数据参数。使用 --format json 获取机器可读输出:
{"timestamp":1709000000000,"name":"robot1/pose","data":[1.0,2.0,3.0],"metadata":null}
测量频率
交互式 TUI 显示每个主题的发布频率:
# All topics with 10-second sliding window
adora topic hz -d my-dataflow --window 10
# Specific topics with 5-second window
adora topic hz -d my-dataflow robot1/pose robot2/vel --window 5
TUI 显示:
- 平均频率 (Hz)
- 平均、最小、最大间隔
- 标准差
- 显示近期活动的火花图
按 q 或 Ctrl-C 退出。需要交互式终端。
Publishing Test Data
Inject data into a running dataflow for testing. Requires publish_all_messages_to_zenoh: true.
# Publish a single Arrow array
adora topic pub -d my-dataflow sensor/threshold '[42]'
# Publish from a JSON file
adora topic pub -d my-dataflow sensor/config --file test-config.json
# Publish multiple messages
adora topic pub -d my-dataflow sensor/trigger '[1]' --count 10
This is useful for:
- Testing node behavior with known input data
- Triggering specific code paths in downstream nodes
- Simulating sensor inputs without hardware
主题元数据与统计
一次性统计采集:
# Collect stats for 5 seconds (default)
adora topic info -d my-dataflow camera_node/image
# Collect for 10 seconds
adora topic info -d my-dataflow camera_node/image --duration 10
Reports:
- Arrow 数据类型
- 发布者节点
- 订阅者节点(来自描述符)
- 消息计数和带宽
- 发布频率
Runtime Parameters
Runtime parameters let you read and modify node configuration while a dataflow is running, without restarting. Parameters are stored in the coordinator and optionally forwarded to running nodes.
# List all parameters for a node
adora param list -d my-dataflow detector
# Get a single parameter
adora param get -d my-dataflow detector confidence
# Set a parameter (value is JSON)
adora param set -d my-dataflow detector confidence 0.8
adora param set -d my-dataflow detector config '{"nms": 0.5, "classes": ["car", "person"]}'
# Delete a parameter
adora param delete -d my-dataflow detector confidence
Parameters are persisted in the coordinator store (in-memory or redb). When a node is running, param set also forwards the new value to the node’s daemon. Nodes can read parameters through the node event stream.
Limits: Keys max 256 bytes, values max 64KB serialized.
Environment Diagnosis
adora doctor performs a comprehensive health check of your environment:
# Basic diagnosis
adora doctor
# Diagnosis + dataflow validation
adora doctor --dataflow dataflow.yml
Checks performed:
- Coordinator reachability
- Connected daemon status
- Active dataflow health
- Dataflow YAML validation (if
--dataflowprovided)
Use this as a first step when debugging any issue, or in CI to validate the environment before running tests.
追踪检查
协调器从 adora_coordinator 和 adora_core crate 在内存中捕获追踪 span(环形缓冲区中最多 4096 个 span)。您可以在没有任何外部追踪基础设施的情况下查看这些追踪(无需 Jaeger、Tempo 等)。
列出追踪
adora trace list
显示所有捕获的追踪及其根 span 名称、span 计数、开始时间和总持续时间:
TRACE ID ROOT SPAN SPANS STARTED DURATION
a1b2c3d4e5f6 spawn_dataflow 12 2026-03-01 10:30:05 1.234s
f8e7d6c5b4a3 build_dataflow 5 2026-03-01 10:29:58 0.500s
查看追踪
# Full trace ID
adora trace view a1b2c3d4-e5f6-7890-abcd-1234567890ab
# Or use a unique prefix
adora trace view a1b2c3d4
以缩进树形式显示 span,展示父子关系、日志级别、持续时间和 span 字段:
spawn_dataflow [INFO 1.234s] {build_id="abc", session_id="def"}
build_dataflow [INFO 0.500s]
download_node [DEBUG 0.200s] {url="..."}
start_inner [INFO 0.734s]
spawn_node [INFO 0.100s] {node_id="camera"}
spawn_node [INFO 0.080s] {node_id="detector"}
何时使用追踪检查
- 快速调试 – 无需设置 Jaeger/Tempo 即可查看协调器在
start、stop或build期间的操作 - 性能分析 – 识别数据流生命周期操作中的慢 span
- 部署故障排查 – 了解协调器操作的顺序和时间
要获取跨守护进程和节点的完整分布式追踪,请设置 ADORA_OTLP_ENDPOINT 并使用兼容 OTLP 的后端。
资源监控
adora top(也可用 adora inspect top)提供实时 TUI 显示每个节点的资源使用情况:
# Default 2-second refresh
adora top
# Custom refresh interval
adora top --refresh-interval 5
# JSON snapshot for scripting/CI
adora top --once | jq .
为每个节点显示:
- CPU 使用率(单核百分比)
- 内存(RSS)
- 节点状态(Running、Restarting、Degraded、Failed)
- 重启次数
- 队列深度(待处理消息)
- 网络 TX/RX(通过 Zenoh 的跨守护进程字节数)
- 磁盘 I/O 读/写
指标由守护进程采集并报告给协调器,因此适用于跨多台机器的分布式数据流。按 q 或 Ctrl-C 退出。
使用 --once 打印单次 JSON 快照并退出,适用于 CI 流水线和监控集成。
注意:CPU 百分比为单核值,因此多线程节点的值可能超过 100%。不同机器上的节点可能有不同的 CPU,因此百分比在跨机器间不可直接比较。
日志分析
实时日志流
# Stream logs from a specific node
adora logs my-dataflow sensor-node --follow
# Stream logs from all nodes
adora logs my-dataflow --all-nodes --follow
# Filter by log level
adora logs my-dataflow sensor-node --follow --level debug
# Stream with grep filter
adora logs my-dataflow --all-nodes --follow --grep "error"
不使用 --follow 时,从本地日志文件读取。使用 --follow 时,通过 WebSocket 从协调器实时流式传输。
本地日志文件
日志存储在 out/ 目录中:
out/
<dataflow-uuid>/
log_<node-id>.jsonl # current log
log_<node-id>.1.jsonl # rotated (previous)
log_<node-id>.2.jsonl # rotated (older)
直接读取:
# All nodes, local files
adora logs --local --all-nodes
# Specific node, last 50 lines
adora logs --local sensor-node --tail 50
过滤与搜索
| 标志 | 示例 | 描述 |
|---|---|---|
--level <LEVEL> | --level debug | 最低级别:error、warn、info、debug、trace、stdout |
--log-filter <FILTER> | --log-filter "sensor=debug,processor=warn" | 按节点级别过滤 |
--grep <PATTERN> | --grep "timeout" | 不区分大小写的子串匹配 |
--since <DURATION> | --since 5m | 仅显示此时间之后的日志 |
--until <DURATION> | --until 1h | 仅显示此时间之前的日志 |
--tail <N> | --tail 100 | 显示最后 N 行 |
--log-format <FMT> | --log-format json | 输出格式:pretty(默认)或 json |
环境变量:
ADORA_LOG_LEVEL– 默认日志级别ADORA_LOG_FORMAT– 默认日志格式ADORA_LOG_FILTER– 默认按节点过滤
数据流可视化
生成数据流的可视化图表:
# Generate HTML and open in browser
adora graph dataflow.yml --open
# Generate Mermaid diagram text
adora graph dataflow.yml --mermaid
Mermaid 输出可以粘贴到 mermaid.live 或在 GitHub markdown 中使用:
```mermaid
graph TD
sensor --> processor
processor --> controller
```
HTML 模式生成一个包含交互式 mermaid.js 图表的自包含文件。
监控运行中的数据流
# Full environment diagnosis
adora doctor
# List all dataflows (active and completed)
adora list
# List nodes in a specific dataflow
adora node list -d my-dataflow
# Get detailed info on a specific node
adora node info -d my-dataflow camera
# Check coordinator/daemon status
adora status
# View/modify runtime parameters
adora param list -d my-dataflow detector
adora param set -d my-dataflow detector threshold 0.5
adora list 显示每个数据流的 UUID、名称、状态和节点数量。将 -d <name> 与其他命令配合使用以指定特定数据流。
端到端调试工作流
工作流 1:节点未产生输出
# 1. Verify the node is running
adora list
adora top
# 2. Check its logs
adora logs my-dataflow problem-node --follow --level trace
# 3. Check if upstream nodes are publishing
adora topic echo -d my-dataflow upstream-node/output
# 4. Verify topic wiring
adora topic list -d my-dataflow
adora graph dataflow.yml --open
工作流 2:意外数据或错误值
# 1. Echo the topic to see raw data
adora topic echo -d my-dataflow node/output --format json
# 2. Record for offline analysis
adora record dataflow.yml -o debug.adorec
# 3. Replay with known input to isolate the issue
adora replay debug.adorec --replace sensor --speed 0
工作流 3:性能问题
# 1. Check CPU/memory per node
adora top
# 2. Measure publish frequencies
adora topic hz -d my-dataflow --window 10
# 3. Get bandwidth stats for suspected bottleneck
adora topic info -d my-dataflow heavy-node/output --duration 10
# 4. Record and replay at max speed to find throughput limits
adora record dataflow.yml -o perf.adorec
adora replay perf.adorec --speed 0
工作流 4:复现现场问题
# On the robot / target machine:
adora start dataflow.yml --detach
adora record dataflow.yml --proxy -o field-capture.adorec
# Transfer the .adorec file to your workstation, then:
adora replay field-capture.adorec
adora replay field-capture.adorec --speed 0.5 # slow motion
adora replay field-capture.adorec --loop # continuous replay
工作流 5:远程调试(无直接访问)
当您仅有到协调器的 WebSocket 连接时:
# All these commands work over WebSocket -- no Zenoh needed
adora list
adora top
adora logs my-dataflow --all-nodes --follow
adora topic echo -d my-dataflow node/output
adora topic hz -d my-dataflow
adora record dataflow.yml --proxy -o remote-capture.adorec
另请参阅
- CLI 参考 – 完整命令参考
- WebSocket Control Plane – how CLI communicates with coordinator
- WebSocket Topic Data Channel – how topic data is proxied
- Testing Guide – running smoke tests
容错
Adora 为机器人和 AI 数据流提供了内置的容错能力。节点可以在故障时自动重启、检测上游连接过期、在输入不可用时优雅降级,同时协调器可以将状态持久化到磁盘以便在崩溃和重启后恢复。
功能一览
| 特性 | 范围 | 配置 |
|---|---|---|
| 重启策略 | Per-node | restart_policy、max_restarts、restart_delay、… |
| 健康监控 | Per-node | health_check_timeout、health_check_interval(数据流级别) |
| 输入超时 | Per-input | input_timeout |
| 熔断器 | Automatic | 由 input_timeout 触发,自动恢复 |
| NodeRestarted 事件 | 下游节点 | 上游重启时自动触发 |
| InputTracker API | Rust 节点 | adora_node_api::InputTracker |
| Observability | Daemon-wide | 原子计数器定期记录日志 |
| 分布式健康 | Multi-daemon | 协调器心跳监控 |
| 协调器状态持久化 | Coordinator | --store redb(需要 redb-backend 特性) |
重启策略
控制节点退出或崩溃时的行为。
配置
nodes:
- id: my-node
path: ./target/debug/my-node
restart_policy: on-failure # never | on-failure | always
max_restarts: 5 # 0 = unlimited (default: 0)
restart_delay: 1.0 # initial delay in seconds
max_restart_delay: 30.0 # cap for exponential backoff
restart_window: 300.0 # reset counter after this many seconds
策略类型
never(默认)—— 节点不会被重启。故障正常传播。
on-failure —— 仅在节点以非零退出码退出时重启。正常退出(退出码 0)不会重启。
always —— 任何退出都会重启,以下情况除外:
- 用户停止了数据流(
adora stop或 Ctrl-C) - 所有输入已关闭且节点以非零退出码退出
重启的内部工作原理
当节点进程退出时,守护进程按以下顺序评估重启决策:
- 策略检查:重启策略是否允许?
Never-> 不重启OnFailure-> 仅在退出码 != 0 时重启Always-> 重启
- 禁用检查:
disable_restart是否已设置?(当所有输入关闭或通过stop_all手动停止时设置) - 窗口检查:如果设置了
restart_window且窗口从首次重启开始已过期,则将计数器重置为 0 - 限制检查:如果
max_restarts > 0且窗口计数器超过该值,则永久放弃 - 退避:如果设置了
restart_delay,则休眠计算出的延迟时间(唤醒后重新检查disable_restart) - 重新生成:使用相同配置重新生成节点进程
守护进程在 spawn/prepared.rs 生命周期循环中跟踪每个节点实例的重启状态。每个节点运行在自己的 tokio 任务中,因此重启不会阻塞其他节点。
Backoff
当设置了 restart_delay 时,守护进程在重启前会等待。延迟每次尝试加倍(指数退避),并受 max_restart_delay 限制。
退避指数在内部限制为 16,以防止溢出(2^16 = 65536x 倍数)。
以 restart_delay: 1.0 和 max_restart_delay: 10.0 为例:
Attempt 1: wait 1s (1.0 * 2^0)
Attempt 2: wait 2s (1.0 * 2^1)
Attempt 3: wait 4s (1.0 * 2^2)
Attempt 4: wait 8s (1.0 * 2^3)
Attempt 5: wait 10s (capped at max_restart_delay)
Attempt 6: wait 10s (capped)
在退避休眠期间,守护进程持续监控 disable_restart 标志。如果在节点等待重启时所有输入都关闭了,重启将被取消,并输出日志消息:“restart cancelled: inputs closed during backoff wait”。
重启窗口
当设置了 restart_window 时,重启计数器在窗口过期后重置(从当前窗口的首次重启开始计算)。这实现了 “每 M 秒最多 N 次重启” 的语义。
例如:max_restarts: 5、restart_window: 300.0 表示 “每 5 分钟最多 5 次重启”。如果窗口过期前未达到限制,计数器重置,节点获得另外 5 次机会。
关闭期间禁用重启
当守护进程停止数据流(通过 stop_all)时,它在发送 Stop 事件之前对每个节点调用 disable_restart()。这防止了重启机制与关闭过程冲突。disable_restart 标志是一个在守护进程事件循环和节点生成生命周期任务之间共享的 Arc<AtomicBool>。
NodeRestarted 事件
当节点重启时,守护进程向所有消费其输出的下游节点发送 NodeRestarted 事件。这使下游节点能够:
- 重置内部状态或缓存
- 记录上游恢复
- 重新初始化连接或会话
该事件携带重启节点的 NodeId。下游节点通过事件流自动接收:
#![allow(unused)]
fn main() {
match event {
Event::NodeRestarted { id } => {
println!("upstream node {id} restarted, resetting state");
// 清除旧节点实例的所有缓存状态
}
_ => {}
}
}
守护进程通过 dataflow.mappings 查找下游节点,该映射将每个节点的输出映射到所有订阅的 (receiver_node, input_id) 对。每个唯一的接收者在每次重启时获得一个 NodeRestarted 事件。
健康监测
被动监控检测停止与守护进程通信的挂起节点。
health_check_interval: 2.0 # seconds (default: 5.0, dataflow-level)
nodes:
- id: my-node
path: ./target/debug/my-node
health_check_timeout: 30.0 # seconds (per-node)
restart_policy: on-failure
可配置的健康检查间隔
health_check_interval 是一个数据流级别的设置,控制守护进程检查节点健康状态的频率。默认值为 5.0 秒。较小的值可以更快检测到挂起的节点,但会增加更多开销。在数据流 YAML 的顶层设置此项,而非按节点设置。
内部工作原理
守护进程按配置的 health_check_interval 运行健康检查扫描(通过发出 Event::NodeHealthCheckInterval 的 tokio 间隔流)。
每个 RunningNode 有一个 last_activity: Arc<AtomicU64> 字段,存储最后一次通信的时间戳(自纪元以来的毫秒数)。每当节点向守护进程发送任何请求(事件订阅、输出发送等)时,节点的通信处理器(node_communication/mod.rs)会原子地更新该字段。
健康检查函数(check_node_health)遍历所有运行中的节点:
- 跳过未设置
health_check_timeout的节点 - 跳过
last_activity == 0的节点(尚未连接) - 计算
elapsed_ms = now - last_activity - 如果
elapsed_ms > timeout_ms,记录警告并终止节点进程
终止后,正常的退出处理流程会运行,评估重启策略。这意味着 health_check_timeout 配合 restart_policy: on-failure 可以自动恢复挂起的节点。
什么算作 “活动”
从节点到守护进程的任何消息都算:
- 事件订阅请求
- 输出数据发送(通过共享内存或 TCP)
- 定时器 tick 确认
从其他节点接收的正常输入数据不会重置计时器——节点必须主动与守护进程通信。
输入超时和熔断器
按输入超时检测上游节点何时停止产生数据。
配置
nodes:
- id: downstream-node
path: ./target/debug/downstream
inputs:
sensor_data:
source: camera-node/frames
input_timeout: 5.0 # seconds
input_timeout 按输入设置,而非按节点设置。不同的输入可以有不同的超时时间。
内部工作原理
守护进程为每个设置了超时的输入维护一个 InputDeadline:
struct InputDeadline {
timeout: Duration, // configured timeout
last_received: Instant, // last time data arrived
}
这些存储在 RunningDataflow.input_deadlines 中,以 (NodeId, DataId) 为键。
超时检测在相同的 5 秒健康检查间隔内运行。check_input_timeouts 函数:
- 扫描所有
input_deadlines条目 - 如果
last_received.elapsed() > timeout,则输入被标记为 “broken” (node_id, input_id)对从input_deadlines移动到broken_inputs- 守护进程调用
break_input(),向下游节点发送InputClosed { id } - 如果节点的所有输入现在都已关闭(且没有处于 broken/可恢复状态的),则发送
AllInputsClosed并禁用节点的重启
截止时间重置:每当数据到达某个输入时,其 last_received 被重置为 Instant::now()。
熔断器:自动恢复
熔断器在 RunningDataflow.broken_inputs 中跟踪断开的输入。当新数据到达断开的输入时:
- 数据正常传递给节点
broken_inputs条目被移除- 输入被重新添加到
open_inputs - 创建新的
InputDeadline(重新开始超时计时) - 向节点发送
InputRecovered { id }事件 circuit_breaker_recoveries计数器递增
这意味着恢复是完全自动的。如果上游节点重启(通过重启策略)并重新开始产生数据,下游节点将无缝恢复接收。
节点端处理
在 Rust 节点中,在事件循环中处理这些事件:
#![allow(unused)]
fn main() {
use adora_node_api::{AdoraNode, Event};
let (mut node, mut events) = AdoraNode::init_from_env()?;
while let Some(event) = events.recv() {
match event {
Event::Input { id, data, .. } => {
// 正常处理
}
Event::InputClosed { id } => {
// 上游停止在此输入上产生数据。
// 你可以:使用缓存数据、跳过处理、通知操作员等。
}
Event::InputRecovered { id } => {
// 上游在此输入上恢复在线。
// 恢复正常处理。
}
Event::Stop(_) => break,
_ => {}
}
}
}
InputTracker API(Rust)
InputTracker 辅助工具跟踪输入健康状态并缓存每个输入最后接收到的值,使优雅降级变得简单。
#![allow(unused)]
fn main() {
use adora_node_api::{AdoraNode, Event, InputTracker, InputState};
let (mut node, mut events) = AdoraNode::init_from_env()?;
let mut tracker = InputTracker::new();
while let Some(event) = events.recv() {
tracker.process_event(&event);
match event {
Event::Input { id, data, .. } => {
// 有新数据可用
}
Event::InputClosed { id } => {
// 输入超时——回退到缓存数据
if let Some(stale_data) = tracker.last_value(&id) {
// 使用过期数据作为降级方案
}
}
Event::Stop(_) => break,
_ => {}
}
// 检查整体健康状态
if tracker.any_closed() {
let closed: Vec<_> = tracker.closed_inputs();
// 记录日志或调整行为
}
}
}
内部设计
InputTracker 维护两个 HashMap:
states: HashMap<DataId, InputState>—— 每个输入的当前状态(Healthy 或 Closed)cache: HashMap<DataId, ArrowData>—— 每个输入最后接收到的值
收到 Event::Input 时,两个映射都会更新(状态 = Healthy,缓存 = 数据克隆)。收到 Event::InputClosed 时,仅状态变化(缓存保留)。收到 Event::InputRecovered 时,状态恢复为 Healthy。缓存永远不会被清除,因此 last_value() 即使在输入关闭后也始终返回最近的数据。
注意:ArrowData 包装了 Arc<dyn arrow::array::Array>,因此缓存克隆是引用计数的(低开销)。
API 参考
| 方法 | 返回值 | 描述 |
|---|---|---|
new() | InputTracker | 创建空的追踪器 |
process_event(&Event) | bool | 更新状态。如果事件相关则返回 true |
state(&DataId) | Option<InputState> | 当前状态(Healthy 或 Closed) |
is_closed(&DataId) | bool | 检查输入是否已关闭 |
last_value(&DataId) | Option<&ArrowData> | 最后接收到的值(即使关闭后仍可用) |
closed_inputs() | Vec<&DataId> | 所有当前已关闭的输入 |
any_closed() | bool | 如果任何被追踪的输入已关闭则为 true |
Observability
守护进程使用原子计数器(FaultToleranceStats)跟踪容错事件,并在健康检查间隔期间每 5 秒记录一次摘要。
Counters
| Counter | 类型 | 递增条件 |
|---|---|---|
restarts | AtomicU64 | 节点重启被启动(在生成生命周期中) |
health_check_kills | AtomicU64 | 节点被健康检查终止(无响应) |
input_timeouts | AtomicU64 | 输入超时触发(熔断器跳闸) |
circuit_breaker_recoveries | AtomicU64 | 数据到达断开的输入(自动恢复) |
所有计数器使用 Ordering::Relaxed,因为它们仅用于信息展示,不需要严格的排序保证。
日志输出
当任何计数器非零时,守护进程发出结构化日志行:
INFO fault tolerance stats restarts=3 health_kills=0 input_timeouts=1 cb_recoveries=1
这些计数器在守护进程生命周期内是累积的。它们不会在数据流之间重置。
分布式健康
在多守护进程部署中,协调器监控守护进程心跳。
协议
- 心跳间隔:3 秒(协调器向每个守护进程发送心跳)
- 断开阈值:30 秒无响应
- 检测:在每次心跳扫描时,协调器移除在阈值内未响应的守护进程
- 通知:协调器向所有剩余的守护进程广播
PeerDaemonDisconnected { daemon_id }
DaemonInfo
ConnectedMachines CLI 查询返回 Vec<DaemonInfo>:
#![allow(unused)]
fn main() {
pub struct DaemonInfo {
pub daemon_id: DaemonId,
pub last_heartbeat_ago_ms: u64, // 自上次心跳以来的毫秒数
}
}
这使监控工具能够检测存活但响应缓慢的守护进程。
守护进程端处理
当守护进程收到 PeerDaemonDisconnected 时,它记录一条结构化警告:
WARN peer daemon disconnected daemon_id=machine-B
目前这仅用于信息展示。未来的工作可能包括从断开的守护进程自动迁移节点。
协调器状态持久化
默认情况下,协调器将所有状态保存在内存中。如果协调器进程崩溃或重启,所有运行中数据流的信息都会丢失——守护进程继续运行但成为孤立状态,用户必须手动重新运行数据流。
redb 存储后端通过使用 redb 将协调器状态持久化到磁盘上的单个文件来解决这个问题。redb 是一个纯 Rust 嵌入式键值存储,采用写时复制 B 树,设计上具有崩溃安全性。
设计:无状态协调器与有状态后端
协调器本身在 K8s 意义上保持无状态——它可以随时停止和重启。所有持久状态存储在 CoordinatorStore trait 背后的存储后端中:
Coordinator (stateless process)
|
v
CoordinatorStore trait
|
+-- InMemoryStore (default, no persistence)
+-- RedbStore (persists to ~/.adora/coordinator.redb)
这种分离意味着:
- 协调器事件循环在正常运行期间从不读取文件系统(仅在启动恢复时)
- 所有状态变更在明确定义的持久化点写入存储
- 可以在不改变协调器逻辑的情况下更换存储
启用持久化
# Use default path (~/.adora/coordinator.redb)
adora coordinator --store redb
# Use custom path
adora coordinator --store redb:/path/to/coordinator.redb
# Default: in-memory only (no persistence)
adora coordinator --store memory
redb 后端需要 redb-backend Cargo 特性,默认 CLI 构建中已启用。
持久化内容
存储跟踪三种记录类型:
| Record | Key | 持久化字段 |
|---|---|---|
DataflowRecord | UUID(16 字节) | uuid、name、descriptor(JSON)、status、daemon IDs、generation 计数器、创建/更新时间戳 |
BuildRecord | UUID(16 字节) | build ID、status、errors、创建/更新时间戳 |
DaemonInfo | DaemonId(bincode) | daemon ID、machine ID |
记录使用 bincode 序列化,实现紧凑、快速的编码。
数据流状态生命周期
协调器在每次状态转换时持久化数据流状态:
Start command --> Pending
All daemons ready --> Running
Stop command --> Stopping
All nodes finish --> Succeeded or Failed { error }
Spawn failure --> Failed { error: "spawn failed: ..." }
每次持久化调用递增记录的 generation 计数器,提供用于冲突检测的单调版本。
持久化点
协调器在事件循环的以下时刻写入存储:
- 数据流启动 (
ControlRequest::Start) —— 创建状态为Pending的记录 - 数据流已生成 (所有守护进程的
DataflowSpawnResult成功) —— 更新为Running - 生成失败 (
DataflowSpawnResult错误) —— 更新为Failed并附带实际错误消息 - 请求停止 (
ControlRequest::Stop或StopByName) —— 更新为Stopping - 所有节点完成 (
DataflowFinishedOnDaemon) —— 更新为Succeeded或Failed并附带每个节点的错误详情 - 优雅关闭(Ctrl-C 或
Destroy命令)—— 在发送停止消息之前将所有运行中的数据流标记为Stopping
如果存储写入失败,协调器记录警告并继续使用内存状态运行。这防止存储故障阻塞数据流生命周期。
启动恢复
当协调器使用包含上次运行数据的 redb 存储启动时,它执行恢复:
- 通过
store.list_dataflows()读取所有持久化的数据流记录 - 对于任何非终态状态(
Pending、Running、Stopping)的记录:- 将其标记为
Failed { error: "coordinator restarted" } - 递增 generation 计数器
- 将更新后的记录写回存储
- 将其标记为
- 终态记录(
Succeeded、Failed)保持不变
这确保了崩溃的协调器遗留的过期数据流不会与正在运行的数据流混淆。运行这些数据流的守护进程将独立检测到协调器断开。
错误详情保留
当数据流失败时,Failed 状态包含实际的每节点错误消息,而非通用字符串:
Failed { error: "node-1: exited with code 137; node-2: failed to spawn node: binary not found" }
错误从所有守护进程的 DataflowDaemonResult.node_results 收集,格式为 node_id: error_message,以 ; 连接。
Schema 版本控制
redb 数据库包含一个带有 schema_version 键的 meta 表。打开时:
- 如果不存在版本(新数据库),则写入当前版本
- 如果存储的版本与二进制文件的版本匹配,数据库正常打开
- 如果不匹配,数据库将以错误被拒绝
这防止了在 Adora 版本之间存储记录的序列化格式发生变化时的静默数据损坏。当前 schema 版本为 1。
文件安全
在 Unix 系统上:
- 数据库文件在创建后被设置为
0600(仅所有者可读写) - 默认目录(
~/.adora/)被设置为0700(仅所有者可访问) - 通过
redb:/path提供的自定义路径会经过验证以拒绝..组件
内部架构
#![allow(unused)]
fn main() {
// Store trait (libraries/coordinator-store/src/lib.rs)
pub trait CoordinatorStore: Send + Sync {
fn put_dataflow(&self, record: &DataflowRecord) -> Result<()>;
fn get_dataflow(&self, uuid: &Uuid) -> Result<Option<DataflowRecord>>;
fn list_dataflows(&self) -> Result<Vec<DataflowRecord>>;
fn delete_dataflow(&self, uuid: &Uuid) -> Result<()>;
// ... daemon and build methods
}
}
RedbStore 实现使用三个 redb 表(daemons、dataflows、builds),以基于 UUID 的二进制键和 bincode 序列化的值。所有操作都是同步的(redb 是同步库);协调器直接从异步事件循环中调用它们,因为它们是快速的进程内操作。
bincode 反序列化限制为 64 MiB,以防止损坏的数据在长度前缀中编码巨大的分配大小。
完整 YAML 参考
# Dataflow-level settings
health_check_interval: 2.0 # health check sweep interval (default: 5.0s)
nodes:
- id: sensor-node
path: ./target/debug/sensor
inputs:
tick: adora/timer/millis/100
outputs:
- frames
- id: processor
path: ./target/debug/processor
# Restart policy
restart_policy: on-failure # never | on-failure | always
max_restarts: 5 # 0 = unlimited
restart_delay: 1.0 # initial backoff delay (seconds)
max_restart_delay: 30.0 # max backoff cap (seconds)
restart_window: 300.0 # reset counter after N seconds
# Health monitoring
health_check_timeout: 30.0 # kill if no activity for N seconds
inputs:
frames:
source: sensor-node/frames
input_timeout: 5.0 # circuit breaker timeout (seconds)
queue_size: 10 # input buffer size (default: 10)
outputs:
- result
使用场景
1. 间歇性硬件故障的摄像头流水线
摄像头驱动节点偶尔因 USB 断开而崩溃。处理流水线应在这些中断中存活,并在摄像头重新连接时恢复。
nodes:
- id: camera-driver
path: ./target/debug/camera-driver
restart_policy: on-failure
max_restarts: 0 # unlimited -- hardware failures are expected
restart_delay: 2.0 # wait for USB to re-enumerate
max_restart_delay: 30.0
inputs:
tick: adora/timer/millis/33 # ~30 FPS
outputs:
- frames
- id: object-detector
path: ./target/debug/detector
inputs:
frames:
source: camera-driver/frames
input_timeout: 5.0 # tolerate 5s camera outage
outputs:
- detections
- id: planner
path: ./target/debug/planner
inputs:
detections:
source: object-detector/detections
input_timeout: 10.0 # longer tolerance -- can plan with stale data
lidar:
source: lidar-driver/points
input_timeout: 3.0
摄像头崩溃时会发生什么:
camera-driver以非零退出码退出- 守护进程评估
on-failure策略 -> 2 秒退避后重启 - 在中断期间,
object-detector在 5 秒后收到InputClosed { id: "frames" } planner在 10 秒后收到InputClosed { id: "detections" }- 摄像头重启,开始产生帧
object-detector收到新帧数据 +InputRecovered { id: "frames" }(熔断器恢复)planner收到检测结果 +InputRecovered { id: "detections" }
规划节点端的处理:
#![allow(unused)]
fn main() {
use adora_node_api::{AdoraNode, Event, InputTracker};
let (mut node, mut events) = AdoraNode::init_from_env()?;
let mut tracker = InputTracker::new();
while let Some(event) = events.recv() {
tracker.process_event(&event);
match event {
Event::Input { id, data, .. } => match id.as_ref() {
"detections" => plan_with_detections(&data),
"lidar" => update_lidar_map(&data),
_ => {}
},
Event::InputClosed { id } => match id.as_ref() {
"detections" => {
// 摄像头流水线中断——仅使用 lidar 进行规划
plan_lidar_only();
}
"lidar" => {
// LiDAR 中断——使用最近已知的检测数据
if let Some(stale) = tracker.last_value(&"detections".into()) {
plan_with_stale_detections(stale);
}
}
_ => {}
},
Event::Stop(_) => break,
_ => {}
}
}
}
2. 带 OOM 崩溃的 ML 推理节点
ML 推理节点偶尔在大型输入上耗尽内存。它应该快速重启,但在重复失败后放弃(表明存在系统性问题)。
nodes:
- id: ml-inference
path: ./target/debug/ml-inference
restart_policy: on-failure
max_restarts: 3
restart_delay: 0.5
restart_window: 60.0 # 3 restarts per minute
health_check_timeout: 60.0 # ML inference can be slow
inputs:
images:
source: preprocessor/images
outputs:
- predictions
Behavior:
- 节点因 OOM 崩溃 -> 0.5 秒后重启
- 在另一个大型输入上再次崩溃 -> 1.0 秒后重启
- 第三次崩溃 -> 2.0 秒后重启
- 在 60 秒内第四次崩溃 -> 超过
max_restarts,节点永久失败 - 如果节点在首次崩溃后稳定运行 60 秒,重启窗口重置,获得另外 3 次机会
3. 带优雅降级的多传感器融合
机器人融合来自多个传感器的数据。个别传感器可能会故障,但系统应以降低的能力继续运行。
nodes:
- id: sensor-fusion
path: ./target/debug/sensor-fusion
inputs:
camera:
source: camera-node/frames
input_timeout: 3.0
lidar:
source: lidar-node/points
input_timeout: 3.0
imu:
source: imu-node/readings
input_timeout: 1.0 # IMU is critical, short timeout
gps:
source: gps-node/fix
input_timeout: 10.0 # GPS can be intermittent
outputs:
- fused-state
使用 InputTracker 的节点端:
#![allow(unused)]
fn main() {
use adora_node_api::{AdoraNode, Event, InputTracker};
let (mut node, mut events) = AdoraNode::init_from_env()?;
let mut tracker = InputTracker::new();
while let Some(event) = events.recv() {
tracker.process_event(&event);
match event {
Event::Input { id, data, .. } => {
// 处理来自任何传感器的新数据
update_sensor(&id, &data);
compute_and_send_fusion(&mut node, &tracker);
}
Event::InputClosed { id } => {
// 传感器离线——调整融合权重
eprintln!("sensor {id} offline, degrading");
compute_and_send_fusion(&mut node, &tracker);
}
Event::InputRecovered { id } => {
// 传感器恢复在线
eprintln!("sensor {id} recovered");
}
Event::Stop(_) => break,
_ => {}
}
}
fn compute_and_send_fusion(node: &mut AdoraNode, tracker: &InputTracker) {
// 有新数据时使用新数据,降级传感器使用过期缓存
let camera = tracker.last_value(&"camera".into());
let lidar = tracker.last_value(&"lidar".into());
let imu = tracker.last_value(&"imu".into());
if tracker.is_closed(&"imu".into()) {
// IMU 是关键传感器——切换到紧急模式
emergency_stop(node);
return;
}
// 融合可用传感器,活跃传感器赋予更高权重
let closed = tracker.closed_inputs();
let active_count = 4 - closed.len();
// ... 使用 active_count 进行置信度加权的融合逻辑
}
}
4. 长期运行的数据处理流水线
批处理流水线持续运行。处理节点偶尔因第三方库 bug 而挂起。健康监控检测并从这些挂起中恢复。
nodes:
- id: data-ingest
path: ./target/debug/ingest
restart_policy: always # always restart -- this is a long-running service
max_restarts: 0 # unlimited
restart_delay: 1.0
inputs:
tick: adora/timer/millis/1000
outputs:
- records
- id: processor
path: ./target/debug/processor
restart_policy: on-failure
max_restarts: 10
restart_delay: 0.5
restart_window: 600.0 # 10 restarts per 10 minutes
health_check_timeout: 30.0 # kill if hung for 30s
inputs:
records: data-ingest/records
outputs:
- results
- id: writer
path: ./target/debug/writer
restart_policy: on-failure
max_restarts: 5
restart_delay: 2.0 # give DB time to recover
max_restart_delay: 60.0
inputs:
results:
source: processor/results
input_timeout: 60.0 # processor may be slow
处理器挂起时会发生什么:
- 处理器停止与守护进程通信
- 30 秒后,健康检查检测到挂起并终止进程
health_check_kills计数器递增- 守护进程评估
on-failure-> 0.5 秒后重启 - 新处理器实例启动,从
data-ingest恢复消费 writer可能在 60 秒超时期间收到了InputClosed——如果重启足够快也可能未收到- 如果
writer确实收到了InputClosed,当新结果到达时会收到InputRecovered
5. 带守护进程故障检测的分布式部署
协调器监控守护进程健康状态的多机器部署。
Machine A (coordinator + daemon): camera-driver, preprocessor
Machine B (daemon): ml-inference, postprocessor
Machine C (daemon): planner, actuator-driver
当机器 B 失去网络时会发生什么:
- 协调器到机器 B 的心跳失败
- 30 秒无响应后,协调器将机器 B 从活跃守护进程中移除
- 协调器向机器 A 和机器 C 广播
PeerDaemonDisconnected { daemon_id: "machine-B" } - A 和 C 上的守护进程记录:
WARN peer daemon disconnected daemon_id=machine-B - A 和 C 上从机器 B 节点接收输入的节点收到
InputClosed事件(通过其输入超时) - CLI 查询
ConnectedMachines仅显示 A 和 C 及其last_heartbeat_ago_ms
6. 使用 redb 持久化的协调器崩溃恢复
长期运行的多守护进程部署,协调器必须在重启后不丢失数据流历史记录。
# Start coordinator with persistent store
adora coordinator --store redb
# In another terminal, start a dataflow
adora start examples/rust-dataflow/dataflow.yml --name my-pipeline --detach
# Coordinator crashes or is killed (e.g., OOM, hardware failure)
# ... time passes ...
# Restart coordinator with the same store
adora coordinator --store redb
重启时会发生什么:
- 协调器打开
~/.adora/coordinator.redb并读取持久化的数据流记录 - 发现
my-pipeline状态为Running - 将其标记为
Failed { error: "coordinator restarted" },递增 generation - 记录日志:
INFO recovering stale dataflow <uuid> ("my-pipeline") -> marking as Failed adora list现在显示my-pipeline及其最终状态和时间戳- 守护进程独立检测到协调器断开并停止其节点
- 用户可以启动新的数据流——协调器已完全恢复运行
关键优势:协调器在重启后保留完整的数据流生命周期事件历史。如果不使用 --store redb,所有状态都会丢失,运维人员将无法得知崩溃前正在运行什么。
7. 使用 Always-Restart 的周期性批处理任务
一个处理批次并在完成后退出的节点。它应该重启以处理下一个批次。
nodes:
- id: batch-processor
path: ./target/debug/batch-proc
restart_policy: always # restart even on clean exit
max_restarts: 0 # unlimited
restart_delay: 10.0 # wait 10s between batches
max_restart_delay: 10.0 # no exponential growth
inputs:
trigger: adora/timer/millis/1 # immediate first trigger
outputs:
- batch-result
节点处理一个批次,以退出码 0 退出,等待 10 秒,然后重启处理下一个。always 策略确保即使成功也会重启。设置 restart_delay == max_restart_delay 可获得恒定延迟。
最佳实践
从 on-failure 开始。仅对预期退出并重启的节点(如周期性批处理任务)使用 always。
设置 max_restarts。无限重启可能掩盖 bug。从 3-5 开始,必要时增加。仅对崩溃不可避免的节点(硬件驱动、外部 API 客户端)使用 max_restarts: 0。
使用 restart_window。防止永久重启循环。60-300 秒的窗口是典型值。没有窗口时,启动时崩溃的节点会立即耗尽其重启预算。
调优 restart_delay。从 0.5-1.0 秒开始。太短会导致抖动;太长会延迟恢复。将延迟匹配到节点的典型启动时间和故障根因:
- USB/硬件重连:2-5 秒
- 网络服务重连:1-3 秒
- OOM/瞬态 bug:0.5-1.0 秒
宽裕地设置 health_check_timeout。应至少为节点最长预期处理时间的 2-3 倍。ML 推理节点可能需要 60 秒以上。如果太短,健康的节点会在正常处理期间被终止。
按输入设置 input_timeout。不是所有输入都需要相同的超时时间。对高频输入(IMU、摄像头)使用较短超时,对慢速/突发源(GPS、批处理结果)使用较长超时。一个好的起点是预期发布间隔的 3-5 倍。
对关键路径使用 InputTracker。当节点必须在输入降级时仍继续运行,使用 InputTracker 回退到缓存数据。这对传感器融合、规划和控制节点至关重要。
生产部署使用 --store redb。redb 后端确保协调器在崩溃和重启后保留数据流历史。内存默认值适合开发,但退出时会丢失所有状态。redb 文件很小(与数据流记录数量成比例),开销可忽略不计。
组合特性实现纵深防御:
restart_policy+restart_delay-> 从节点崩溃中恢复health_check_timeout-> 从挂起的节点中恢复input_timeout-> 检测过期的上游数据InputTracker-> 节点代码中的优雅降级--store redb-> 协调器崩溃后存活
分布式部署指南
Adora 支持跨多台机器部署数据流,用于多机器人车队、边缘 AI 流水线和分布式机器人系统。本指南涵盖集群管理、节点调度、二进制分发、自动恢复和运维最佳实践。
目录
- Overview
- 快速开始
- 特性概览
- 集群配置参考
- 集群命令参考
- 节点调度
- 二进制分发
- systemd 服务管理
- Auto-Recovery
- 滚动升级
- 使用场景
- 运维手册
- 部署 YAML 参考
- 最佳实践
概述
Adora 的分布式架构有三个层级:
CLI --> Coordinator --> Daemon(s) --> Nodes / Operators
(one) (per machine) (user code)
- CLI 向协调器发送控制命令(构建、启动、停止)。
- 协调器编排守护进程、解析节点放置、管理数据流生命周期。
- 守护进程在每台机器上运行,生成和监控节点进程。
- 节点通过共享内存(同一机器)或 Zenoh 发布/订阅(跨机器)通信。
分布式部署有两种路径:
临时部署 —— 在每台机器上手动启动 adora daemon,然后使用协调器进行控制。适合开发和测试。参见 CLI 参考中的分布式部署。
托管部署 (cluster.yml) —— 在 YAML 文件中定义集群拓扑,然后使用 adora cluster 命令进行基于 SSH 的生命周期管理。本指南重点介绍托管路径。
快速开始
- 创建
cluster.yml:
coordinator:
addr: 10.0.0.1
machines:
- id: robot
host: 10.0.0.2
user: ubuntu
- id: gpu-server
host: 10.0.0.3
user: ubuntu
- 启动集群:
adora cluster up cluster.yml
- 启动数据流:
adora start dataflow.yml --name my-app --attach
- 检查集群健康状态:
adora cluster status
- 关闭:
adora cluster down
功能一览
| 特性 | 命令 / 配置 | 描述 |
|---|---|---|
| 集群生命周期 | adora cluster up/status/down | 从单台机器进行基于 SSH 的守护进程管理 |
| 标签调度 | _unstable_deploy.labels | 通过键值标签将节点路由到守护进程 |
| 二进制分发 | _unstable_deploy.distribute | local、scp 或 http 策略 |
| systemd 服务 | adora cluster install/uninstall | 可在重启后存活的持久化守护进程服务 |
| Auto-recovery | Automatic | 守护进程重新连接时重新生成节点 |
| 滚动升级 | adora cluster upgrade | SCP 二进制文件 + 逐台机器顺序重启 |
| 数据流重启 | adora cluster restart | 按名称或 UUID 重启运行中的数据流 |
集群配置参考
cluster.yml 文件定义协调器地址和集群中的机器集合。
完整模式
coordinator:
addr: 10.0.0.1 # IP address the coordinator binds to (required)
port: 6013 # WebSocket port (default: 6013)
machines:
- id: edge-01 # 唯一机器标识符(必填)
host: 10.0.0.2 # SSH-reachable hostname or IP (required)
user: ubuntu # SSH 用户(可选,默认为当前用户)
labels: # Key-value labels for scheduling (optional)
gpu: "true"
arch: arm64
- id: edge-02
host: 10.0.0.3
labels:
arch: arm64
字段
coordinator
| Field | 类型 | 默认 | 描述 |
|---|---|---|---|
addr | IP 地址 | (required) | 协调器绑定的地址 |
port | u16 | 6013 | WebSocket 端口 |
machines[]
| Field | 类型 | 默认 | 描述 |
|---|---|---|---|
id | string | (required) | 唯一机器标识符,用于 _unstable_deploy.machine |
host | string | (required) | 可通过 SSH 访问的主机名或 IP 地址 |
user | string | 当前用户 | SSH 用户名 |
labels | map | empty | 用于基于标签调度的键值对 |
验证规则
- 至少必须定义一台机器。
- 机器 ID 必须非空且唯一。
- 机器主机名必须非空。
- 未知字段会被拒绝(
deny_unknown_fields)。
示例:3 机器 GPU 集群
coordinator:
addr: 192.168.1.1
machines:
- id: coordinator-host
host: 192.168.1.1
labels:
role: control
- id: gpu-a100
host: 192.168.1.10
user: ml
labels:
gpu: a100
arch: x86_64
- id: jetson-01
host: 192.168.1.20
user: nvidia
labels:
gpu: jetson
arch: arm64
集群命令参考
所有 adora cluster 命令都基于 cluster.yml 文件操作,并使用 SSH 管理远程机器。
使用的 SSH 选项:BatchMode=yes、ConnectTimeout=10、StrictHostKeyChecking=accept-new。
adora cluster up
从 cluster.yml 文件启动多机器集群。在本地启动协调器,然后通过 SSH 登录每台机器启动守护进程。
adora cluster up <PATH>
Arguments:
| Argument | 描述 |
|---|---|
PATH | 集群配置文件的路径 |
Behavior:
- 加载并验证集群配置。
- 在本地
addr:port上启动协调器。 - 对每台机器,通过 SSH 登录并运行
nohup adora daemon --machine-id <id> --coordinator-addr <addr> --coordinator-port <port> [--labels k1=v1,k2=v2] --quiet。 - 轮询直到所有预期的守护进程注册到协调器(30 秒超时)。
Example:
$ adora cluster up cluster.yml
Starting coordinator on 10.0.0.1:6013...
Starting daemon on robot (ubuntu@10.0.0.2)... OK
Starting daemon on gpu-server (ubuntu@10.0.0.3)... OK
All 2 daemons connected.
adora cluster status
显示集群的当前状态。展示已连接的守护进程和活跃数据流数量。
adora cluster status [--coordinator-addr ADDR] [--coordinator-port PORT]
Flags:
| 标志 | 默认 | 描述 |
|---|---|---|
--coordinator-addr | localhost | 协调器主机名或 IP |
--coordinator-port | 6013 | 协调器 WebSocket 端口 |
Example:
$ adora cluster status
DAEMON ID LAST HEARTBEAT
robot 2s ago
gpu-server 1s ago
Active dataflows: 1
adora cluster down
关闭集群(协调器和所有守护进程)。
adora cluster down [--coordinator-addr ADDR] [--coordinator-port PORT]
终止所有守护进程和协调器进程。
adora cluster install
在每台机器上将 adora-daemon 安装为 systemd 服务。通过 SSH 登录每台机器,写入 systemd 单元文件并启用服务。
adora cluster install <PATH>
Arguments:
| Argument | 描述 |
|---|---|
PATH | 集群配置文件的路径 |
Behavior:
对每台机器,创建并启用名为 adora-daemon-<id> 的 systemd 服务。单元文件:
[Unit]
Description=Adora Daemon (<id>)
After=network-online.target
Wants=network-online.target
[Service]
ExecStart=adora daemon --machine-id <id> --coordinator-addr <addr> --coordinator-port <port> --labels k1=v1,k2=v2 --quiet
Restart=on-failure
RestartSec=5
[Install]
WantedBy=multi-user.target
Example:
$ adora cluster install cluster.yml
Installing adora-daemon-robot on ubuntu@10.0.0.2... OK
Installing adora-daemon-gpu-server on ubuntu@10.0.0.3... OK
2/2 succeeded.
adora cluster uninstall
从每台机器卸载 adora-daemon systemd 服务。停止、禁用并移除 systemd 单元。
adora cluster uninstall <PATH>
Behavior:
对每台机器运行:
sudo systemctl stop adora-daemon-<id>
sudo systemctl disable adora-daemon-<id>
sudo rm -f /etc/systemd/system/adora-daemon-<id>.service
sudo systemctl daemon-reload
adora cluster upgrade
滚动升级:通过 SCP 将本地 adora 二进制文件传输到每台机器并重启守护进程。按顺序处理机器以保持可用性。
adora cluster upgrade <PATH>
Behavior:
对每台机器按顺序执行:
- 通过 SCP 将本地
adora二进制文件传输到目标机器的/usr/local/bin/adora。 - 通过
sudo systemctl restart adora-daemon-<id>重启 systemd 服务。 - 轮询协调器直到守护进程重新连接(30 秒超时,500 毫秒间隔)。
在每台机器升级期间,其他机器上的节点继续运行。
Example:
$ adora cluster upgrade cluster.yml
Upgrading robot (ubuntu@10.0.0.2)...
SCP binary... OK
Restart service... OK
Waiting for reconnect... OK (3.2s)
Upgrading gpu-server (ubuntu@10.0.0.3)...
SCP binary... OK
Restart service... OK
Waiting for reconnect... OK (2.8s)
2/2 succeeded.
adora cluster restart
按名称或 UUID 重启运行中的数据流。停止数据流并立即使用存储的描述符重新启动(不需要 YAML 路径)。
adora cluster restart <DATAFLOW>
Arguments:
| Argument | 描述 |
|---|---|
DATAFLOW | 要重启的数据流的名称或 UUID |
Example:
$ adora cluster restart my-app
Restarting dataflow `my-app`
dataflow restarted: a1b2c3d4-... -> e5f6a7b8-...
节点调度
当协调器收到数据流时,它根据数据流 YAML 中的 _unstable_deploy 部分决定哪个守护进程运行每个节点。解析优先级:machine > labels > unnamed。
基于机器的调度
通过 cluster.yml 中的 id 将节点分配到特定机器:
nodes:
- id: camera
_unstable_deploy:
machine: robot
path: ./camera-driver
outputs:
- frames
协调器查找 machine-id 匹配的守护进程。如果没有匹配的守护进程连接,部署将失败并提示:no matching daemon for machine id "robot"。
基于标签的调度
通过要求目标守护进程具有特定标签来分配节点:
nodes:
- id: inference
_unstable_deploy:
labels:
gpu: "true"
path: ./ml-model
inputs:
frames: camera/frames
outputs:
- predictions
协调器查找第一个标签是所需标签超集的已连接守护进程。所有必需的键值对必须完全匹配。如果没有守护进程满足要求,部署将失败并提示:no daemon matches labels {"gpu": "true"}。
未分配的节点
没有 _unstable_deploy 部分(或该部分为空)的节点被分配到第一个未命名的守护进程——即未使用 --machine-id 标志连接的守护进程。
resolve_daemon() 的内部工作原理
协调器在 coordinator/run/mod.rs 中解析节点放置:
resolve_daemon(connections, deploy) -> DaemonId
1. If deploy.machine is Some(id):
-> look up daemon by machine-id
2. Else if deploy.labels is non-empty:
-> find first daemon where all required labels match
3. Else:
-> pick first unnamed daemon
标签匹配函数遍历所有已连接的守护进程,检查每个必需的键值对是否存在于守护进程的标签集中(conn.labels.get(k) == Some(v))。这是一个超集检查:具有 {gpu: "true", arch: "arm64", role: "edge"} 的守护进程满足 {gpu: "true"} 的要求。
二进制分发
通过 distribute 字段控制节点二进制文件如何交付到远程守护进程。
Local(默认)
每个守护进程在自己的机器上从源码构建。这是当前的默认行为。
nodes:
- id: my-node
_unstable_deploy:
machine: edge-01
distribute: local
path: ./my-node
SCP 模式
CLI 在生成前通过 SSH/SCP 将本地构建的二进制文件推送到目标机器。
nodes:
- id: my-node
_unstable_deploy:
machine: edge-01
distribute: scp
path: ./my-node
HTTP 模式
协调器运行制品存储。守护进程在生成前通过 HTTP 从协调器拉取二进制文件。
nodes:
- id: my-node
_unstable_deploy:
machine: edge-01
distribute: http
path: ./my-node
制品通过协调器 WebSocket 端口上的 GET /api/artifacts/{build_id}/{node_id} 提供。该端点需要认证(Bearer token)并对节点 ID 进行清理以防止路径遍历。
何时使用每种策略
| Strategy | 最适用于 | Tradeoffs |
|---|---|---|
local | 同构集群、CI 构建 | 需要在每台机器上安装构建工具链 |
scp | 异构集群、交叉编译的二进制文件 | 需要从 CLI 到所有机器的 SSH 访问 |
http | 隔离的守护进程、防火墙网络 | 需要所有守护进程能访问协调器 |
systemd 服务管理
对于生产部署,将守护进程安装为 systemd 服务,使其在重启后存活并在故障时自动重启。
Install
adora cluster install cluster.yml
在每台机器上创建 systemd 单元文件(完整单元模板见 adora cluster install)。关键属性:
- Restart=on-failure 配合 RestartSec=5:守护进程崩溃时自动重启。
- After=network-online.target:启动前等待网络就绪。
- WantedBy=multi-user.target:开机启动。
Uninstall
adora cluster uninstall cluster.yml
停止、禁用并从每台机器移除单元文件,然后重新加载 systemd 守护进程。
验证服务状态
安装后,直接检查服务:
ssh ubuntu@10.0.0.2 sudo systemctl status adora-daemon-robot
自动恢复
当守护进程断开并重新连接时(例如网络闪断、机器重启或服务重启后),协调器自动在该守护进程上重新生成所有缺失的数据流。
工作原理
- 守护进程重新连接并发送
StatusReport,列出当前运行的数据流。 - 协调器将报告与其预期状态(应在此守护进程上有节点的数据流)进行比较。
- 对于分配到此守护进程但守护进程未报告的每个运行中数据流,协调器发送
SpawnDataflowNodes命令以重新生成缺失的节点。
30 秒退避
为防止崩溃循环(例如节点在生成时立即崩溃),恢复使用每守护进程、每数据流的退避:
- 恢复尝试后,协调器记录时间戳。
- 同一守护进程/数据流对的后续恢复在 30 秒过去之前被跳过。
- 当守护进程报告数据流再次运行时,退避清除。
这意味着立即崩溃的节点只会每 30 秒重新生成一次,而不是紧密循环。
限制
- 自动恢复仅适用于通过
adora start启动的数据流(协调器管理的)。本地adora run数据流不受协调器跟踪。 - 恢复会重新生成分配到重新连接的守护进程的所有节点,而非单个节点。对于节点崩溃时的单节点重启,请使用重启策略。
滚动升级
使用逐台机器顺序升级,以零停机时间升级所有集群机器上的 adora 二进制文件。
Process
adora cluster upgrade cluster.yml
对每台机器按顺序执行:
- SCP 将本地
adora二进制文件传输到目标机器的/usr/local/bin/adora。 - 重启 systemd 服务(
systemctl restart adora-daemon-<id>)。 - 轮询协调器直到守护进程重新连接(30 秒超时)。
由于机器逐台升级,其他机器上的节点继续运行。守护进程重新连接后,自动恢复会重新生成在该机器上运行的所有数据流节点。
前提条件
- 守护进程必须已安装为 systemd 服务(
adora cluster install)。 - 本地
adora二进制文件必须与集群的协调器版本兼容。 - 所有目标机器上具有
sudo权限的 SSH 访问。
使用场景
1. 边缘 AI 流水线(机器人 + GPU 服务器)
摄像头节点在机器人上运行,将帧发送到 GPU 服务器进行推理,结果流回机器人上的执行器。
cluster.yml:
coordinator:
addr: 192.168.1.1
machines:
- id: robot
host: 192.168.1.10
user: ubuntu
labels:
role: edge
- id: gpu-server
host: 192.168.1.20
user: ml
labels:
gpu: "true"
dataflow.yml:
nodes:
- id: camera
_unstable_deploy:
machine: robot
path: ./camera-driver
outputs:
- frames
- id: inference
_unstable_deploy:
labels:
gpu: "true"
path: ./ml-model
inputs:
frames: camera/frames
outputs:
- predictions
- id: actuator
_unstable_deploy:
machine: robot
path: ./actuator-driver
inputs:
commands: inference/predictions
2. 多机器人车队
中央协调器管理 N 个具有异构硬件的机器人。标签调度将节点路由到正确的机器,无需硬编码机器 ID。
cluster.yml:
coordinator:
addr: 10.0.0.1
machines:
- id: bot-01
host: 10.0.0.11
user: robot
labels:
fleet: warehouse
lidar: "true"
- id: bot-02
host: 10.0.0.12
user: robot
labels:
fleet: warehouse
camera: rgbd
- id: bot-03
host: 10.0.0.13
user: robot
labels:
fleet: warehouse
lidar: "true"
camera: rgbd
dataflow.yml:
nodes:
- id: lidar-driver
_unstable_deploy:
labels:
lidar: "true"
path: ./lidar-driver
outputs:
- scans
- id: camera-driver
_unstable_deploy:
labels:
camera: rgbd
path: ./camera-driver
outputs:
- frames
使用此配置,lidar-driver 在 bot-01 或 bot-03 上运行,camera-driver 在 bot-02 或 bot-03 上运行。
3. 机器人 CI/CD 流水线
在 CI 中自动化集群管理:
# Setup
adora cluster install cluster.yml
# Deploy new version
adora cluster upgrade cluster.yml
# Run integration tests
adora start test-dataflow.yml --name integration-test --attach
# Monitor
adora cluster status
adora top
# Cleanup
adora stop integration-test
4. 从开发到生产
| Stage | Approach | 命令 |
|---|---|---|
| 本地开发 | 单进程,无协调器 | adora run dataflow.yml |
| Staging | 临时守护进程,手动设置 | 每台机器上 adora up + adora daemon |
| Production | 托管集群,systemd 服务 | adora cluster install cluster.yml |
运维手册
初始设置清单
- SSH 密钥:分发 SSH 密钥,使 CLI 机器无需密码即可连接所有集群机器(
BatchMode=yes)。 - Adora 二进制文件:在所有机器上安装
adora二进制文件(相同版本)。 - 网络:确保所有机器可访问协调器端口(默认 6013)。确保守护进程之间的 Zenoh 端口开放,以支持跨机器节点通信。
- cluster.yml:创建包含正确 IP、用户和标签的集群配置。
日常运维
# Start a dataflow
adora start dataflow.yml --name my-app --attach
# List running dataflows
adora list
# Monitor resource usage
adora top
# View node logs
adora logs my-app <node-id> --follow
# Stop a dataflow
adora stop my-app
# Check cluster health
adora cluster status
Upgrading
- 在本地构建或下载新的
adora二进制文件。 - 运行
adora cluster upgrade cluster.yml。 - 使用
adora cluster status验证所有守护进程已重新连接。 - 运行中的数据流通过自动恢复机制自动重新生成。
故障排除
守护进程未连接
- 验证协调器正在运行且可访问:
curl http://<addr>:6013/api/health(或检查协调器日志)。 - 检查守护进程日志:
journalctl -u adora-daemon-<id> -f(systemd)或守护进程的 stderr 输出(临时部署)。 - 确认
--coordinator-addr和--coordinator-port与协调器的实际绑定地址匹配。
集群命令期间的 SSH 失败
- 确保从 CLI 机器可以成功执行
ssh -o BatchMode=yes <user>@<host> echo ok。 - 检查
StrictHostKeyChecking=accept-new对你的环境是否可接受(首次连接自动接受主机密钥)。 - 验证
cluster.yml中的user字段与目标机器上的有效 SSH 用户匹配。
标签不匹配错误
- 错误:
no daemon matches labels {"gpu": "true"}。 - 检查守护进程是否使用了正确的
--labels标志启动。 - 运行
adora cluster status查看已连接的守护进程。标签在守护进程启动时从cluster.yml设置,运行时无法更改。
自动恢复未触发
- 自动恢复仅适用于协调器管理的数据流(
adora start),不适用于adora run。 - 检查协调器日志中的
auto-recovery: re-spawning消息。 - 如果节点立即崩溃,恢复被限制为每个守护进程每个数据流每 30 秒一次。
部署 YAML 参考
每个节点上的 _unstable_deploy 部分控制放置和分发。所有字段都是可选的。
nodes:
- id: my-node
_unstable_deploy:
machine: edge-01 # 来自 cluster.yml 的目标机器 ID
labels: # Label requirements (superset match)
gpu: "true"
arch: arm64
distribute: local # local | scp | http
working_dir: /opt/my-app # 目标机器上的工作目录
path: ./my-node
字段
| Field | 类型 | 默认 | 描述 |
|---|---|---|---|
machine | string | none | 目标机器 ID。优先于标签。 |
labels | map | empty | 必需的守护进程标签。所有键值对必须匹配。 |
distribute | string | local | 二进制分发策略:local、scp 或 http。 |
working_dir | path | none | 目标机器上的工作目录。 |
解析优先级
- machine —— 如果设置,节点被分配到具有该机器 ID 的守护进程。
- labels —— 如果设置(且未设置 machine),节点被分配到标签是所需标签超集的第一个守护进程。
- 回退 —— 如果两者都未设置,节点被分配到第一个未命名(无 machine-id)的守护进程。
最佳实践
- 优先使用标签而非机器 ID 以获得灵活性。标签将数据流与特定机器解耦,使添加、移除或替换硬件更容易。
- 生产环境使用 systemd 安装。守护进程服务在重启后存活,并通过
Restart=on-failure在故障时自动重启。 - 在集群中使用协调器持久化(
adora coordinator --store redb),使协调器在重启后存活。参见协调器状态持久化。 - 在节点上设置重启策略以实现每节点弹性。与自动恢复结合实现纵深防御。参见重启策略。
- 使用多种工具监控:
adora cluster status查看守护进程健康状态,adora top查看资源使用,adora logs查看节点输出。 - 先在本地测试。使用
adora run dataflow.yml开发,然后部署到集群。相同的数据流 YAML 在两种模式下都有效——_unstable_deploy字段在本地模式下被忽略。 - 使用滚动升级而非停止整个集群。
adora cluster upgrade每次处理一台机器以保持可用性。 - 将 cluster.yml 与数据流定义一起纳入版本控制。
Performance
Adora achieves 10-17x lower latency than ROS2 Python through zero-copy shared memory IPC, Apache Arrow columnar format, and 100% Rust internals. This document covers methodology, reproduction, and tuning.
Architecture Advantages
| 层级 | Adora | ROS2 (rclpy) |
|---|---|---|
| Runtime | Rust async (tokio) | Python + C++ middleware |
| IPC (>4KB) | Zero-copy shared memory | DDS serialization + copy |
| IPC (<4KB) | TCP with bincode | DDS serialization + copy |
| Data format | Apache Arrow (zero-serde) | CDR serialization |
| Threading | Lock-free channels (flume) | GIL-bound callbacks |
Benchmark Suite
Internal benchmarks (examples/benchmark/)
Measures Adora’s own latency and throughput across 10 payload sizes (0B to 4MB).
cd examples/benchmark
./compare.sh # Rust vs Python sender comparison
Metrics reported: avg, p50, p95, p99, p99.9, min, max latency; msg/s throughput.
ROS2 comparison (examples/ros2-comparison/)
Apples-to-apples comparison using identical Python workloads on both frameworks.
cd examples/ros2-comparison
./run_comparison.sh # Requires ROS2 Humble+
Both sides use time.perf_counter_ns() timestamps embedded in payload first 8 bytes. Same message count, sizes, and sleep intervals ensure comparable results.
Criterion micro-benchmarks
Isolated benchmarks for internal hot paths:
# Daemon message routing (fan-out x payload size matrix)
cargo bench -p adora-daemon
# Message serialization/deserialization
cargo bench -p adora-message
CI tracks these via benchmark-action/github-action-benchmark with 120% alert threshold.
Reproducing Results
要求
- Linux or macOS (shared memory IPC)
- Rust 1.85+ with release profile
- Python 3.10+ with
numpy,pyarrow - ROS2 Humble+ (for comparison only)
Steps
-
Build Adora:
cargo install --path binaries/cli --locked -
Run internal benchmark:
cd examples/benchmark BENCH_CSV=results/rust.csv adora run dataflow.yml -
Run ROS2 comparison:
cd examples/ros2-comparison ./run_comparison.sh
Environment Notes
- Close background applications to reduce variance
- Use
tasksetorcpusetto pin processes for consistent results - Run at least 3 iterations and report median
- Shared memory benefits appear at payloads >4KB
Performance Tuning
Queue sizes
Default queue size is 10. For high-throughput outputs, increase it:
inputs:
data:
source: producer/output
queue_size: 1000
Payload size
Adora automatically uses shared memory for messages >4KB, avoiding copies. Structure data to exceed this threshold when low latency matters.
Arrow format
Use Arrow arrays directly instead of converting to/from Python lists:
# Fast: pass Arrow array directly
node.send_output("out", pa.array(data, type=pa.uint8()))
# Slow: convert through Python list
node.send_output("out", pa.array(list(data), type=pa.uint8()))
Operator vs Node
Operators run in-process with the runtime (zero IPC overhead) but share the GIL in Python. Use Rust operators for compute-heavy work, Python operators for glue logic.
Distributed deployment
For cross-machine communication, Adora uses Zenoh pub-sub. Latency depends on network quality. Use local deployment (single-machine) when sub-millisecond latency is required.
CSV Output Format
All benchmarks support BENCH_CSV environment variable for machine-readable output:
latency,<bytes>,<label>,<n>,<avg_ns>,<p50_ns>,<p95_ns>,<p99_ns>,<p999_ns>,<min_ns>,<max_ns>
throughput,<bytes>,<label>,<n>,<msg_per_sec>,<elapsed_ns>,0,0,0,0,0
ROS2 桥接
Adora 提供声明式的基于 YAML 的 ROS2 桥接,允许任何 Adora 节点与 ROS2 主题、服务和动作通信,无需导入 ROS2 库。你在数据流 YAML 中使用 ros2: 键定义桥接,框架自动生成一个在 Apache Arrow(Adora 的原生格式)和 ROS2 CDR/DDS 之间转换的桥接二进制文件。你的用户节点保持无 ROS2 依赖——它们收发纯 Arrow StructArray 数据。
功能一览
| 特性 | 配置 | 描述 |
|---|---|---|
| 主题订阅 | topic + direction: subscribe | 从 ROS2 接收,作为 Arrow 转发 |
| 主题发布 | topic + direction: publish | 接收 Arrow,发布到 ROS2 |
| Multi-topic | topics | 单个 ROS2 节点上的多个主题 |
| 服务客户端 | service + role: client | 发送请求,接收响应 |
| 服务服务端 | service + role: server | 接收请求,发送响应 |
| 动作客户端 | action + role: client | 发送目标,接收反馈 + 结果 |
| 动作服务端 | action + role: server | 接收目标,发送反馈 + 结果 |
| QoS 策略 | qos | 可靠性、持久性、历史、活跃度 |
| Auto-spawn | Automatic | 守护进程作为自定义节点生成桥接二进制文件 |
架构
当 Adora 描述符解析器在节点上遇到 ros2: 键时,它将其转换为指向 adora-ros2-bridge-node 二进制文件的 Custom 节点。桥接配置被序列化为 JSON 到 ADORA_ROS2_BRIDGE_CONFIG 环境变量中。
User Node <--(Arrow/SharedMem)--> Bridge Binary <--(CDR/DDS)--> ROS2
桥接二进制文件:
- 读取
AMENT_PREFIX_PATH以定位已安装的 ROS2 消息包 - 启动时解析消息/服务/动作定义
- 创建
ros2_client节点和相应的发布者、订阅者、客户端或服务端 - 将传入的 ROS2 CDR 消息转换为 Arrow
StructArray(订阅/响应/反馈) - 将传入的 Arrow
StructArray转换为 ROS2 CDR 消息(发布/请求/目标)
你的用户节点永远不会链接 ROS2——所有 ROS2 通信都隔离在桥接二进制文件中。
前提条件
- 已 source ROS2 环境:
AMENT_PREFIX_PATH必须设置并指向包含所需消息包的工作空间 - 已安装消息包:例如
turtlesim、geometry_msgs、example_interfaces - 服务客户端:ROS2 服务服务端必须正在运行(或使用配套的服务端数据流)
- 动作客户端:ROS2 动作服务端必须在启动数据流_之前_运行(无
wait_for_action_server机制) - 动作服务端:ROS2 动作客户端向桥接发送目标(例如
ros2 action send_goal)
主题桥接
单主题(订阅)
订阅 ROS2 主题并将消息作为 Arrow 数据转发到下游 Adora 节点。
nodes:
- id: pose_bridge
ros2:
topic: /turtle1/pose
message_type: turtlesim/Pose
direction: subscribe # 默认值,可省略
outputs:
- pose
桥接在 /turtle1/pose 上创建 ROS2 订阅,将每个传入的 turtlesim/Pose 消息反序列化为 Arrow StructArray,并通过 pose 输出发送。
单主题(发布)
从 Adora 节点接收 Arrow 数据并发布到 ROS2 主题。
nodes:
- id: cmd_bridge
ros2:
topic: /turtle1/cmd_vel
message_type: geometry_msgs/Twist
direction: publish
inputs:
cmd_vel: planner/cmd_vel
桥接在 cmd_vel 输入上接收 Arrow 数据,将其序列化为 geometry_msgs/Twist CDR,并发布到 /turtle1/cmd_vel。
Multi-Topic
在单个 ROS2 节点上下文中桥接多个主题,混合订阅和发布方向。
nodes:
- id: turtle_bridge
ros2:
topics:
- topic: /turtle1/pose
message_type: turtlesim/Pose
direction: subscribe
output: pose
- topic: /turtle1/cmd_vel
message_type: geometry_msgs/Twist
direction: publish
input: velocity
qos:
reliable: true
keep_last: 10
inputs:
velocity: planner/cmd_vel
outputs:
- pose
多主题模式每个桥接节点最多支持 64 个主题。
输入/输出 ID 映射
默认情况下,主题名称通过去除前导 / 并将剩余的 / 替换为 _ 来转换为 Adora ID:
| ROS2 主题 | 默认 Adora ID |
|---|---|
/turtle1/pose | turtle1_pose |
/camera/image_raw | camera_image_raw |
在多主题模式下,你可以使用显式的 output(订阅)或 input(发布)字段覆盖此行为。在单主题模式下,直接使用节点声明的 outputs 或 inputs。
服务桥接
服务客户端
从 Adora 向外部 ROS2 服务发送请求并接收响应。
nodes:
- id: add_client
ros2:
service: /add_two_ints
service_type: example_interfaces/AddTwoInts
role: 客户端
inputs:
request: requester/data
outputs:
- response
桥接等待服务可用(最多 10 次重试,每次 2 秒),然后对每个收到的 Arrow 输入:
- 将 Arrow 数据序列化为
AddTwoInts_RequestCDR 消息 - 向 ROS2 服务发送请求
- 等待响应(30 秒超时)
- 将响应反序列化为 Arrow 并通过
response输出发送
服务服务端
将 Adora 处理节点公开为外部 ROS2 客户端可调用的 ROS2 服务。
nodes:
- id: add_server
ros2:
service: /adora_add_two_ints
service_type: example_interfaces/AddTwoInts
role: 服务端
inputs:
response: handler/result
outputs:
- request
- id: handler
path: path/to/handler-node
inputs:
request: add_server/request
outputs:
- result
桥接接收 ROS2 服务请求,为每个请求分配唯一的 request_id(UUID v7),将请求数据作为 Arrow 通过 request 输出转发,元数据中包含 request_id,然后等待处理节点通过 response 输入发送回带有相同 request_id 的响应。响应随后返回给正确的 ROS2 客户端。
工作示例见 examples/ros2-bridge/yaml-bridge-service/。
请求 ID 关联
每个传入的 ROS2 请求被分配一个 request_id 元数据参数。处理节点在发送响应时必须在元数据中包含相同的 request_id。最简单的方法是直接传递 metadata.parameters:
#![allow(unused)]
fn main() {
Event::Input { id, metadata, data } => {
// metadata.parameters 包含 request_id
let result = compute(data);
node.send_service_response("response".into(), metadata.parameters, result)?;
}
}
响应可以以任意顺序到达——桥接通过 request_id 而非到达顺序进行关联。过期的待处理请求在 30 秒后被逐出。待处理请求队列最大为 64——队列满时额外的请求被丢弃。
服务等待和超时
| Behavior | 值 |
|---|---|
| 服务客户端:等待可用性 | 10 次重试,每次 2 秒(共 20 秒) |
| 服务客户端:响应超时 | 30 秒 |
| 服务服务端:待处理请求限制 | 64 |
动作桥接
动作客户端
从 Adora 向外部 ROS2 动作服务端发送目标,接收反馈和结果。
nodes:
- id: fib_client
ros2:
action: /fibonacci
action_type: example_interfaces/Fibonacci
role: 客户端
inputs:
goal: goal_sender/goal
outputs:
- feedback
- result
对每个 Arrow 目标输入:
- 将 Arrow 数据序列化为
Fibonacci_GoalCDR 消息 - 向动作服务端发送目标(30 秒超时)
- 如果被接受,生成后台线程用于反馈和结果
- 反馈消息在
feedback输出上以流式方式到达 - 最终结果在
result输出上到达(5 分钟超时)
反馈和结果流
动作桥接在单独的输出上发送反馈和结果:
feedback:从动作服务端接收到每条反馈消息时流式传输。包含动作的反馈消息(Arrow 格式,例如 Fibonacci 的{partial_sequence: int32[]})result:动作完成时发送一次。包含动作的结果消息(Arrow 格式,例如 Fibonacci 的{sequence: int32[]})
并发目标
桥接最多支持 8 个并发进行中的目标(MAX_CONCURRENT_GOALS)。额外的目标会被丢弃并发出警告。每个目标生成专用的反馈和结果读取线程。
Timeouts
| Behavior | 值 |
|---|---|
| 目标发送超时 | 30 秒 |
| 结果获取超时 | 5 分钟 |
| Feedback | 无超时(流式传输直到动作完成) |
动作服务端
将 Adora 处理节点公开为外部 ROS2 客户端可调用的 ROS2 动作服务端。
nodes:
- id: fib_server
ros2:
action: /fibonacci
action_type: example_interfaces/Fibonacci
role: 服务端
inputs:
feedback: handler/feedback
result: handler/result
outputs:
- goal
- id: handler
path: path/to/handler-node
inputs:
goal: fib_server/goal
outputs:
- feedback
- result
桥接接收来自 ROS2 客户端的目标,自动接受它们,并通过 goal 输出转发目标数据。处理程序计算反馈和结果,并通过 feedback 和 result 输入发回。
工作示例 Fibonacci 见 examples/ros2-bridge/yaml-bridge-action-server/。
目标 ID 元数据
每个目标由作为 goal_id 元数据参数传递的 UUID 字符串标识。桥接在每个 goal 输出上设置 goal_id。处理程序在发送 feedback 和 result 时必须在元数据中包含相同的 goal_id,以便桥接将其关联到正确的目标。
最简单的方法是从目标事件中传递 metadata.parameters:
#![allow(unused)]
fn main() {
Event::Input { id, metadata, data } => match id.as_str() {
"goal" => {
let params = metadata.parameters; // 包含 goal_id
// ... 计算 ...
node.send_output("feedback".into(), params.clone(), feedback)?;
node.send_output("result".into(), params, result)?;
}
// ...
}
}
动作服务端生命周期
- ROS2 客户端发送目标请求
- 桥接自动接受目标并开始执行
- 桥接通过
goal输出发送目标数据,元数据中包含goal_id - 处理程序发送
feedback(零次或多次),带有相同的goal_id - 处理程序发送
result(一次),带有相同的goal_id;桥接将其返回给 ROS2 客户端 - 如果客户端从未请求,结果发送在 5 分钟后超时
不包含数据或无法转发给处理程序的目标会自动中止——桥接向 ROS2 客户端返回 Aborted 状态,使其不会无限期挂起。
目标状态
默认情况下,结果以 Succeeded 状态返回。处理程序可以通过在结果输出上设置 goal_status 元数据参数来覆盖:
goal_status 值 | ROS2 状态 | 用例 |
|---|---|---|
"succeeded"(或省略) | Succeeded | 目标成功完成 |
"aborted" | Aborted | 目标在执行期间失败 |
"canceled" | Canceled | 目标被处理程序取消 |
无法识别的 goal_status 值默认为 Aborted 并记录警告。完全省略 goal_status 默认为 Succeeded。
Rust 示例:
#![allow(unused)]
fn main() {
use adora_node_api::{GOAL_STATUS, GOAL_STATUS_ABORTED, Parameter};
let mut params = metadata.parameters; // 包含 goal_id
params.insert(GOAL_STATUS.to_string(), Parameter::String(GOAL_STATUS_ABORTED.to_string()));
node.send_output("result".into(), params, error_result)?;
}
动作服务端限制
| Behavior | 值 |
|---|---|
| 最大并发目标数 | 8(额外目标收到 Aborted 状态) |
| Auto-accept | 所有目标自动接受 |
| 结果发送超时 | 5 分钟 |
Python 动作服务端处理程序
Python 节点接收目标数据,以 PyArrow 数组形式,元数据字典中包含 goal_id。在反馈/结果输出上传递它:
for event in node:
if event["type"] == "INPUT" and event["id"] == "goal":
goal_id = event["metadata"]["goal_id"]
order = event["value"]["order"][0].as_py()
# Send feedback
node.send_output("feedback", feedback_array, {"goal_id": goal_id})
# Send result (with optional status)
node.send_output("result", result_array, {
"goal_id": goal_id,
"goal_status": "succeeded", # or "aborted", "canceled"
})
C++ 动作服务端处理程序
C++ 节点通过类型安全的元数据访问器访问 goal_id:
auto goal_id = metadata->get_str("goal_id");
// 发送带 goal_id 的反馈
auto fb_metadata = new_metadata();
fb_metadata->set_string("goal_id", goal_id);
send_arrow_output_with_metadata("feedback", feedback_data, fb_metadata);
// 发送带 goal_id 的结果
auto res_metadata = new_metadata();
res_metadata->set_string("goal_id", goal_id);
send_arrow_output_with_metadata("result", result_data, res_metadata);
服务质量(QoS)
配置
在桥接级别设置 QoS(适用于所有主题/通道),或在多主题模式下按主题设置。
nodes:
- id: my_bridge
ros2:
topic: /sensor/data
message_type: sensor_msgs/LaserScan
qos:
reliable: true
durability: transient_local
keep_last: 10
liveliness: automatic
lease_duration: 5.0
max_blocking_time: 0.5
Defaults
| Field | 默认 |
|---|---|
reliable | false(尽力而为) |
durability | volatile |
liveliness | automatic |
lease_duration | infinity |
max_blocking_time | 100ms(仅在 reliable: true 时适用) |
keep_last | 1 |
keep_all | false |
按主题 QoS 覆盖
在多主题模式下,每个主题可以覆盖桥接级别的 QoS:
ros2:
topics:
- topic: /fast_sensor
message_type: sensor_msgs/Imu
direction: subscribe
qos:
reliable: false # override: best effort for this topic
keep_last: 1
- topic: /cmd
message_type: geometry_msgs/Twist
direction: publish
# inherits bridge-level QoS (reliable: true)
qos:
reliable: true # default for all topics
keep_last: 10
验证规则
| Field | 有效值 |
|---|---|
reliable | true、false |
durability | "volatile"、"transient_local" |
liveliness | "automatic"、"manual_by_participant"、"manual_by_topic" |
keep_last | 1 到 10000 |
keep_all | true、false(与 keep_last 互斥) |
lease_duration | 有限非负浮点数(秒) |
max_blocking_time | 有限非负浮点数(秒) |
数据格式:Arrow 结构体
你的节点与桥接之间交换的所有数据使用单行 Arrow StructArray。ROS2 消息中的每个字段成为结构体中的一列。
如何构建 Arrow 消息
Rust 示例:构建 AddTwoInts_Request({a: i64, b: i64}):
#![allow(unused)]
fn main() {
use std::sync::Arc;
use arrow::array::{Array, Int64Array, StructArray};
use arrow::datatypes::{DataType, Field};
fn make_add_request(a: i64, b: i64) -> StructArray {
let fields = vec![
Arc::new(Field::new("a", DataType::Int64, false)),
Arc::new(Field::new("b", DataType::Int64, false)),
];
let arrays: Vec<Arc<dyn Array>> = vec![
Arc::new(Int64Array::from(vec![a])),
Arc::new(Int64Array::from(vec![b])),
];
StructArray::try_new(fields.into(), arrays, None)
.expect("failed to create struct array")
}
}
读取响应({sum: i64}):
#![allow(unused)]
fn main() {
use arrow::array::{Int64Array, StructArray};
fn read_response(data: &dyn arrow::array::Array) -> i64 {
let struct_array = data
.as_any()
.downcast_ref::<StructArray>()
.expect("expected struct array");
struct_array
.column_by_name("sum")
.expect("missing 'sum' field")
.as_any()
.downcast_ref::<Int64Array>()
.expect("expected Int64Array")
.value(0)
}
}
ROS2 类型到 Arrow 类型的映射
| ROS2 类型 | Arrow 类型 | Rust Arrow 数组 |
|---|---|---|
bool | Boolean | BooleanArray |
int8 | Int8 | Int8Array |
int16 | Int16 | Int16Array |
int32 | Int32 | Int32Array |
int64 | Int64 | Int64Array |
uint8 / byte / char | UInt8 | UInt8Array |
uint16 | UInt16 | UInt16Array |
uint32 | UInt32 | UInt32Array |
uint64 | UInt64 | UInt64Array |
float32 | Float32 | Float32Array |
float64 | Float64 | Float64Array |
string | Utf8 | StringArray |
wstring | Utf8(CDR 端编码为 UTF-16) | StringArray |
| 嵌套消息 | Struct | StructArray |
序列和数组
| ROS2 类型 | Arrow 类型 | Rust Arrow 数组 |
|---|---|---|
变长序列(int32[]) | List | ListArray |
有界序列(int32[<=10]) | List(长度已验证) | ListArray |
固定大小数组(int32[3]) | FixedSizeList | FixedSizeListArray |
示例:从 Fibonacci 反馈中读取 ListArray({partial_sequence: int32[]}):
#![allow(unused)]
fn main() {
use arrow::array::{Int32Array, ListArray, StructArray};
let struct_array = data.as_any().downcast_ref::<StructArray>().unwrap();
let list = struct_array
.column_by_name("partial_sequence")
.unwrap()
.as_any()
.downcast_ref::<ListArray>()
.unwrap();
let values = list
.value(0)
.as_any()
.downcast_ref::<Int32Array>()
.unwrap()
.values()
.to_vec();
}
完整 YAML 参考
nodes:
- id: my_bridge
ros2:
# --- Mode (exactly one required) ---
# Single topic mode
topic: /topic_name # ROS2 主题名称
message_type: package/TypeName # ROS2 消息类型
direction: subscribe # subscribe(默认)| publish
# Multi-topic mode (mutually exclusive with topic)
topics:
- topic: /topic_a
message_type: package/TypeA
direction: subscribe
output: custom_output_id # 覆盖默认 ID 映射
qos: # per-topic QoS override
reliable: true
- topic: /topic_b
message_type: package/TypeB
direction: publish
input: custom_input_id # 覆盖默认 ID 映射
# Service mode (mutually exclusive with topic/topics/action)
service: /service_name # ROS2 服务名称
service_type: package/TypeName # ROS2 服务类型
role: client # client | server
# Action mode (mutually exclusive with topic/topics/service)
action: /action_name # ROS2 动作名称
action_type: package/TypeName # ROS2 动作类型
role: client # client | server
# --- QoS (optional, applies to all channels) ---
qos:
reliable: false # true | false (default: false = best effort)
durability: volatile # volatile(默认)| transient_local
liveliness: automatic # automatic | manual_by_participant | manual_by_topic
lease_duration: 5.0 # seconds (default: infinity)
max_blocking_time: 0.1 # seconds (default: 0.1, reliable only)
keep_last: 1 # 1-10000 (default: 1)
keep_all: false # true | false (default: false)
# --- Optional ROS2 node config ---
namespace: / # ROS2 命名空间(默认:"/")
node_name: my_ros_node # ROS2 节点名称(默认:adora 节点 id)
# --- Standard Adora node fields ---
inputs:
input_id: source_node/output_id
outputs:
- output_id
使用场景
1. 订阅传感器数据(turtlesim 位姿)
nodes:
- id: pose_bridge
ros2:
topic: /turtle1/pose
message_type: turtlesim/Pose
outputs:
- pose
- id: my_processor
path: ./target/debug/my-processor
inputs:
pose: pose_bridge/pose
#![allow(unused)]
fn main() {
// 在 my_processor 中:以 Arrow 形式接收 turtlesim/Pose
Event::Input { id, data, .. } if id.as_str() == "pose" => {
let s = data.as_any().downcast_ref::<StructArray>().unwrap();
let x = s.column_by_name("x").unwrap()
.as_any().downcast_ref::<Float32Array>().unwrap().value(0);
let y = s.column_by_name("y").unwrap()
.as_any().downcast_ref::<Float32Array>().unwrap().value(0);
println!("Turtle at ({x}, {y})");
}
}
2. 发布速度命令
nodes:
- id: planner
path: ./target/debug/planner
inputs:
tick: adora/timer/millis/100
outputs:
- cmd_vel
- id: cmd_bridge
ros2:
topic: /turtle1/cmd_vel
message_type: geometry_msgs/Twist
direction: publish
inputs:
cmd_vel: planner/cmd_vel
#![allow(unused)]
fn main() {
// 在 planner 中:以 Arrow 形式发送 geometry_msgs/Twist
// Twist 有嵌套的 Vector3 字段:linear {x,y,z} 和 angular {x,y,z}
fn make_twist(linear_x: f64, angular_z: f64) -> StructArray {
let vec3_fields = vec![
Arc::new(Field::new("x", DataType::Float64, false)),
Arc::new(Field::new("y", DataType::Float64, false)),
Arc::new(Field::new("z", DataType::Float64, false)),
];
let linear = StructArray::try_new(
vec3_fields.clone().into(),
vec![
Arc::new(Float64Array::from(vec![linear_x])) as _,
Arc::new(Float64Array::from(vec![0.0])) as _,
Arc::new(Float64Array::from(vec![0.0])) as _,
],
None,
).unwrap();
let angular = StructArray::try_new(
vec3_fields.into(),
vec![
Arc::new(Float64Array::from(vec![0.0])) as _,
Arc::new(Float64Array::from(vec![0.0])) as _,
Arc::new(Float64Array::from(vec![angular_z])) as _,
],
None,
).unwrap();
let fields = vec![
Arc::new(Field::new("linear", linear.data_type().clone(), false)),
Arc::new(Field::new("angular", angular.data_type().clone(), false)),
];
StructArray::try_new(
fields.into(),
vec![Arc::new(linear) as _, Arc::new(angular) as _],
None,
).unwrap()
}
}
3. 多主题双向桥接
在单个 ROS2 节点上订阅位姿并发布速度。
nodes:
- id: turtle_bridge
ros2:
topics:
- topic: /turtle1/pose
message_type: turtlesim/Pose
direction: subscribe
output: pose
- topic: /turtle1/cmd_vel
message_type: geometry_msgs/Twist
direction: publish
input: velocity
qos:
reliable: true
keep_last: 10
inputs:
velocity: planner/cmd_vel
outputs:
- pose
- id: planner
path: ./target/debug/planner
inputs:
pose: turtle_bridge/pose
tick: adora/timer/millis/100
outputs:
- cmd_vel
4. 服务客户端:调用外部 ROS2 服务
nodes:
- id: requester
path: ./target/debug/requester
inputs:
tick: adora/timer/millis/1000
response: add_client/response
outputs:
- request
- id: add_client
ros2:
service: /add_two_ints
service_type: example_interfaces/AddTwoInts
role: 客户端
inputs:
request: requester/request
outputs:
- response
前提条件:先运行 ROS2 服务:
ros2 run examples_rclcpp_minimal_service service_main
5. 服务服务端:将 Adora 处理程序公开为 ROS2 服务
nodes:
- id: add_server
ros2:
service: /add_two_ints
service_type: example_interfaces/AddTwoInts
role: 服务端
inputs:
response: handler/response
outputs:
- request
- id: handler
path: ./target/debug/handler
inputs:
request: add_server/request
outputs:
- response
处理程序以 Arrow 形式接收 {a: i64, b: i64},计算结果,并发回 {sum: i64}。外部 ROS2 客户端可以调用此服务:
ros2 service call /add_two_ints example_interfaces/srv/AddTwoInts "{a: 3, b: 5}"
6. 动作客户端:长时间运行的 Fibonacci 目标
nodes:
- id: goal_sender
path: ./target/debug/goal-sender
inputs:
tick: adora/timer/millis/5000
feedback: fib_client/feedback
result: fib_client/result
outputs:
- goal
- id: fib_client
ros2:
action: /fibonacci
action_type: example_interfaces/Fibonacci
role: 客户端
inputs:
goal: goal_sender/goal
outputs:
- feedback
- result
前提条件:在数据流之前启动动作服务端:
ros2 run examples_rclcpp_action_server fibonacci_action_server
目标节点发送 {order: int32},接收流式 {partial_sequence: int32[]} 反馈,以及最终的 {sequence: int32[]} 结果。
7. 动作服务端:将 Adora 处理程序公开为 ROS2 动作
nodes:
- id: fib_server
ros2:
action: /fibonacci
action_type: example_interfaces/Fibonacci
role: 服务端
inputs:
feedback: handler/feedback
result: handler/result
outputs:
- goal
- id: handler
path: ./target/debug/handler
inputs:
goal: fib_server/goal
outputs:
- feedback
- result
处理程序接收元数据中带有 goal_id 的 {order: int32} 目标,发送 {partial_sequence: int32[]} 反馈,以及最终的 {sequence: int32[]} 结果——所有消息在元数据中都带有相同的 goal_id。外部 ROS2 客户端可以发送目标:
ros2 action send_goal /fibonacci example_interfaces/action/Fibonacci "{order: 10}"
限制和已知约束
- 动作服务端自动接受:所有传入目标自动接受。处理程序无法在执行开始前拒绝目标。
- 不支持动作取消:客户端和服务端都不处理 ROS2 取消请求。
- 无
wait_for_action_server:ros2_client库不提供此 API。在数据流之前启动动作服务端。如果服务端不可用,第一个目标将超时(30 秒)。 - 单次服务客户端:服务客户端按顺序处理请求——每个请求阻塞直到响应到达(或 30 秒超时)。
- 服务/动作通道 QoS 统一:
qos配置适用于所有服务/动作子通道(goal、result、cancel、feedback、status)。不支持按通道配置 QoS。 - 需要
AMENT_PREFIX_PATH:如果找不到 ROS2 消息定义,桥接在启动时会失败。 - 最多 64 个主题:多主题模式每个桥接节点最多支持 64 个主题。
- 最多 8 个并发动作目标:达到限制时,额外目标收到
Aborted状态。 - 最多 64 个待处理服务请求(服务端):队列满时请求被丢弃。
最佳实践
运行前 source ROS2 环境。 确保 AMENT_PREFIX_PATH 已设置并包含所有必需的消息包。如果找不到定义,桥接会记录错误。
在数据流之前启动动作服务端。 没有动作服务端的等待机制。如果服务端未就绪,第一次目标发送将在 30 秒后超时。
对相关主题使用多主题模式。 在同一桥接节点上桥接 /turtle1/pose(订阅)和 /turtle1/cmd_vel(发布)比使用两个单独的桥接节点减少资源使用。
精确匹配 Arrow 字段名。 桥接验证 Arrow 结构体字段名与 ROS2 消息定义匹配。缺失字段使用默认值(数字为零,字符串为空)。多余字段会导致错误。
在多主题模式下使用显式 output/input。 默认 ID 映射(去除 /,将 / 替换为 _)对深层主题名称可能造成混淆。显式 ID 使数据流 YAML 更具自文档性。
设置 QoS 以匹配 ROS2 发布者/订阅者。 QoS 不匹配(例如可靠订阅者与尽力而为发布者)会导致静默通信失败。使用 ros2 topic info -v /topic_name 查看现有 QoS 设置。
在服务响应中传递 request_id。 桥接使用 request_id 元数据参数将响应与请求关联。如果处理程序未在响应元数据中包含 request_id,桥接无法将响应与原始 ROS2 请求匹配。
WebSocket 控制面
Adora 的控制面使用 WebSocket 连接进行 CLI、协调器和守护进程之间的所有通信。单个 Axum 服务器在一个端口上暴露三个路由,取代了之前的多端口 TCP 设计。JSON 文本帧承载基于 UUID 关联的请求/应答协议,以及用于日志流的即发即弃事件。
功能一览
| 特性 | 详情 |
|---|---|
| 路由 | /api/control(CLI)、/api/daemon(守护进程)、/health |
| 传输格式 | JSON 文本帧 + 用于主题数据的二进制帧 |
| 协议 | UUID 关联的请求/应答 + 即发即弃事件 |
| 消息大小限制 | 1 MiB(MAX_CONTROL_MESSAGE_BYTES) |
| 并发限制 | 256 个连接(MAX_WS_CONNECTIONS) |
| 服务器框架 | Axum + Tower 中间件 |
| 客户端库 | tokio-tungstenite(集成测试、守护进程),自定义 WsSession(CLI) |
| 安全 | 重注册保护、守护进程 ID 验证、机器 ID 长度限制 |
架构
Single Axum server (one port)
┌────────────────────────────┐
│ /api/control (CLI) │
CLI ──── WS ────────>│ /api/daemon (Daemons) │
│ /health (HTTP GET) │
Daemon ── WS ───────>│ │
└──────────┬─────────────────┘
│ mpsc::Sender<Event>
v
Coordinator
(event loop)
协调器绑定单个 TcpListener 并提供 Axum 路由。每次 WebSocket 升级都生成一个处理任务,通过 mpsc::Sender<Event> 通道与协调器的主事件循环通信。
关键源文件
| File | Role |
|---|---|
binaries/coordinator/src/ws_server.rs | 路由、serve()、常量、ShutdownTrigger |
binaries/coordinator/src/ws_control.rs | /api/control 处理器 |
binaries/coordinator/src/ws_daemon.rs | /api/daemon 处理器、安全、事件转换 |
binaries/cli/src/ws_client.rs | WsSession 同步客户端包装器 |
libraries/message/src/ws_protocol.rs | WsRequest、WsResponse、WsEvent、WsMessage 类型 |
线路协议
所有消息都是 JSON 文本帧。存在三种消息形式:
WsRequest(客户端 -> 服务端)
{
"id": "550e8400-e29b-41d4-a716-446655440000",
"method": "control",
"params": { "List": null }
}
| Field | 类型 | 描述 |
|---|---|---|
id | UUID | 用于应答关联的唯一请求标识符 |
method | string | "control" 用于 CLI 请求,"daemon_event" / "daemon_command" 用于守护进程 |
params | object | 序列化的 ControlRequest 或 Timestamped<CoordinatorRequest> |
WsResponse(服务端 -> 客户端)
Success:
{
"id": "550e8400-e29b-41d4-a716-446655440000",
"result": { "DataflowList": [] }
}
Error:
{
"id": "550e8400-e29b-41d4-a716-446655440000",
"error": "no running dataflow with id ..."
}
| Field | 类型 | 描述 |
|---|---|---|
id | UUID | 匹配发起请求的 id |
result | object? | 成功时存在(序列化的 ControlRequestReply) |
error | string? | 失败时存在 |
WsEvent(双向)
{
"event": "log",
"payload": { "message": "sensor started", "level": "info" }
}
在 LogSubscribe/BuildLogSubscribe 被确认后用于日志流传输。
Dispatch
每个处理器使用自己的策略解析传入帧以保持 u128 保真度(见 u128 序列化):
- CLI(
ws_client.rs):对result/payload字段使用扁平的IncomingFrame结构体配合serde_json::value::RawValue,完全避免使用serde_json::Value。通过event(日志推送)或id(响应)的存在来区分。 - 协调器控制处理器(
ws_control.rs):解析为WsRequest(始终是来自 CLI 的请求)。 - 协调器守护进程处理器(
ws_daemon.rs):检查"method"键以区分请求和响应。对请求使用DaemonWsRequestRaw辅助结构。 - 守护进程(
coordinator.rs):使用CoordinatorCommandRaw/RegisterReplyRaw辅助结构直接从原始 JSON 文本解析。
ws_protocol.rs 中定义了一个 WsMessage 无标签枚举用于通用分发,但生产处理器未使用:
#![allow(unused)]
fn main() {
#[serde(untagged)]
pub enum WsMessage {
Request(WsRequest),
Response(WsResponse),
Event(WsEvent),
}
}
CLI 控制面(/api/control)
CLI 连接到 /api/control 发送 ControlRequest 命令并接收 ControlRequestReply 响应。
连接生命周期
- 连接 —— HTTP 升级到 WebSocket
- 请求-应答 —— CLI 发送
WsRequest,协调器处理ControlRequest,发送WsResponse - 日志订阅(可选)—— CLI 发送
LogSubscribe/BuildLogSubscribe,协调器以WsResponse确认,然后推送WsEvent{event:"log"}帧 - 关闭 —— CLI 发送
Close帧或断开连接
支持的 ControlRequest 变体
| Variant | 描述 |
|---|---|
List | 列出所有运行中的数据流 |
Build | 触发数据流构建 |
WaitForBuild | 阻塞直到构建完成 |
Start | 启动数据流 |
WaitForSpawn | 阻塞直到节点生成 |
Stop / StopByName | 停止运行中的数据流 |
Reload | 热重载节点/算子 |
Check | 检查数据流状态 |
Destroy | 关闭所有守护进程 |
Logs | 获取历史日志 |
Info | 获取数据流详情 |
DaemonConnected | 检查是否有守护进程连接 |
ConnectedMachines | 列出已连接的守护进程 |
LogSubscribe | 订阅实时数据流日志 |
BuildLogSubscribe | 订阅实时构建日志 |
CliAndDefaultDaemonOnSameMachine | 检查共置 |
GetNodeInfo | 获取节点元数据 |
TopicSubscribe | Subscribe to live topic data via binary WS frames (details) |
TopicUnsubscribe | 取消主题订阅 |
日志订阅流程
CLI Coordinator
│ │
│─── WsRequest{LogSubscribe} ─>│
│ │ (check dataflow exists)
│<── WsResponse{subscribed} ───│
│ │
│<── WsEvent{event:"log"} ────│ (repeated)
│<── WsEvent{event:"log"} ────│
│ │
│─── Close ───────────────────>│ (log_subscribers dropped)
如果找不到数据流,协调器返回带有错误的 WsResponse,不发送事件。
WsSession(CLI 客户端)
WsSession 是一个同步包装器,将阻塞的 CLI 代码桥接到异步 WebSocket 连接。它创建内部的 tokio::runtime::Runtime(当前线程)并生成异步 session_loop 任务。
CLI thread (sync) session_loop (async)
│ │
│── SessionCommand::Request ────────────>│── WsRequest ──> server
│ │<── WsResponse ──
│<── oneshot reply ─────────────────────│
│ │
│── SessionCommand::SubscribeLogs ──────>│── WsRequest ──> server
│ │<── WsResponse (ack)
│<── oneshot ack ───────────────────────│
│<── std_mpsc log events ───────────────│<── WsEvent ──
会话循环维护:
pending_requests: HashMap<Uuid, oneshot::Sender>—— 用于请求-应答关联pending_subscribes: HashMap<Uuid, (ack_tx, log_tx)>—— 用于订阅确认路由log_subscribers: Vec<std_mpsc::Sender>—— 用于广播日志事件pending_topic_subscribes: HashMap<Uuid, (ack_tx, data_tx)>—— 用于主题订阅确认路由topic_subscribers: HashMap<Uuid, std_mpsc::Sender>—— 用于按订阅 UUID 分发二进制帧
Binary WS frames (topic data) are dispatched separately from text frames. See WebSocket Topic Data Channel for details.
断开连接时,所有待处理请求通过其 oneshot 通道收到错误。
守护进程面(/api/daemon)
守护进程连接到 /api/daemon 进行注册、事件报告和接收协调器命令。
注册流程
Daemon Coordinator
│ │
│── WsRequest{Register} ─────>│
│ │ (validate, assign daemon_id)
│ │ (track connection + cmd channel)
│ │
│── WsRequest{Event{...}} ───>│ (subsequent events)
- 守护进程发送包含
DaemonRegisterRequest(版本 + 机器 ID)的Register请求 - 协调器验证版本兼容性和机器 ID 长度
- 协调器分配
DaemonId并存储DaemonConnection(包含用于向守护进程发送命令的cmd_tx通道) - 连接通过
tracked_daemon_id跟踪,用于断开时的清理
事件转换
守护进程事件被转换为协调器内部 Event 变体:
| DaemonEvent | 协调器事件 |
|---|---|
AllNodesReady | Event::Dataflow { ReadyOnDaemon } |
AllNodesFinished | Event::Dataflow { DataflowFinishedOnDaemon } |
Heartbeat | Event::DaemonHeartbeat |
Log(message) | Event::Log(message) |
Exit | Event::DaemonExit |
NodeMetrics | Event::NodeMetrics |
BuildResult | Event::DataflowBuildResult |
SpawnResult | Event::DataflowSpawnResult |
双向通信
协调器可以通过存储在 DaemonConnection 中的 cmd_tx 通道向守护进程发送命令。守护进程处理器维护 pending_replies: HashMap<Uuid, oneshot::Sender> 来关联守护进程响应与协调器发起的请求。
守护进程处理器上的消息路由:
- 帧有
"method"键 -> 守护进程请求(注册或事件) - 帧缺少
"method"键 -> 守护进程对协调器命令的响应
u128 序列化变通方案
uhlc::ID 包含一个 NonZeroU128,超出了 serde_json::Value::Number 范围(仅 i64/u64/f64)。使用 serde_json::to_value() 会报 “number out of range” 错误,而 serde_json::from_slice::<Value>() 会通过存储为 f64 静默丢失精度。
所有生产代码对包含 uhlc::Timestamp 的数据绕过 serde_json::Value:
| Component | Serialization | Deserialization |
|---|---|---|
守护进程(coordinator.rs) | to_string + format! | 辅助结构体(RegisterReplyRaw、CoordinatorCommandRaw)+ from_str |
协调器控制(ws_control.rs) | to_string + format! 用于应答 | 不适用(CLI 请求不包含 u128) |
协调器守护进程(ws_daemon.rs) | N/A | DaemonWsRequestRaw + from_str |
协调器状态(state.rs) | str::from_utf8 + format!(原始字节嵌入) | N/A |
CLI(ws_client.rs) | 不适用(请求不包含 u128) | IncomingFrame 配合 serde_json::value::RawValue |
集成测试同样通过 format!() + serde_json::to_string()(非 to_value())手动构造 WsRequest JSON 字符串以匹配真实的线路格式。
安全
重注册保护
每个守护进程 WebSocket 连接只允许一次 Register 请求。如果连接尝试第二次注册,协调器记录警告并关闭连接:
daemon attempted re-register on same connection, rejecting
守护进程 ID 验证
注册后,每条 Event 消息必须包含与注册时分配的 daemon_id 匹配的 ID。不匹配的 ID 会导致连接终止:
daemon sent event with mismatched id: expected `X`, got `Y` -- closing connection
机器 ID 长度验证
DaemonRegisterRequest 中的 machine_id 字段限制为 256 字节。超大值会导致连接终止。
连接和消息限制
| Limit | 值 | 实施方 |
|---|---|---|
| 最大消息大小 | 1 MiB | WebSocketUpgrade::max_message_size |
| 最大并发连接数 | 256 | Tower ConcurrencyLimitLayer |
连接生命周期和保活
Establishment
/api/control 和 /api/daemon 都使用标准 HTTP/1.1 WebSocket 升级。Axum WebSocketUpgrade 提取器处理握手。
Ping/pong
两个处理器都用包含相同载荷的 Pong 帧响应 Ping 帧:
#![allow(unused)]
fn main() {
Ok(Message::Ping(data)) => {
let _ = ws_tx.send(Message::Pong(data)).await;
continue;
}
}
优雅关闭
收到 Close 帧时:
- 控制处理器:中断处理循环,丢弃日志订阅者通道
- 守护进程处理器:中断循环,然后发出
Event::DaemonExit { daemon_id }以立即清理
断开时的清理
控制连接:
log_tx通道被丢弃,停止向该客户端转发日志- 无需清理协调器状态(控制连接是无状态的)
守护进程连接:
- 如果
daemon_id被跟踪则发出DaemonExit事件 cmd_tx和pending_replies被丢弃- 协调器从其连接映射中移除守护进程
WsSession(CLI 客户端):
pending_requests中的所有条目收到Err("WS connection closed")pending_subscribes中的所有条目收到Err("WS connection closed")
消息流示例
CLI 列出数据流
CLI WsSession Coordinator
│ │ │
│── request(&List) ───────────>│ │
│ │── WsRequest ────────────────>│
│ │ id: "abc-123" │
│ │ method: "control" │
│ │ params: "List" │
│ │ │
│ │ ControlEvent::IncomingRequest
│ │ reply via oneshot
│ │ │
│ │<── WsResponse ──────────────│
│ │ id: "abc-123" │
│ │ result: {DataflowList:[]} │
│ │ │
│<── ControlRequestReply ─────│ │
守护进程注册
Daemon Coordinator
│ │
│── WsRequest ─────────────────────────────>│
│ method: "daemon_event" │
│ params: {inner: Register{...}, │
│ timestamp: ...} │
│ │ validate version
│ │ validate machine_id
│ │ assign daemon_id
│ │ store DaemonConnection
│ │
│── WsRequest{Event{Heartbeat}} ──────────>│
│ │ Event::DaemonHeartbeat
│ │
│ (on WS close) ────>│ Event::DaemonExit
日志订阅生命周期
CLI WsSession Coordinator
│ │ │
│── subscribe_logs() ───>│ │
│ │── WsRequest ──────────>│
│ │ params: LogSubscribe │
│ │ │ find dataflow
│ │<── WsResponse ────────│ {subscribed: true}
│<── ack (Ok) ──────────│ │
│ │ │
│ │<── WsEvent{log} ──────│ (node produces log)
│<── log_rx.recv() ─────│ │
│ │<── WsEvent{log} ──────│
│<── log_rx.recv() ─────│ │
│ │ │
│ (drop session) ─────>│── Close ─────────────>│ (log_subscribers dropped)
测试覆盖
测试层级
| Tier | Location | Tests | 覆盖内容 |
|---|---|---|---|
| 单元测试(协议) | libraries/message/src/ws_protocol.rs | 10 | 往返序列化、无标签分发、错误情况 |
| 单元测试(客户端) | binaries/cli/src/ws_client.rs | 6 | 响应路由、订阅确认、主题订阅确认、孤立处理、断开 |
| 集成测试(控制) | binaries/coordinator/tests/ws_control_tests.rs | 11 | 健康检查、列表、无效 JSON/参数、销毁、DaemonConnected、ping/pong、并发请求、连接关闭、日志订阅 |
| 集成测试(守护进程) | binaries/coordinator/tests/ws_daemon_tests.rs | 4 | 注册、注册后状态、断开清理、ping/pong |
| 端到端测试(WsSession) | tests/ws-cli-e2e.rs | 4 | WsSession + 协调器:列表、状态、停止、多请求 |
| Total | 35 |
Key test patterns
轮询超时机制:集成测试通过轮询协调器状态(例如 DaemonConnected),设置 2 秒截止时间和 20 毫秒休眠间隔,避免不稳定的时序假设。
禁止嵌套运行时:端到端测试在后台 std::thread 上运行协调器并使用独立的 tokio 运行时,而 WsSession(会创建自己的当前线程运行时)则在测试主线程上运行。这样可以避免 “cannot start a runtime from within a runtime” 恐慌错误。
测试中的 u128 变通方案:守护进程测试辅助函数通过 format!() + serde_json::to_string()(而非 serde_json::to_value())手动构造 WsRequest JSON 字符串,以保留线上传输的 uhlc::ID u128 值。
测试协调器设置:集成测试和端到端测试均使用 adora_coordinator::start_testing(),该函数绑定到端口 0(由操作系统分配)并接受空的外部事件流。
Configuration Reference
Constants
| Constant | 值 | File | 用途 |
|---|---|---|---|
MAX_CONTROL_MESSAGE_BYTES | 1 MiB (1,048,576) | ws_server.rs | WebSocket 最大帧大小 |
MAX_WS_CONNECTIONS | 256 | ws_server.rs | Tower concurrency limit |
Server setup
#![allow(unused)]
fn main() {
// Production: called by coordinator's main startup
let (port, shutdown, future) = ws_server::serve(bind_addr, event_tx, clock).await?;
tokio::spawn(future);
// ...
shutdown.shutdown(); // graceful stop
}
Test setup
#![allow(unused)]
fn main() {
// Binds to port 0, returns (port, future)
let (port, future) = adora_coordinator::start_testing(
"127.0.0.1:0".parse().unwrap(),
futures::stream::empty(),
).await?;
}
Shutdown
ShutdownTrigger 封装了一个 oneshot::Sender<()>。调用 .shutdown() 会发送信号,Axum 服务器通过 with_graceful_shutdown 接收该信号。正在处理的请求会继续完成,新的连接将被拒绝。
WebSocket 主题数据通道
主题数据通道扩展了 WebSocket 控制面,将实时数据流消息从协调器代理到 CLI 客户端。CLI 命令(如 topic echo、topic hz 和 topic info)无需直接访问 Zenoh 网络,而是通过现有的 WebSocket 连接以二进制帧的形式接收消息数据。
动机
| 场景 | Before (Zenoh direct) | After (WS proxy) |
|---|---|---|
| CLI 与守护进程在同一台机器上 | Works | Works |
| CLI 远程访问,Zenoh 可达 | Works | Works |
| CLI 远程访问,无法访问 Zenoh | Fails | Works |
| Browser-based web UI | Impossible | Possible |
| 嵌入式目标设备,无本地磁盘 | Cannot record locally | --proxy 将数据流式传输到 CLI |
关键设计思路:CLI 和未来的 Web UI 通过 WebSocket 连接到协调器。由协调器代为订阅 Zenoh 并以二进制帧转发消息,使主题检查功能在 WebSocket 连接可达的任何地方都能使用。
架构
CLI ──── WS (binary frames) ────> Coordinator ──── Zenoh sub ────> Daemon
(Zenoh proxy) (debug publish)
协调器充当 Zenoh 代理:
- CLI 通过现有的文本帧 WS 协议发送
TopicSubscribe请求 - 协调器验证数据流并打开 Zenoh 订阅者
- 协调器将每个 Zenoh 采样以二进制 WS 帧转发回 CLI
- CLI 按订阅 UUID 将二进制帧分发到相应的消费者
关键源文件
| File | Role |
|---|---|
libraries/message/src/cli_to_coordinator.rs | TopicSubscribe、TopicUnsubscribe 请求变体 |
libraries/message/src/coordinator_to_cli.rs | TopicSubscribed reply variant |
binaries/coordinator/src/ws_control.rs | Zenoh 代理:订阅并转发二进制帧 |
binaries/coordinator/src/control.rs | ControlEvent::TopicSubscribe for validation |
binaries/cli/src/ws_client.rs | WsSession::subscribe_topics(),二进制帧分发 |
binaries/cli/src/command/topic/echo.rs | 通过 WS 进行主题回显 |
binaries/cli/src/command/topic/hz.rs | 通过 WS 进行主题频率测量 |
binaries/cli/src/command/topic/info.rs | 通过 WS 获取主题元数据/统计信息 |
binaries/cli/src/command/record.rs | --proxy 标志用于基于 WS 的录制 |
线路协议
订阅握手(JSON 文本帧)
订阅使用现有的基于 UUID 关联的请求-应答协议:
请求(CLI -> 协调器):
{
"id": "abc-123",
"method": "control",
"params": {
"TopicSubscribe": {
"dataflow_id": "550e8400-...",
"topics": [["camera_node", "image"], ["lidar_node", "points"]]
}
}
}
响应(协调器 -> CLI):
{
"id": "abc-123",
"result": {
"TopicSubscribed": {
"subscription_id": "7f1b3a00-..."
}
}
}
取消订阅(CLI -> 协调器):
{
"id": "def-456",
"method": "control",
"params": {
"TopicUnsubscribe": {
"subscription_id": "7f1b3a00-..."
}
}
}
Binary data frames
握手完成后,协调器推送二进制 WS 帧。每个帧都有一个固定大小的头部:
0 16 N
├───────────────────┼──────────────────────────────┤
│ subscription_id │ Timestamped<InterDaemonEvent>│
│ (16 bytes UUID) │ (bincode serialized) │
└───────────────────┴──────────────────────────────┘
| Field | Size | 描述 |
|---|---|---|
subscription_id | 16 bytes | 与 TopicSubscribed 确认匹配的 UUID,用于多路复用 |
| payload | variable | 来自 Zenoh 的原始 Timestamped<InterDaemonEvent> bincode 字节 |
16 字节的 UUID 前缀允许在单个 WS 连接上多路复用多个订阅,而无需额外的帧开销。
Data Flow
CLI WsSession Coordinator
│ │ │
│── subscribe_topics() ───────>│ │
│ │── WsRequest{TopicSubscribe} >│
│ │ │ validate dataflow
│ │ │ open Zenoh session (lazy)
│ │ │ spawn subscriber tasks
│ │<── WsResponse{TopicSubscribed}│
│<── (sub_id, data_rx) ───────│ │
│ │ │
│ │ ┌── Zenoh sample ──────│ Daemon publishes
│ │<──────│ Binary frame │
│<── data_rx.recv() ──────────│ │ (sub_id + payload) │
│ │ │ │
│ │<──────│ Binary frame │
│<── data_rx.recv() ──────────│ │ │
│ │ └ │
│ │ │
│ (drop session) ───────────>│── Close ────────────────────>│ abort subscriber tasks
Coordinator internals
- 验证:
ControlEvent::TopicSubscribe被发送到协调器事件循环,由其检查数据流是否存在以及是否启用了publish_all_messages_to_zenoh: true - Zenoh 延迟初始化:协调器的 Zenoh 会话在第一次
TopicSubscribe请求时打开,并在同一 WS 连接的后续订阅中复用 - 按主题分配任务:每个
(node_id, data_id)对会生成一个 tokio 任务,订阅对应的 Zenoh 主题并将采样转发到二进制帧通道 - 背压:二进制帧通道容量为 64。使用
try_send—— 如果通道已满(消费者过慢),采样将被静默丢弃,而不是阻塞 Zenoh 订阅者 - 清理:当 WS 连接关闭时,所有订阅者任务将被终止
WsSession (CLI side)
The WsSession::subscribe_topics() method:
- 序列化
TopicSubscribe请求 - 通过内部命令通道发送
SessionCommand::SubscribeTopics - 异步
session_loop将其包装为WsRequest并发送 - 收到
TopicSubscribed确认后,将data_tx发送者注册到以subscription_id为键的topic_subscribers中 - 二进制帧的分发方式是:提取前 16 字节作为 UUID,将剩余部分发送到匹配的
data_tx
session_loop 中维护的状态:
pending_topic_subscribes: HashMap<Uuid, (ack_tx, data_tx)>—— 等待确认topic_subscribers: HashMap<Uuid, Sender>—— 正在接收二进制数据的活跃订阅
前提条件
数据流描述符必须启用调试消息发布:
_unstable_debug:
publish_all_messages_to_zenoh: true
如果未启用,协调器将拒绝 TopicSubscribe 并返回:
dataflow {id} not found or publish_all_messages_to_zenoh not enabled
CLI Commands
adora topic echo
将主题数据实时流式输出到终端。
# Echo a single topic
adora topic echo -d my-dataflow camera_node/image
# Echo multiple topics
adora topic echo -d my-dataflow robot1/pose robot2/vel
# JSON output for piping
adora topic echo -d my-dataflow robot1/pose --format json
内部实现:调用 session.subscribe_topics(),从 data_rx 通道接收 Timestamped<InterDaemonEvent>,反序列化 Arrow 数据,并以表格或 JSON 格式渲染。
adora topic hz
交互式 TUI,显示每个主题的发布频率统计信息。
# All topics
adora topic hz -d my-dataflow --window 10
# Specific topics
adora topic hz -d my-dataflow robot1/pose robot2/vel --window 5
使用 ratatui 构建 TUI。后台 std::thread 从 data_rx 接收事件,并通过 BTreeMap<(node_id, data_id), index> 查找分发到每个主题的 HzStats 跟踪器。
adora topic info
一次性获取主题元数据和统计信息。
adora topic info -d my-dataflow camera_node/image --duration 5
在 --duration 指定的秒数内收集消息,然后显示类型信息、发布者、订阅者(来自描述符)、消息数量和带宽。
adora record --proxy
通过 WebSocket 流式传输数据流数据以进行本地录制。
# Start dataflow first
adora start dataflow.yml --detach
# Record via proxy (data streams through coordinator to CLI)
adora record dataflow.yml --proxy -o capture.adorec
# Record specific topics
adora record dataflow.yml --proxy --topics sensor/image,lidar/points
使用场景:目标机器(运行守护进程的机器)没有本地磁盘或存储空间有限。--proxy 标志将数据通过协调器 WebSocket 路由到 CLI 所在的机器,在本地写入 .adorec 文件。
不使用 --proxy(默认行为)时,会向数据流中注入一个录制节点,直接在守护进程所在的机器上录制。
Zenoh Topic Format
协调器使用 adora_core::topics::zenoh_output_publish_topic() 中的格式订阅 Zenoh 主题:
adora/{dataflow_id}/{node_id}/{data_id}
每个主题的负载为 Timestamped<InterDaemonEvent>,使用 bincode 序列化。协调器将这些字节原样转发(前置订阅 UUID)—— 无需重新序列化。
Backpressure and Performance
| 参数 | 值 | Rationale |
|---|---|---|
| 二进制帧通道容量 | 64 | 在延迟和内存之间取得平衡 |
| Drop policy | Drop on full | 优先保证新鲜度而非完整性 |
| Binary format | 原始 bincode(不使用 base64) | 避免大负载 33% 的额外开销 |
对于高吞吐量的主题(摄像头图像、点云),如果 WS 连接较慢,二进制帧通道可能会被填满。丢弃的采样是静默的 —— CLI 会在 topic hz 中显示降低的频率,但不会卡住。
错误处理
| Error | Source | Response |
|---|---|---|
| Dataflow not found | Coordinator validation | 带有错误消息的 WsResponse |
publish_all_messages_to_zenoh not enabled | Coordinator validation | 带有错误消息的 WsResponse |
| Zenoh 会话打开失败 | Coordinator | 带有错误消息的 WsResponse |
| Zenoh subscriber failure | Per-topic task | 输出警告日志,任务退出 |
| 二进制帧过短(<16 字节) | CLI session_loop | 输出警告日志,帧被丢弃 |
| Unknown subscription UUID | CLI session_loop | Frame dropped silently |
| WS connection closed | Either side | 所有任务被终止,待处理的确认收到错误 |
测试覆盖
| Tier | Location | 覆盖内容 |
|---|---|---|
| 单元测试(客户端) | binaries/cli/src/ws_client.rs | handle_response_topic_subscribe_ack —— 验证确认路由和订阅者注册 |
| Unit (all existing) | binaries/cli/src/ws_client.rs | 已更新,通过 handle_response 传递主题订阅状态 |
The TopicSubscribe / binary frame path is primarily validated via integration testing with a running coordinator and Zenoh session. See Testing Guide for smoke test instructions.
Adora 测试指南
本指南介绍如何在 Adora 工作空间中运行、编写和排查测试。
快速开始(5 分钟验证)
运行这三个命令来验证工作空间是否健康:
# 1. Format check (~5s)
cargo fmt --all -- --check
# 2. Lint (~60s first run, cached after)
cargo clippy --all \
--exclude adora-node-api-python \
--exclude adora-operator-api-python \
--exclude adora-ros2-bridge-python \
-- -D warnings
# 3. Unit + integration tests (~90s first run)
cargo test --all \
--exclude adora-node-api-python \
--exclude adora-operator-api-python \
--exclude adora-ros2-bridge-python
在创建 PR 之前,以下三项必须全部通过。Python 包因需要 maturin 而被排除。
Test Tiers
| Tier | What it covers | 命令 | Speed |
|---|---|---|---|
| Format | Code style | cargo fmt --all -- --check | ~5s |
| Lint | Warnings, correctness | cargo clippy --all ... | ~60s |
| Unit | Individual functions | cargo test --all ... | ~90s |
| CLI | Command parsing, validation | cargo test -p adora-cli | ~5s |
| Integration | 通过环境变量进行节点 I/O | cargo test --test example-tests | ~30s |
| Smoke | Full CLI lifecycle | cargo test --test example-smoke -- --test-threads=1 | ~3min |
| E2E | Multi-dataflow scenarios | cargo test --test ws-cli-e2e -- --ignored --test-threads=1 | ~2min |
| Fault tolerance | Restart policies, timeouts | cargo test --test fault-tolerance-e2e | ~45s |
| Typos | Spelling | 安装 typos-cli,然后运行 typos | ~2s |
Tier Details
单元测试
单元测试使用 #[cfg(test)] 模块,与被测试的代码放在同一文件中。包含测试的主要 crate:
| Crate | Test count | What’s tested |
|---|---|---|
| adora-arrow-convert | ~26 | Arrow 类型的往返转换 |
| adora-cli | ~96 | 命令解析、值解析器、日志过滤、JSON 解析、WebSocket 客户端、集群配置 |
| adora-coordinator | ~24 | WS 控制面/守护进程面、健康检查、并发请求、构件存储、速率限制器、错误信息脱敏 |
| adora-coordinator-store | ~10 | 内存和 redb CRUD、模式版本管理、持久化 |
| adora-core | ~8 | Dataflow descriptor validation |
| adora-daemon | ~2 | Shlex argument parsing |
| adora-node-api | ~10 | 输入跟踪、服务/动作辅助函数(ID 生成、send_service_request/response) |
| adora-log-utils | ~11 | Log parsing utilities |
| adora-message | ~36 | 通用类型、WS 协议、节点/数据 ID、元数据、认证令牌 |
| ros2-bridge | ~30 | ROS2 message/service/action parsing |
运行单个 crate 的测试:
cargo test -p adora-cli
cargo test -p adora-core
cargo test -p adora-arrow-convert
CLI Tests
CLI 测试验证命令解析、参数校验和值解析器,无需实际执行任何命令。它们位于 CLI crate 内的 #[cfg(test)] 模块中。
What’s tested:
- Clap 模式验证(
Args::command().debug_assert()) - 每个子命令的解析(
run、up、down、start、stop、list、logs、build、graph、new、status、inspect top、topic list/hz/echo、node list) - 拒绝未知子命令
--help和--version退出码- 值解析器:
parse_store_spec(协调器存储后端)、parse_window(topic hz 窗口) - Utility functions:
parse_version_from_pip_show
How to run:
cargo test -p adora-cli
如何添加新测试:
添加新的 CLI 子命令或值解析器时,请在同一文件的 #[cfg(test)] 模块中添加对应的测试。对于子命令解析,在 binaries/cli/src/command/mod.rs 中添加 parse_ok 调用。对于值解析器,在定义解析函数的文件中添加测试。
集成测试(节点 I/O)
File: tests/example-tests.rs
这些测试使用预录制的输入运行编译好的节点可执行文件,并将输出与预期基线进行比较。无需协调器或守护进程。
cargo test --test example-tests
How it works:
- 构建并运行节点 crate(例如
rust-dataflow-example-node) - 将
ADORA_TEST_WITH_INPUTS设置为包含定时事件的 JSON 文件 - 设置
ADORA_TEST_NO_OUTPUT_TIME_OFFSET=1以获得确定性输出 - 将 JSONL 输出与
tests/sample-inputs/expected-outputs-*.jsonl进行比较
示例输入/输出文件位于 tests/sample-inputs/ 中。
冒烟测试
File: tests/example-smoke.rs
每个适用的示例都在两种执行模式下进行测试:
- 联网模式(
adora up+adora start --detach+ 轮询 +adora stop+adora down):测试完整的协调器/守护进程 WS 控制面。 - 本地模式(
adora run --stop-after):在进程内运行所有组件,测试单进程数据流路径。
# Must run single-threaded (shared coordinator port)
cargo test --test example-smoke -- --test-threads=1
# Run only networked or local tests
cargo test --test example-smoke smoke_rust -- --test-threads=1
cargo test --test example-smoke smoke_local -- --test-threads=1
还提供了一个 bash 脚本用于快速本地验证:
./scripts/smoke-all.sh # all examples
./scripts/smoke-all.sh --rust-only # Rust examples only
./scripts/smoke-all.sh --python-only # Python examples only
Networked tests (17):
| Test | 示例 | Timeout |
|---|---|---|
smoke_rust_dataflow | rust-dataflow/dataflow.yml | 30s |
smoke_rust_dataflow_dynamic | rust-dataflow/dataflow_dynamic.yml | 30s |
smoke_rust_dataflow_socket | rust-dataflow/dataflow_socket.yml | 30s |
smoke_rust_dataflow_url | rust-dataflow-url/dataflow.yml | 30s |
smoke_benchmark | benchmark/dataflow.yml | 30s |
smoke_log_sink_file | log-sink-file/dataflow.yml | 30s |
smoke_log_sink_alert | log-sink-alert/dataflow.yml | 30s |
smoke_log_sink_tcp | log-sink-tcp/dataflow.yml | 30s |
smoke_python_dataflow | python-dataflow/dataflow.yml | 30s |
smoke_python_async | python-async/dataflow.yaml | 15s |
smoke_python_drain | python-drain/dataflow.yaml | 15s |
smoke_python_log | python-log/dataflow.yaml | 15s |
smoke_python_logging | python-logging/dataflow.yml | 15s |
smoke_python_multiple_arrays | python-multiple-arrays/dataflow.yml | 15s |
smoke_python_concurrent_rw | python-concurrent-rw/dataflow.yml | 15s |
smoke_service_example | service-example/dataflow.yml | 30s |
smoke_action_example | action-example/dataflow.yml | 30s |
Local tests (9):
| Test | 示例 | stop-after |
|---|---|---|
smoke_local_python_dataflow | python-dataflow/dataflow.yml | 30s |
smoke_local_python_async | python-async/dataflow.yaml | 10s |
smoke_local_python_drain | python-drain/dataflow.yaml | 10s |
smoke_local_python_log | python-log/dataflow.yaml | 10s |
smoke_local_python_logging | python-logging/dataflow.yml | 10s |
smoke_local_python_multiple_arrays | python-multiple-arrays/dataflow.yml | 10s |
smoke_local_python_concurrent_rw | python-concurrent-rw/dataflow.yml | 10s |
smoke_local_service_example | service-example/dataflow.yml | 10s |
smoke_local_action_example | action-example/dataflow.yml | 10s |
需要特殊依赖项(摄像头、CUDA、ROS2、C/C++ 工具链、多机部署)的示例不包含在冒烟测试中。
端到端测试(WebSocket CLI)
File: tests/ws-cli-e2e.rs
Two groups:
非忽略(快速): 启动进程内协调器并直接测试 WsSession:
cargo test --test ws-cli-e2e
cli_list_empty—— 空数据流列表cli_status_no_daemon—— 守护进程连接检查cli_stop_nonexistent—— 不存在的数据流返回错误cli_multiple_requests_same_session—— 会话复用
忽略标记(全栈): 使用 adora up 运行真实节点:
cargo test --test ws-cli-e2e -- --ignored --test-threads=1
e2e_start_list_stop—— 启动、列表、停止生命周期e2e_sequential_dataflows—— 两个数据流依次执行
Fault Tolerance Tests
File: tests/fault-tolerance-e2e.rs
这些测试直接使用 Daemon::run_dataflow 测试重启策略和输入超时(无需 CLI)。
cargo test --test fault-tolerance-e2e
Tests:
restart_recovers_from_failure—— 设置了restart_policy: on-failure的节点能够在恐慌后恢复(15秒)max_restarts_limit_reached—— 节点耗尽max_restarts: 2的重启预算(15秒)input_timeout_closes_stale_input—— 当上游停止时触发input_timeout: 2.0s(10秒)
这些测试的数据流 YAML 文件位于 tests/dataflows/ 中。
Coordinator Integration Tests
Files: binaries/coordinator/tests/ws_control_tests.rs, binaries/coordinator/tests/ws_daemon_tests.rs
这些测试启动进程内协调器并测试 WebSocket 控制面/守护进程面。
cargo test -p adora-coordinator
涵盖主题:健康检查、列表/停止/销毁请求、无效 JSON/参数、并发请求、ping/pong、守护进程注册、断开连接清理、错误信息脱敏(不泄露内部错误链)、构件存储的 drop 清理。
CI Pipeline
CI 在推送/PR 到 main 时运行。请参阅 .github/workflows/ci.yml。
fmt ──────────────┐
clippy ────────────┤ (all run in parallel)
test ──────────────┤
typos ─────────────┘
│
e2e (depends on test)
| Job | Runner | What runs |
|---|---|---|
| fmt | ubuntu-latest | cargo fmt --all -- --check |
| clippy | ubuntu-latest | cargo clippy --all ... -- -D warnings |
| test | ubuntu-latest | cargo test --all ...(排除 Python + adora-examples) |
| e2e | ubuntu-latest | example-tests、容错测试、冒烟测试、WS 端到端测试 |
| typos | ubuntu-latest | crate-ci/typos@master |
e2e 任务仅在 test 通过后运行。所有其他任务并行运行。
Writing New Tests
Unit tests
在被测试代码所在的同一文件中添加 #[cfg(test)] 模块:
#![allow(unused)]
fn main() {
#[cfg(test)]
mod tests {
use super::*;
#[test]
fn parses_valid_input() {
let result = parse("valid");
assert_eq!(result, expected);
}
}
}
节点的集成测试
使用 adora-node-api 中的集成测试框架。三种方式:
1. setup_integration_testing (recommended)
在节点的 main 函数之前调用,以注入输入并捕获输出:
#![allow(unused)]
fn main() {
#[test]
fn test_main_function() -> eyre::Result<()> {
let events = vec![
TimedIncomingEvent {
time_offset_secs: 0.01,
event: IncomingEvent::Input {
id: "tick".into(),
metadata: None,
data: None,
},
},
TimedIncomingEvent {
time_offset_secs: 0.055,
event: IncomingEvent::Stop,
},
];
let inputs = TestingInput::Input(
IntegrationTestInput::new("node_id".parse().unwrap(), events),
);
let (tx, rx) = flume::unbounded();
let outputs = TestingOutput::ToChannel(tx);
let options = TestingOptions { skip_output_time_offsets: true };
integration_testing::setup_integration_testing(inputs, outputs, options);
crate::main()?;
let outputs = rx.try_iter().collect::<Vec<_>>();
assert_eq!(outputs, expected_outputs);
Ok(())
}
}
2. 环境变量模式
直接测试编译后的可执行文件,最接近生产环境行为:
ADORA_TEST_WITH_INPUTS=path/to/inputs.json \
ADORA_TEST_NO_OUTPUT_TIME_OFFSET=1 \
ADORA_TEST_WRITE_OUTPUTS_TO=/tmp/out.jsonl \
cargo run -p my-node
3. AdoraNode::init_testing
用于测试节点逻辑而不经过 main 函数:
#![allow(unused)]
fn main() {
let (node, events) = AdoraNode::init_testing(inputs, outputs, Default::default())?;
}
生成测试输入文件
通过设置 ADORA_WRITE_EVENTS_TO 录制真实的数据流事件:
ADORA_WRITE_EVENTS_TO=/tmp/recorded-events adora run examples/rust-dataflow/dataflow.yml
这将写入 inputs-{node_id}.json 文件,可直接用于 ADORA_TEST_WITH_INPUTS。
Workspace-level integration tests
在 tests/ 目录中添加新的测试文件。对于需要完整 CLI 栈的测试,请遵循 tests/example-smoke.rs 中的模式:
联网模式(测试协调器 + 守护进程):
- 使用
Once守卫构建节点(避免每个测试都重新构建) - 使用
adora down清理残留进程 - 使用
adora up启动集群 - 使用
adora start --detach运行数据流 - 轮询
adora list --json检查完成状态 - 使用
adora stop --all和adora down进行清理
本地模式(单进程,进程内协调器):
- 使用
Once守卫构建 CLI - 运行
adora run <yaml> --stop-after <duration> - 断言退出码为成功
Conventions
- 使用
assert2::assert!获取更好的错误信息(可作为 dev-dependency 使用) - 使用
tempfile::NamedTempFile生成临时输出文件 - 需要独占端口访问的端到端测试应标记为
#[ignore]并使用--test-threads=1运行 - 异步测试使用
#[tokio::test(flavor = "multi_thread")] - 容错测试的数据流文件放在
tests/dataflows/中 - 示例输入/输出基线文件放在
tests/sample-inputs/中
故障排除
cargo test 无法编译 Python 包
始终排除 Python 包:
cargo test --all \
--exclude adora-node-api-python \
--exclude adora-operator-api-python \
--exclude adora-ros2-bridge-python
冒烟/端到端测试报 “address already in use” 错误
有残留的协调器或守护进程仍在运行。请清理:
adora down
# or kill processes manually:
pkill -f adora-coordinator
pkill -f adora-daemon
冒烟测试挂起或超时
-
如果您的机器较慢,请增加测试中的超时时间(查找
Duration::from_secs(...)) -
检查示例节点是否能成功构建:
cargo build -p rust-dataflow-example-node -p rust-dataflow-example-status-node \ -p rust-dataflow-example-sink -p rust-dataflow-example-sink-dynamic cargo build -p log-sink-file -p log-sink-alert -p log-sink-tcp cargo build --release -p benchmark-example-node -p benchmark-example-sink -
对于 Python 冒烟测试,请确保已安装
pyarrow和numpy
端到端测试并行运行时失败
冒烟测试和被忽略的端到端测试必须单线程运行:
cargo test --test example-smoke -- --test-threads=1
cargo test --test ws-cli-e2e -- --ignored --test-threads=1
集成测试输出与预期不匹配
- 检查是否设置了
ADORA_TEST_NO_OUTPUT_TIME_OFFSET=1(时间偏移因机器而异) - 如果节点行为有意更改,请重新生成基线:
ADORA_TEST_WITH_INPUTS=tests/sample-inputs/inputs-rust-node.json \ ADORA_TEST_NO_OUTPUT_TIME_OFFSET=1 \ ADORA_TEST_WRITE_OUTPUTS_TO=tests/sample-inputs/expected-outputs-rust-node.jsonl \ cargo run -p rust-dataflow-example-node
Typos check fails
拼写检查配置位于 _typos.toml。添加误报排除项:
[default.extend-identifiers]
MyCustomIdent = "MyCustomIdent"
测试在本地通过但在 CI 中失败
- CI 在 Ubuntu 上运行;检查是否存在平台相关的假设(路径、进程信号)
- CI 使用
rust-cache,因此依赖版本可能与本地 lockfile 不同 - 确保
cargo fmt --all -- --check通过(CI 强制执行此检查)