InferenceNode 作为机器人强化学习推理系统的 ROS 2 中枢节点,通过标准化话题实现与外部感知、控制输入及可视化工具的数据交换,同时以 std_srvs/srv/Trigger 服务接口暴露电机生命周期管理与推理启停能力。本页将系统梳理该节点对外暴露的全部 4 路订阅话题、3 路发布话题 与 10 项 Trigger 服务,并结合 QoS 设计与线程调用上下文说明其工程意图。
Sources: inference_node.hpp
接口总览
下表按输入、输出、控制三类职责汇总 InferenceNode 的全部 ROS 2 接口。所有话题均运行于同一节点命名空间(默认 inference_node),服务名不加斜杠前缀,可直接通过 ros2 service call <name> std_srvs/srv/Trigger 调用。
| 方向 | 名称 | 消息类型 | 职责 |
|---|---|---|---|
| 订阅 | /joy |
sensor_msgs/msg/Joy |
手柄输入:速度指令 + 功能按键 |
| 订阅 | /cmd_vel |
geometry_msgs/msg/Twist |
上位机速度指令(与手柄互斥) |
| 订阅 | elevation_data(可配置) |
std_msgs/msg/Float32MultiArray |
高程/感知观测输入 |
| 订阅 | /joint_ref_states |
sensor_msgs/msg/JointState |
中断动作关节参考覆盖 |
| 发布 | /action |
sensor_msgs/msg/JointState |
推理输出关节目标位置 |
| 发布 | /imu |
sensor_msgs/msg/Imu |
四元数与角速度广播 |
| 发布 | /joint_states |
sensor_msgs/msg/JointState |
关节位置/速度/力矩反馈 |
| 服务 | init_motors |
std_srvs/srv/Trigger |
初始化电机驱动 |
| 服务 | deinit_motors |
std_srvs/srv/Trigger |
关闭电机并使能释放 |
| 服务 | start_inference |
std_srvs/srv/Trigger |
启动策略推理循环 |
| 服务 | stop_inference |
std_srvs/srv/Trigger |
暂停策略推理循环 |
| 服务 | reset_joints |
std_srvs/srv/Trigger |
关节复位至默认角度 |
| 服务 | set_zeros |
std_srvs/srv/Trigger |
标定当前位置为零点 |
| 服务 | refresh_joints |
std_srvs/srv/Trigger |
刷新电机状态缓存 |
| 服务 | read_joints |
std_srvs/srv/Trigger |
主动触发关节状态发布 |
| 服务 | read_imu |
std_srvs/srv/Trigger |
主动触发 IMU 数据发布 |
| 服务 | clear_errors |
std_srvs/srv/Trigger |
清除电机错误标志 |
Sources: inference_node.hpp, ros_interface.cpp
话题接口详解
输入话题
InferenceNode 注册 4 路订阅话题,分别承担人机交互指令、外部速度控制、感知观测融合与动作中断覆盖四类职责。所有订阅共用同一 QoS 配置:KeepLast(1) + best_effort + durability_volatile,这意味着系统只保留最新一条消息,允许网络丢包但不引入排队延迟,契合实时控制对低延迟的苛刻要求。
/joy(手柄输入)
手柄消息通过 sensor_msgs/msg/Joy 接收,映射关系遵循 Xbox 风格布局:右摇杆 axes[4]、axes[3] 控制 x/y 方向线速度,左右扳机 axes[2]/axes[5] 控制偏航角速度;X、A、B、Y、LB、RB 六个按键分别对应电机初始化/反初始化、关节复位、推理启停切换、控制源切换、中断/动作策略切换、动作序列切换。每次状态切换时均要求当前按键值为 1 且上一次为 0,实现边沿触发防抖。当 is_joy_control_ 为真时,速度指令写入 cmd_vel_ 缓冲区,直接参与后续观测组装。
Sources: ros_interface.cpp
/cmd_vel(外部速度指令)
该话题接收 geometry_msgs/msg/Twist,在 is_joy_control_ 为假时生效。linear.x、linear.y 与 angular.z 经 clip_cmd_ 限幅后映射到与手柄相同的 cmd_vel_ 缓冲区,实现手柄与上位机两种控制源的无缝互斥切换。该设计使开发者在调试阶段可通过 ros2 topic pub 直接注入速度指令,无需依赖物理手柄。
Sources: ros_interface.cpp
elevation_data(感知观测,可配置)
默认 topic 名称为 elevation_data,可通过 launch 参数 perception_obs_topic 重映射。消息类型为 std_msgs/msg/Float32MultiArray,接收高程图或其他感知网络输出的浮点数组。回调函数将数据拷贝至 perception_obs_buffer_,若消息长度小于预期则填充零并输出警告。该缓冲区的内容在 观测布局配置与动态解析 中按 perception 观测源注入策略输入张量。
Sources: ros_interface.cpp, ros_interface.cpp
/joint_ref_states(中断动作参考)
仅在系统支持中断模式(supports_interrupt() 为真)且 is_interrupt_ 使能时生效。外部节点通过发布 sensor_msgs/msg/JointState 的 position 字段,将特定关节角度实时覆盖到推理输出中,实现动作中断或局部关节保护。该机制在 中断动作与外部覆盖机制 中有更深入的策略层说明。
Sources: ros_interface.cpp
输出话题
/action(推理动作输出)
inference 线程每次完成 ONNX 模型前向传播后,将输出经 action_scale_ 缩放并叠加上 joint_default_angle_ 偏移,最终通过 sensor_msgs/msg/JointState 的 position 字段发布。该话题频率由 dt * decimation 决定(例如 dt=0.004、decimation=5 时为 50 Hz)。若当前处于中断模式,对应关节会被 interrupt_action_ 覆盖后再发布。
Sources: ros_interface.cpp, inference_node.cpp
/joint_states(关节状态反馈)
发布真实的电机反馈状态,包含 position、velocity、effort 三个字段,数据分别来自 robot_->get_joint_q()、robot_->get_joint_vel() 与 robot_->get_joint_tau()。该话题在 inference 线程每次观测更新阶段自动触发,也支持通过 read_joints 服务手动触发。其频率与推理循环一致,适用于 RViz、rqt_plot 或外部记录节点订阅。
Sources: ros_interface.cpp, inference_node.cpp
/imu(惯性测量单元广播)
发布四元数(orientation.w/x/y/z)与角速度(angular_velocity.x/y/z),数据来自 robot_->get_quat() 和 robot_->get_ang_vel()。与 /joint_states 类似,该话题在 inference 线程内自动发布,同时支持 read_imu 服务手动触发。注意该消息当前未填充线性加速度字段。
Sources: ros_interface.cpp, inference_node.cpp
服务接口详解
全部 10 项服务统一采用 std_srvs/srv/Trigger 类型,即无输入参数、返回 success 布尔标志与 message 字符串。这种极简契约降低了外部脚本与命令行调用的门槛,同时通过内部状态守卫(如 is_running_、robot_->is_init_)防止危险操作在错误时机执行。
电机生命周期服务
| 服务名 | 前置条件 | 执行动作 | 失败场景 |
|---|---|---|---|
init_motors |
电机未初始化 | 调用 robot_->init_motors() |
电机已初始化 |
deinit_motors |
电机已初始化 | 调用 robot_->deinit_motors() |
电机未初始化 |
reset_joints |
推理已停止且电机已初始化 | 各关节回到 joint_default_angle_ |
推理运行中或电机未初始化 |
set_zeros |
推理已停止且电机已初始化 | 标定当前机械零位 | 推理运行中或电机未初始化 |
refresh_joints |
电机已初始化 | 刷新电机内部状态缓存 | 电机未初始化 |
clear_errors |
robot_ 已实例化 |
清除驱动错误标志 | 接口未初始化 |
reset_joints 与 set_zeros 明确要求推理处于停止状态,因为二者会改变关节位置基准,若与实时控制并发将导致不可预测的动作跳变。refresh_joints 则允许在推理运行时调用,仅用于状态同步而不改变控制输出。
Sources: ros_interface.cpp
推理控制服务
| 服务名 | 状态转换 | 说明 |
|---|---|---|
start_inference |
is_running_: false → true |
启动 inference 线程中的 ONNX 推理与观测组装循环 |
stop_inference |
is_running_: true → false |
暂停推理,但保持电机使能与 control 线程运行 |
与手柄 B 键功能等价,服务接口便于自动化测试脚本或上层行为树节点调用。stop_inference 不会关闭电机,机器人将保持在最后一条动作指令位置,由底层电机的位置环维持。
Sources: ros_interface.cpp
状态诊断服务
| 服务名 | 触发效果 |
|---|---|
read_joints |
立即调用 publish_joint_states() 发布一次 /joint_states |
read_imu |
立即调用 publish_imu() 发布一次 /imu |
二者用于按需诊断场景:当外部节点不希望以固定频率订阅话题、而仅在特定时刻抓取一次传感器状态时,可通过服务调用实现拉取式数据采集。
Sources: ros_interface.cpp
数据流与线程模型
从 ROS 2 接口视角看,InferenceNode 内部的两条实时线程对话题的调用存在明确分工。inference 线程负责传感器读取与动作发布,control 线程负责高频动作下发。
graph TD
subgraph 外部节点
JOY[joy_node<br>/joy]
CMD[nav2 / teleop<br>/cmd_vel]
PERC[perception_node<br>elevation_data]
JREF[joint_override_node<br>/joint_ref_states]
RVIZ[RViz / Recorder]
end
subgraph InferenceNode
INF[inference 线程<br>优先级 70]
CTRL[control 线程<br>优先级 70]
SUB1[/joy 回调/]
SUB2[/cmd_vel 回调/]
SUB3[/elevation 回调/]
SUB4[/joint_ref_states 回调/]
PUB1[/publish_imu/]
PUB2[/publish_joint_states/]
PUB3[/publish_action/]
end
subgraph RobotInterface
IMU[(IMU 驱动)]
MOT[(CAN 电机驱动)]
end
JOY -->|Joy| SUB1
CMD -->|Twist| SUB2
PERC -->|Float32MultiArray| SUB3
JREF -->|JointState| SUB4
INF -->|读取| IMU
INF -->|读取| MOT
INF --> PUB1
INF --> PUB2
INF --> PUB3
PUB1 -->|sensor_msgs/Imu<br>/imu| RVIZ
PUB2 -->|sensor_msgs/JointState<br>/joint_states| RVIZ
PUB3 -->|sensor_msgs/JointState<br>/action| MOT
CTRL -->|apply_action| MOT
关键时序特征:publish_action 与 apply_action 解耦。inference 线程以 dt * decimation 周期生成目标动作并发布到 /action 话题,同时该动作写入 act_ 缓冲区;control 线程以 dt 周期从 act_ 读取并通过低通滤波(act_alpha_)后下发至电机。这意味着 /action 话题频率低于实际控制频率,订阅 /action 的节点看到的是策略原始输出,而电机执行的是经过平滑后的轨迹。
Sources: inference_node.cpp, inference_node.cpp
QoS 设计意图
所有话题统一采用 rclcpp::QoS(rclcpp::KeepLast(1)).best_effort().durability_volatile(),这一选择并非偶然,而是针对强化学习实时推理的三项约束做出的工程权衡:
- KeepLast(1):控制与感知数据具有极强时效性,旧观测对当前步决策不仅无用,反而可能因延迟导致策略输入分布偏移。只保留最新一条消息可避免 ROS 2 层内建队列引入的额外延迟。
- Best Effort:推理节点已运行于
SCHED_FIFO实时调度,若强制可靠传输,在订阅端处理慢时可能导致发布端阻塞或内存膨胀。Best Effort 允许丢包,保证发布端非阻塞。 - Volatile Durability:节点重启后不应接收历史消息,避免启动瞬间的策略输入混乱。
对于需要可靠记录或离线分析的场景,建议下游节点(如 rosbag2)自行以 reliable QoS 订阅,而非修改推理节点的发布策略。
Sources: inference_node.hpp
常用调用示例
以下命令假设节点已启动且运行于同一 ROS 2 域中。
通过 cmd_vel 控制机器人前进
ros2 topic pub /cmd_vel geometry_msgs/msg/Twist \
'{linear: {x: 0.3, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}' --once
手动触发一次关节状态发布
ros2 service call read_joints std_srvs/srv/Trigger
启动推理
ros2 service call start_inference std_srvs/srv/Trigger
安全停止推理(电机保持使能)
ros2 service call stop_inference std_srvs/srv/Trigger
查看实时动作输出
ros2 topic echo /action --field position
Sources: ros_interface.cpp, ros_interface.cpp
与其他页面的关系
本文档聚焦 InferenceNode 对外暴露的 ROS 2 接口契约。若需深入了解以下主题,可继续阅读对应页面:
- 若想理解
/action中数值如何由 ONNX 模型输出经缩放与映射得到,请参阅 ONNX Runtime 推理引擎集成 与 观测值组装、归一化与帧堆叠。 - 若需配置
elevation_data的观测维度或obs_layouts字段,请参阅 观测布局配置与动态解析。 - 若需了解
/joint_ref_states的中断优先级与动作覆盖逻辑,请参阅 中断动作与外部覆盖机制。 - 若需查看电机驱动与 IMU 数据在
RobotInterface中的获取方式,请参阅 RobotInterface 设计与实现。