🤖 roboto_origin_03 Wiki
首页 / 部署 / 手柄控制说明

本文档面向初次接触本项目的开发者,系统讲解机器人手柄控制的完整链路。你将了解从手柄硬件信号到推理节点内部速度指令转换的端到端流程,掌握标准启停顺序、按键映射关系以及常见问题的排查思路。阅读前请确保已完成 环境配置与依赖安装启动机器人与推理节点

Sources: README_CN.md

手柄控制架构概览

系统采用经典的 ROS2 发布-订阅模型解耦输入设备与推理节点。joy_node 负责监听 /dev/input/js0 上的手柄事件,将其编码为 sensor_msgs/Joy 消息发布到 /joy 话题;inference_node 通过实时安全的回调函数订阅该话题,解析摇杆与按键状态,最终生成三维速度指令 cmd_vel_[x, y, yaw]。这些指令作为策略观测的一部分送入 ONNX 模型,决定机器人每一步的关节目标位置。

flowchart LR
    A[手柄硬件<br/>USB Receiver] -->|/dev/input/js0| B[joy_node<br/>ROS2 Joy驱动]
    B -->|/joy<br/>sensor_msgs/Joy| C[inference_node<br/>推理节点]
    C -->|cmd_vel_[0..2]| D[策略观测输入<br/>cmd_vel:3]
    D -->|ONNX Runtime| E[关节动作输出<br/>action:23]
    E -->|CAN/CANFD| F[23路关节电机]
    
    style C fill:#f9f,stroke:#333,stroke-width:2px

上述架构的核心优势在于解耦:joy_nodeinference_node 运行在不同 screen 会话中,即使手柄节点意外退出,推理节点仍可通过 /cmd_vel 话题接收外部控制指令,反之亦然。inference_node 内部使用 std::atomic<bool> is_joy_control_ 原子变量保证两种控制源切换时的线程安全。

Sources: inference_node.hpp, ros_interface.cpp

依赖与启动前提

使用手柄控制前,主控板必须已安装 ROS2 Humble 的 joy 包,该包将内核的 joystick 事件封装为 ROS2 标准消息。若未安装,执行以下命令:

sudo apt install -y ros-humble-joy

./tools/start_robot.sh 启动脚本会自动在后台创建 joy_session 会话并运行 ros2 run joy joy_node。启动成功后,可通过 ros2 topic echo /joy 验证手柄信号是否正常上报。若需远程查看手柄节点日志,使用 screen -r joy_session

Sources: README_CN.md, start_robot.sh

按键与摇杆映射表

推理节点对 sensor_msgs/Joy 的消息解析遵循 Xbox 系列手柄的通用布局。下表列出每个物理输入对应的数组索引、功能语义及代码级限制条件。所有按键均通过边沿检测触发,即按下并松开后才响应一次,长按不会重复执行。

物理输入 Joy 消息字段 功能说明 执行条件与限制
X 键 buttons[2] 电机使能 / 失能切换 若推理运行中,先自动暂停推理,再执行电机状态切换
A 键 buttons[0] 所有关节复位到默认姿态 电机必须已使能;若推理运行中,先自动暂停推理
B 键 buttons[1] 启动 / 暂停推理 电机未使能时无动作,日志会提示 Motors are not initialized
Y 键 buttons[3] 切换手柄控制 / cmd_vel 指令控制 原子变量 is_joy_control_ 保证线程安全,切换时日志输出当前控制源
LB 键 buttons[4] 切换策略模式(中断/动作序列) 仅当配置支持 interrupt 观测或存在 motion_policy 时可用
RB 键 buttons[5] 轮询切换预录动作序列 仅当存在 motion_policy 且当前不处于动作序列模式时可用
右摇杆 前后 axes[4] 控制前进 / 后退速度 映射到 cmd_vel_[0],范围受 clip_cmd[0/1] 限制
右摇杆 左右 axes[3] 控制左移 / 右移速度 映射到 cmd_vel_[1],范围受 clip_cmd[2/3] 限制
LT(左扳机) axes[2] < 0 原地左转 映射到 cmd_vel_[2] 负值,与 RT 互斥
RT(右扳机) axes[5] < 0 原地右转 映射到 cmd_vel_[2] 正值,与 LT 互斥

当同时松开 LT 与 RT 时,cmd_vel_[2] 归零,机器人停止偏航运动。右摇杆回中时,对应轴线速度同样归零。

Sources: ros_interface.cpp, inference_node.hpp

速度指令的数值范围

手柄摇杆输出为 [-1.0, 1.0] 的浮点数,推理节点通过 clip_cmd 参数将其映射到实际物理速度上限。默认配置文件中 clip_cmd 的六项分别对应三个维度的 [min, max]

维度 参数索引 默认值 物理含义
cmd_vel[0] 线速度 X clip_cmd[0], clip_cmd[1] -0.4, 0.6 后退最大 0.4 m/s,前进最大 0.6 m/s
cmd_vel[1] 线速度 Y clip_cmd[2], clip_cmd[3] -0.4, 0.4 横移最大 ±0.4 m/s
cmd_vel[2] 角速度 Yaw clip_cmd[4], clip_cmd[5] -0.8, 0.8 旋转最大 ±0.8 rad/s

代码实现上,推理节点先取摇杆值与正向最大值相乘,再通过 std::clamp 截断到上述区间,最后由 get_cmd_vel_obs 将结果乘以 obs_scales_lin_velobs_scales_ang_vel 送入策略输入张量。这意味着如果你希望机器人走得更快或更慢,应修改 src/inference/config/inference.yaml 中的 clip_cmd 而非手柄硬件本身。

