本文面向初次接触本系统的开发者,介绍如何通过游戏手柄或 ROS 2 指令话题驱动机器人运动。你将了解两种控制输入的架构差异、数据如何从手柄/指令流经策略网络并最终作用于电机,以及对应的配置参数与调试方法。掌握本章内容是安全上机实验的前提,建议在阅读 硬件准备与电机初始化 之后、研读 Launch 文件与启动配置 之前学习。
Sources: inference_node.hpp, ros_interface.cpp
控制输入架构概览
推理节点同时监听两类外部输入:手柄的 sensor_msgs/msg/Joy 消息(话题 /joy)与速度指令的 geometry_msgs/msg/Twist 消息(话题 /cmd_vel)。二者共享同一份 cmd_vel_ 内部状态(三维向量,分别表示前进速度、横移速度、旋转角速度),但由原子布尔量 is_joy_control_ 决定当前哪一路输入生效,默认开启手柄控制。无论来自哪一路,指令都会经过 clip_cmd_ 限幅、观测缩放系数归一化后,作为 cmd_vel 观测源送入 ONNX 策略网络,与 IMU、关节状态等信息共同决定下一步动作。
Sources: inference_node.hpp, inference_node.hpp, obs_manager.cpp
graph LR
A[手柄 /joy] -->|axes & buttons| B[InferenceNode]
C[外部节点 /cmd_vel] -->|linear.x/y angular.z| B
B -->|is_joy_control_| D[cmd_vel_ 状态]
D -->|clip_cmd_ 限幅| E[cmd_vel 观测源]
E -->|obs_scales_* 缩放| F[ONNX 策略网络]
F -->|输出动作| G[控制线程]
G -->|apply_action| H[RobotInterface]
H -->|CAN/CANFD| I[电机执行]
Sources: ros_interface.cpp, inference_node.cpp
手柄控制详解
摇杆与扳机映射
系统使用标准 Xbox 布局手柄(或兼容 sensor_msgs/msg/Joy 的等效设备)。在 subs_joy_callback 中,右手摇杆与左右扳机被映射为平面运动与旋转指令:
| 手柄输入 | Joy 消息索引 | 物理意义 | 限幅区间(默认) |
|---|---|---|---|
| 右摇杆 前后 | axes[4] |
前进/后退速度 (x) | [-0.4, 0.6] m/s |
| 右摇杆 左右 | axes[3] |
左移/右移速度 (y) | [-0.4, 0.4] m/s |
| LT (左扳机) | axes[2] < 0 |
逆时针旋转 (yaw) | [-0.8, 0.8] rad/s |
| RT (右扳机) | axes[5] < 0 |
顺时针旋转 (yaw) | [-0.8, 0.8] rad/s |
摇杆/扳机输出会先乘以对应的最大值,再用 std::clamp 裁剪到 clip_cmd_ 区间。若 LT 与 RT 同时未按下,旋转指令归零。
Sources: ros_interface.cpp, config/inference.yaml
功能按键映射
除运动控制外,手柄按键还承担系统级操作。以下为启动时控制台打印的对应关系(基于 Xbox 按键符号):
| 按键 | Joy 索引 | 功能 | 安全前提 |
|---|---|---|---|
| X | buttons[2] |
电机初始化 / 反初始化 | 若推理运行中,先自动暂停 |
| A | buttons[0] |
复位关节到默认角度 | 电机须已初始化;运行中先暂停 |
| B | buttons[1] |
启动 / 暂停推理 | 无 |
| Y | buttons[3] |
切换手柄控制 / cmd_vel 控制 |
无 |
| LB | buttons[4] |
切换策略模式(中断/动作策略) | 仅当配置支持时可用 |
| RB | buttons[5] |
切换动作序列( BeyondMimic 模式) | 仅当配置包含 motion policy 时可用 |
每次按键采用边沿检测(对比 last_buttonX_),避免长按导致重复触发。在切换策略模式(LB)时,系统会临时暂停推理、完成切换后自动恢复,保证状态安全。
Sources: inference_node.cpp, ros_interface.cpp, inference_node.hpp
指令控制 (/cmd_vel)
当 is_joy_control_ 为 false 时,系统转而监听 /cmd_vel 话题。任何发布 geometry_msgs/msg/Twist 的节点(如键盘遥控 teleop_twist_keyboard、导航栈、上位机脚本)均可接管运动控制。回调函数将 linear.x、linear.y、angular.z 直接映射到 cmd_vel_[0/1/2],并同样受 clip_cmd_ 六元组限幅。
Sources: ros_interface.cpp
该模式适合以下场景:
- 没有实体手柄,仅通过键盘或命令行做初期调试
- 集成自主导航或上层规划算法
- 远程上位机通过 Wi-Fi 发送速度指令
若要发布测试指令,可在终端执行:
ros2 topic pub /cmd_vel geometry_msgs/msg/Twist \
"{linear: {x: 0.2, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}"
系统将以前进 0.2 m/s 的速度持续运动,直到收到新指令或超时。
两种控制模式的切换
按下手柄 Y 键会在手柄与 cmd_vel 两种模式间切换,同时输出当前控制源日志。切换本身不影响 cmd_vel_ 的当前值,但会立即阻断另一路输入的写入。例如,若正处于 cmd_vel 模式时手柄摇杆被推动,这些输入将被忽略;反之亦然。
Sources: ros_interface.cpp
系统启动时默认进入手柄模式。若你希望默认使用指令控制,目前需要在源码中将 is_joy_control_ 的初始值改为 false 后重新编译,或通过外部脚本在启动后立即调用服务/发布话题进行接管。
Sources: inference_node.hpp
从指令到动作的数据流
为帮助初学者建立端到端的认知,下面给出一次完整控制循环的流程:
sequenceDiagram
participant U as 用户/上游节点
participant R as InferenceNode
participant O as ObsManager
participant P as ONNX Policy
participant C as Control线程
participant M as 电机
U->>R: 发布 /joy 或 /cmd_vel
R->>R: 限幅写入 cmd_vel_
O->>R: get_cmd_vel_obs()
R-->>O: 返回缩放后的 [vx, vy, yaw]
O->>O: 组装完整观测向量<br/>(imu + cmd_vel + dof + last_action ...)
O->>P: Run ONNX Session
P-->>O: 输出原始动作
O->>R: 动作限幅 + 缩放 + 默认角度偏移
R->>C: 通过 act_ / last_act_ 共享
C->>M: apply_action (dt_ 周期)
Sources: ros_interface.cpp, obs_manager.cpp, inference_node.cpp, inference_node.cpp
配置参数说明
与输入控制直接相关的 YAML 参数如下表所示,可在启动配置中根据机器人平台与安全需求调整:
| 参数名 | 类型 | 含义 | 示例值 |
|---|---|---|---|
clip_cmd |
double[6] |
[min_x, max_x, min_y, max_y, min_yaw, max_yaw] |
[-0.4, 0.6, -0.4, 0.4, -0.8, 0.8] |
obs_scales_lin_vel |
float |
线速度观测缩放系数 | 1.0 |
obs_scales_ang_vel |
float |
角速度观测缩放系数 | 1.0 |
dt |
float |
控制线程周期(秒) | 0.004 |
decimation |
int |
推理线程相对于控制线程的步长倍数 | 5 |
action_scale |
float |
策略输出动作缩放 | 0.25 |
act_alpha |
float |
动作平滑系数(1.0 表示不平滑) | 1.0 |
clip_cmd 是安全上机的核心参数:若机器人响应过于激进,应优先减小其最大值;若需要更快的响应,则可适当放宽,但需配合策略训练时的指令分布保持一致,否则可能出现步态失稳。
Sources: config/inference.yaml, ros_interface.cpp
ROS 2 服务接口(无手柄时的替代方案)
即使没有手柄,也可以通过 ROS 2 服务完成系统级操作。推理节点注册了以下 std_srvs/srv/Trigger 服务:
| 服务名 | 功能 | 等效手柄操作 |
|---|---|---|
/init_motors |
初始化电机 | X 键(电机未初始化时) |
/deinit_motors |
反初始化电机 | X 键(电机已初始化时) |
/reset_joints |
复位关节到默认角度 | A 键 |
/start_inference |
启动推理 | B 键(暂停时) |
/stop_inference |
暂停推理 | B 键(运行时) |
/clear_errors |
清除驱动错误 | 无直接对应 |
/refresh_joints |
刷新电机状态 | 无直接对应 |
调用示例:
ros2 service call /init_motors std_srvs/srv/Trigger
ros2 service call /start_inference std_srvs/srv/Trigger
Sources: inference_node.hpp, ros_interface.cpp
快速操作指南
对于第一次上机的开发者,建议按照以下顺序操作:
- 启动推理节点并确认手柄接收器已连接
- 观察终端提示,按 X 初始化电机
- 按 A 将关节复位到默认姿态
- 轻推右摇杆,按 B 启动推理,机器人应缓慢响应摇杆
- 松开摇杆,机器人回到原地踏步;按 B 暂停推理
- 若需测试自主指令,按 Y 切换到
/cmd_vel模式,从终端发布 Twist 消息
Sources: inference_node.cpp
常见问题排查
| 现象 | 可能原因 | 排查方法 |
|---|---|---|
| 推摇杆机器人无响应 | 推理未启动 / 未初始化电机 / 处于 cmd_vel 模式 |
查看终端日志,确认 is_running_ 与 is_init_ 状态 |
| 运动方向与预期相反 | 手柄轴向映射与本地习惯不符 | 检查 axes 索引,必要时修改 subs_joy_callback |
| 机器人运动过于剧烈 | clip_cmd 最大值过大 |
减小 YAML 中对应方向的最大值并重启 |
| 切换 Y 键后手柄仍无效 | 手柄驱动未发布 /joy |
ros2 topic echo /joy 确认有数据 |
发布 /cmd_vel 无响应 |
仍处于手柄模式 / 消息被限幅到 0 | 检查终端当前控制源日志,确认 Twist 值非零 |
Sources: ros_interface.cpp, config/inference.yaml
后续阅读建议
完成本章后,你已经掌握了人机交互的基本入口。建议继续阅读:
- Launch 文件与启动配置:了解如何组织 YAML 参数与自定义启动行为
- ROS 2 话题与服务接口:深入理解
/action、/joint_states等对外输出 - 多策略 YAML 配置详解:学习
clip_cmd在不同策略组合下的配置技巧 - 安全监控、限位与故障处理:了解关节限位与摔倒检测机制