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 请求匹配。