本文档是部署框架的问题定位与调试中枢,面向已具备基础 ROS2 与嵌入式开发经验的中级开发者。内容覆盖从编译失败、实时调度异常、总线通信故障到推理节点安全保护触发的全链路排查方法。建议在阅读前先完成 环境配置与依赖安装、硬件连接与 CAN/IMU 映射 和 启动机器人与推理节点 的常规流程,以便将本文作为“异常发生后的快速索引”使用。
Sources: README_CN.md
编译与启动失败
./tools/start_robot.sh 是启动流程的入口,它在运行前会执行环境检查、依赖校验与自动编译。若启动脚本直接退出,通常可在其彩色输出中找到第一报错点。
依赖缺失是最常见的启动失败原因。脚本会依次检查 AMENT_PREFIX_PATH(ROS2 环境)、colcon、ros2 与 screen。若任一命令不存在,脚本会以红色错误信息退出。此外,如果推理包编译失败,colcon build --symlink-install 的返回码非零也会触发终止。遇到此类问题时,请依次确认已安装 ccache、libfmt-dev、libspdlog-dev、libeigen3-dev、screen 以及 ros-humble-joy;Python 脚本则额外需要 python3-yaml 与 python3-numpy。
Sources: start_robot.sh
DDS 配置文件缺失或 XML 语法错误同样会导致启动中断。脚本在启动节点前会验证 assets/rt_fastdds_profile.xml 是否存在,并在 xmllint 可用时检查 XML 格式。若此前手动修改过该文件,建议用 xmllint --noout assets/rt_fastdds_profile.xml 先行验证。若文件被误删或路径变更,脚本会输出 DDS 配置文件不存在 并退出。
Sources: start_robot.sh
实时优先级与线程调度异常
推理节点、控制循环、CAN 收发与串口解析均依赖 SCHED_FIFO 实时调度。若系统未授予用户实时权限,或内核未打实时补丁,节点可能在启动瞬间打印 Failed to set realtime priority 并直接调用 rclcpp::shutdown() 终止。
排查步骤如下:首先执行 ulimit -r,若返回值不为 98,说明 /etc/security/limits.conf 中的 rtprio 配置未生效,或当前用户名与规则中的名称不符(Orange Pi 默认用户为 orangepi,RDK X5 为 sunrise)。其次,若日志中出现 mlockall failed,表示进程未能锁定内存页,虽为 WARN 级别不会导致退出,但可能在内存紧张时引发控制周期抖动。最后,CAN 接收线程与发送线程同样尝试设置 SCHED_FIFO 优先级 80,若失败仅记录错误日志而不退出,但长期运行下可能因抢占不足导致总线丢包。
Sources: inference_node.cpp, socket_can.cpp
DDS 通信与节点发现异常
启动脚本在后台拉起 inference_node 与 joy_node 后,会执行 verify_dds_effectiveness 进行五层验证:环境变量、XML 存在性与语法、进程环境变量注入、共享内存文件数、以及节点发现延迟。若某一层未通过,脚本会以黄色或红色提示输出,但不会终止进程。
典型症状与对策见下表:
| 症状 | 根因 | 对策 |
|---|---|---|
ros2 node list 延迟超过 1000 ms |
DDS 发现性能差,常出现在非共享内存传输回退到 UDP 时 | 确认 RMW_IMPLEMENTATION=rmw_fastrtps_cpp 与 FASTRTPS_DEFAULT_PROFILES_FILE 已正确导出;检查 /dev/shm/ 下是否存在 fastrtps 相关文件 |
inference_node 缺少环境变量 |
screen 会话未继承当前 shell 的环境 | start_robot.sh 已在 screen 命令中显式 export 相关变量;若手动 ros2 run,需自行 source 并导出 |
joy_node 未出现 |
joy 包未安装或启动检测超时 |
安装 ros-humble-joy;若硬件未插手柄,节点仍应启动,只是无数据 |
Sources: start_robot.sh
CAN 总线与电机离线
CAN 通信层故障通常表现为电机初始化成功但随即离线,或初始化阶段就抛出异常。RobotInterface::apply_action 在每次控制周期内都会检查 motor->get_response_count() > offline_threshold_(阈值固定为 25)。若某电机连续 25 个周期未收到 CAN 回包,response_count_ 累计超限,节点会抛出 Motor id X offline 并触发 rclcpp::shutdown()。
Sources: robot_interface.cpp, robot_interface.hpp
SocketCAN 层面的报错通常具有以下特征:
Failed to create CAN socket:内核缺少 CAN 支持,或当前用户无网络权限。Unable to detect CAN interface canX:接口未启动,或 udev 规则未生效导致接口名不对。Failed to bind socket to network interface:接口存在但处于DOWN状态,需执行sudo ip link set canX up type can bitrate 1000000。Failed to transmit CAN frame:发送队列满或总线错误(如终端电阻缺失、波特率不匹配)。
若使用 udev 规则自动绑定 USB 转 CAN,插入顺序无关,但 KERNELS 属性必须与物理端口一致。可通过 sudo udevadm monitor 获取实际值并修改 assets/99-auto-up-devs-*.rules。规则生效后重启,执行 ip a 应能看到 can0 至 can3 全部处于 UP 状态。
Sources: socket_can.cpp, README_CN.md
电机错误码与保护状态
达妙(DM)电机在 CAN 回包的高 4 位携带错误码。DmMotorDriver::can_rx_cbk 解析该字段,当数值大于 7 时记录 error_id_ 并通过 spdlog 输出。init_motor() 返回的错误码可用于判断电机上电后的初始健康状态。
DM 电机错误码表:
| 错误码 | 枚举名 | 含义 | 常见根因与处理 |
|---|---|---|---|
| 0x00 | DM_DOWN |
电机未使能(正常待机) | 调用 init_motor() 或手柄 X 键使能 |
| 0x01 | DM_UP |
电机正常运行 | 无错误 |
| 0x08 | DM_OVER_VOLT |
过压 | 检查电源电压是否超过电机额定值;确认降压模块正常 |
| 0x09 | DM_UNDER_VOLT |
欠压 | 电池电量不足或供电线路压降过大 |
| 0x0A | DM_OVER_CURRENT |
过流 | 机械卡滞、碰撞或 PID 增益过大导致电流尖峰 |
| 0x0B | DM_MOS_OVER_TEMP |
MOS 管过温 | 散热不足或长时间大电流输出,停机冷却 |
| 0x0C | DM_COIL_OVER_TEMP |
线圈过温 | 同上过温逻辑,需降低负载或改善通风 |
| 0x0D | DM_LOST_CONN |
通信丢失 | CAN 线松动、波特率不一致或总线负载过高 |
| 0x0E | DM_OVER_LOAD |
过载 | 机械结构干涉或零点偏移导致电机持续堵转 |
Sources: dm_motor_driver.hpp, dm_motor_driver.cpp
零点标定异常是另一类高频问题。set_motor_zero() 写入零点后立即读取当前位置,若绝对值大于 judgment_accuracy_threshold(1e-2),则判定失败并输出 set zero error。出现此问题时,请确认:
- 电机处于可自由转动的阻尼模式;
- 标定前已通过
unlock_motor()清除旧零点; - 对于腰部 yaw 电机,若使用限位块标定,
robot.yaml中的motor_zero_offset应保持2.093;若使用打印件固定标定,则应改为0.0。
Sources: dm_motor_driver.cpp, motor_driver.hpp, robot.yaml
IMU 驱动与数据异常
IMU 默认通过串口 /dev/ttyUSB0 以 921600 波特率通信。HipnucIMUDriver 构造函数中,若 interface_type 不是 serial 或 can,会直接抛出异常。串口初始化阶段最常见的失败是 Failed to open serial port,通常由以下原因导致:
- udev 规则未生效,导致
/dev/ttyUSB0不存在或权限为root:root; - IMU 被其他进程占用(如之前异常退出的实例未释放 fd);
- 波特率设置不匹配(默认要求 921600,且 IMU 固件端频率需大于 200 Hz)。
若推理节点已正常启动,但 get_quat() 或 get_ang_vel() 始终返回全零或恒定值,说明串口虽打开但解析器未收到完整数据包。可用 sudo cat /dev/ttyUSB0 快速验证硬件是否有数据流出(会显示乱码),若无输出则检查 IMU 供电与接线。
Sources: hipnuc_imu_driver.cpp, serial_port.cpp
推理配置与 ONNX 模型加载错误
推理节点在构造阶段会执行严格的配置校验,任何不匹配都会以 std::runtime_error 抛出并在 main() 中被捕获为 RCLCPP_FATAL。以下是构造阶段的高频报错:
ONNX input size mismatch:模型的输入维度与配置中 obs_num * frame_stack + extra_obs_num 不符。排查时请核对 .onnx 模型的输入 shape 与 inference.yaml 中 obs_layouts、frame_stacks、extra_obs_layouts 的乘积是否一致。
Motion file has no frames 或 Motion joint count mismatch:运动序列 .npz 文件损坏、缺少 fps/joint_pos/joint_vel 字段,或关节数与 joint_num 不一致。可用 Python 快速验证:np.load('motion.npz')['joint_pos'].shape 的第二维应为 23。
Unsupported obs stack order 或 Unsupported obs source**:obs_stack_orders 仅支持 frame_major 与 obs_major;obs_layouts 中的字段名必须是 ang_vel、gravity_b、cmd_vel、dof_pos、dof_vel、last_action、interrupt、perception、motion_pos、motion_vel 之一,且格式严格为 name:size。
Sources: inference_node.cpp, motion_loader.cpp, obs_manager.cpp
运行时安全保护触发
推理节点在 inference 线程的每次循环中执行两类安全检测,一旦触发即调用 rclcpp::shutdown() 终止整个进程:
- 机器人倾倒检测:
get_gravity_b_obs计算机体坐标系下的重力向量,若gravity_b.z() > gravity_z_upper_(默认-0.5),说明机体姿态已严重偏离竖直,日志输出Robot fell down! Shutting down...。 - 关节限位检测:
get_dof_pos_obs检查每个关节位置是否超出joint_limits范围,若越界则输出Joint X out of limit! Shutting down...。
此外,若推理循环耗时超过理论周期(dt * decimation,例如 0.004 * 5 = 20 ms),节点会输出 Inference loop overran! Took X us, but period is Y us. 的 WARN 日志。偶发性超 run 通常由系统临时负载引起;若持续出现,需检查 ONNX Runtime 的线程数 intra_threads 是否设置合理,或是否未使用实时内核。
Sources: obs_manager.cpp, inference_node.cpp
ROS2 服务调用失败
所有 ROS2 服务(/init_motors、/set_zeros、/start_inference 等)在执行前都会进行状态预检查,并以 std_srvs/srv/Trigger::Response 返回结构化失败原因。调用服务时若返回 success: false,请直接查看 message 字段。常见预检查规则如下:
/set_zeros与/reset_joints:要求电机已初始化(is_init_ == true)且推理未运行(is_running == false)。/start_inference:要求推理当前处于暂停状态;若已在运行则返回Inference is already running!。/clear_errors:不依赖电机初始化状态,但要求robot_实例已创建。/read_imu:要求imu_已初始化,否则返回IMU is not initialized。
服务层会捕获底层异常(如电机离线抛出的 std::runtime_error)并将其写入 response->message,因此服务返回值是定位硬件层故障的快捷通道。
Sources: ros_interface.cpp
Python SDK 与脚本调试
使用 scripts/set_zero.py、scripts/motors_py_example.py 等脚本时,最常见的报错是 ModuleNotFoundError: No module named 'motors_py'(或 imu_py、robot_py)。这三个模块并非 pip 安装包,而是工作空间编译后通过 pybind11 生成的共享库,必须满足以下前置条件:
- 已完成
colcon build --symlink-install; - 当前终端已
source /opt/ros/humble/setup.bash与source install/setup.bash; PYTHONPATH包含工作空间的install/路径(由setup.bash自动设置)。
set_zero.py 在运行时会读取 scripts/config/set_zero.yaml,其字段应与 src/inference/config/robot.yaml 中的 motors 段落保持一致。若 motor_id、motor_interface、motor_num 的长度不匹配,脚本会在 create_motors() 阶段抛出异常。
Sources: set_zero.py, README_CN.md
Screen 后台会话管理
start_robot.sh 使用 screen 创建 inference_session 与 joy_session 两个后台会话。日常调试中常见的操作误区包括:
- 无法 attach:若终端提示
There is no screen to be resumed matching inference_session,可能是会话已崩溃退出。使用screen -ls查看存活会话。 - 误按 Ctrl+C:在 screen 内按 Ctrl+C 会终止节点而非 detach,导致会话变为空白但进程已消失。正确退出方式是 Ctrl+A 然后按 D。
- 残留会话冲突:若脚本上次启动失败后未清理,再次运行可能因同名会话已存在而行为异常。手动执行
screen -S inference_session -X quit与screen -S joy_session -X quit进行清理。
Sources: start_robot.sh
系统性排查流程
当故障现象不明确时,建议按照**“环境 → 通信 → 硬件 → 算法”**的分层顺序逐步收敛。以下 Mermaid 流程图展示了一条从启动失败到根因定位的完整路径:
flowchart TD
A[启动 ./tools/start_robot.sh] --> B{编译通过?}
B -->|否| C[检查依赖: colcon, ros2, screen]
B -->|是| D{节点启动成功?}
D -->|否| E[检查 DDS 配置与 XML 语法]
D -->|是| F{实时优先级设置成功?}
F -->|否| G[检查 limits.conf 与 ulimit -r]
F -->|是| H{CAN 接口 UP?}
H -->|否| I[检查 udev 规则与 ip a]
H -->|是| J{电机初始化成功?}
J -->|否| K[检查电机错误码与供电]
J -->|是| L{推理运行后异常退出?}
L -->|是| M{日志含 fell down / out of limit?}
M -->|是| N[检查机械零点与关节限位]
M -->|否| O{日志含 Motor offline?}
O -->|是| P[检查 CAN 线束与总线负载]
O -->|否| Q[检查 ONNX 模型与 obs 配置]
该流程优先排除环境层与通信层问题,再深入硬件状态与算法配置,符合“上层现象往往由下层根因引起”的调试原则。
Sources: start_robot.sh
推荐阅读与下一步
完成问题修复后,若需深入理解相关子系统的内部机制,可继续阅读以下页面:
- 通信协议层:CAN/CANFD 与串口 —— 理解 SocketCAN 线程模型与实时优先级绑定逻辑
- RobotInterface 硬件抽象层 —— 理解电机离线检测与闭链解耦的实现细节
- ONNX 模型加载与实时推理 —— 理解推理线程周期与观测堆叠的数学关系
- 配置文件系统详解 —— 理解
inference.yaml与robot.yaml的字段约束与联动关系