Sources: ros_interface.cpp, obs_manager.cpp, inference.yaml

标准上电与启停流程

出于安全考虑,机器人上电后并不会立即运动。新手开发者必须严格按照以下顺序操作,任何跳步都可能导致电机报错或关节失控。

flowchart TD
    A[启动完成<br/>机器人静止] -->|按 X 键| B[电机使能<br/>关节进入力控待机]
    B -->|按 A 键| C[关节复位<br/>回到默认姿态]
    C -->|按 B 键| D[推理启动<br/>机器人响应手柄]
    D -->|右摇杆 + LT/RT| E[行走/转向]
    D -->|再按 B 键| F[推理暂停<br/>保持当前姿态]
    F -->|按 X 键| G[电机失能<br/>机器人自然下垂]
    
    style D fill:#9f9,stroke:#333,stroke-width:2px
    style F fill:#ff9,stroke:#333,stroke-width:2px

第一步:电机使能(X 键)。按下 X 键后,inference_node 调用 robot_->init_motors(),23 个关节电机上电并进入 MIT 力控模式。此时电机有阻尼感,但不会主动运动。若电机已使能,再次按 X 键将调用 deinit_motors() 切断电机输出。

第二步:关节复位(A 键)。按下 A 键后,所有关节按 joint_default_angle 中定义的默认角度归位。这一步确保策略启动前机器人处于已知的合理姿态,避免从折叠或歪斜状态直接启动推理导致失衡。若推理正在运行,A 键会自动先暂停推理,再执行复位。

第三步:启动推理(B 键)。按下 B 键,is_running_ 置为 true,推理线程开始以 dt * decimation 的周期循环执行 ONNX 推理。此时推动右摇杆,机器人将根据手柄速度和 IMU 反馈实时调整步态。再次按 B 键可暂停推理,电机会维持在当前关节角度,但不再计算新动作。

Sources: ros_interface.cpp, inference_node.cpp

双模控制:手柄与 cmd_vel

系统支持两种高层控制源,按 Y 键 实时切换:

这一设计使机器人既支持人工临场遥控,也支持上位机或导航栈的自动路径跟随。切换时日志会明确输出 Controlled by joyControlled by /cmd_vel,方便调试确认。/cmd_vel 的解析逻辑与手柄完全一致,同样受 clip_cmd 范围限制,因此两种模式下的速度上限保持一致。

Sources: ros_interface.cpp, ros_interface.cpp

高级功能:策略与动作序列切换

当配置文件加载了多个策略或包含动作序列(motion_policy)时,LB 与 RB 键将激活额外功能。

LB 键的行为取决于当前策略配置。如果 YAML 的 obs_layouts 中包含 interrupt 观测源,LB 用于启停中断模式,允许外部关节状态话题 /joint_ref_states 覆盖部分动作输出。如果配置中包含动作序列(即 motion_names 非空),LB 则用于在正常策略与动作序列策略之间切换。无论哪种情况,切换前推理都会自动暂停,切换完成后自动恢复,确保状态安全。

RB 键仅在存在动作序列且当前不处于动作序列模式时有效。每按一次,current_motion_policy_idx_ 向后轮询一个索引,日志会输出下一个将被启用的动作序列名称。

Sources: ros_interface.cpp

安全设计与边沿检测

推理节点并非简单检测 buttons[n] == 1,而是维护 last_button0_last_button5_ 六个状态变量,仅在当前帧为按下且上一帧为松开时触发动作。这种边沿检测机制避免了以下风险:

  1. 长按重复触发:按住 X 键不会导致电机在使能/失能间高频震荡。
  2. 单周期多事件:每次按键只产生一次状态转换,便于操作者观察日志确认执行结果。
  3. 抖动容忍:摇杆死区由 joy_node 在驱动层处理,推理节点直接消费归一化后的浮点轴值。

此外,cmd_mutex_ 保护 cmd_vel_ 数组的读写,确保主线程的回调更新与推理线程的观测获取不会相互竞争。

Sources: ros_interface.cpp, inference_node.hpp

常见问题排查

现象 可能原因 排查方法
按任何键机器人均无反应 joy_node 未启动或手柄未配对 执行 ros2 topic list | grep joy,确认存在 /joy;执行 ls /dev/input/js0 确认设备节点存在
摇杆推动后机器人只在原地踏步 cmd_vel 已送入但推理未启动 查看 inference_node 日志,确认已输出 Inference started;若显示 Inference paused,按 B 键启动
按 X 键后电机无锁止感 电机未成功使能或 CAN 总线异常 检查 ip a 确认 can0~can3 均为 UP;查看推理节点是否有电机初始化失败报错
按 B 键提示 Motors are not initialized 跳过了 X 键使能步骤 严格按照「X → A → B」顺序操作
Y 键切换后手柄仍无法控制 当前处于 /cmd_vel 模式 查看日志确认 Controlled by joy;若显示 Controlled by /cmd_vel,再按一次 Y 键切回
手柄信号延迟或漂移 USB 接口供电不足或 2.4G 干扰 将手柄接收器更换到另一个 USB 2.0 接口,远离 CAN 转换器和电机动力线

Sources: start_robot.sh, inference_node.cpp

下一步

掌握手柄控制的基础操作后,你可以继续深入以下方向: