🤖 roboto_origin_03 Wiki
首页 / 部署 / 电机零点标定

电机零点标定是机器人首次装机、更换电机或零点丢失后必须执行的关键步骤。其本质是告诉每个关节驱动器「当前机械位置即为逻辑零位」,使得后续所有控制指令中的位置值都有统一的物理基准。如果零点不准,机器人站立姿态会歪斜,推理策略的输出也无法正确映射到关节动作。本页面向初学者介绍仓库提供的两种标定方式:交互式脚本逐电机标定(适合首次装机),以及 ROS2 服务批量标定(适合软件已运行时的快速重置)。

Sources: README_CN.md

标定前的准备工作

无论采用哪种方式,都需要先确认硬件环境和软件依赖已经就绪。首先,CAN 接口必须处于 up 状态;推荐通过 硬件连接与 CAN/IMU 映射 中介绍的 udev 规则自动完成绑定,这样就不用手动执行 ip link set 指令。其次,工作空间需要至少完成一次编译,以生成 motors_pyrobot_py 等 Python 绑定模块和 ROS2 可执行文件。最后,在运行任何命令前,请在当前终端 source ROS2 环境和工作空间环境:

source /opt/ros/humble/setup.bash
source install/setup.bash

如果你的终端还没有编译过工作空间,请先执行 colcon build --symlink-install。Python 脚本额外依赖 python3-yaml,可通过 sudo apt install python3-yaml 安装。

Sources: README_CN.md, README_CN.md

方式一:交互式脚本标定

scripts/set_zero.py 是最推荐的首次装机标定工具。它会按照 scripts/config/set_zero.yaml 中定义的顺序,逐个电机进行初始化、进入阻尼模式、等待你手动将关节摆到零位,最后按 Enter 将当前位置写入该电机硬件零位。其优点是精细化、可跳过个别电机、无需启动完整 ROS2 推理节点。

标定流程

flowchart TD
    A[运行 python3 scripts/set_zero.py] --> B[读取 set_zero.yaml 配置]
    B --> C[创建电机对象列表]
    C --> D[按顺序取下一个电机]
    D --> E[使能电机并进入 MIT 阻尼模式]
    E --> F[实时显示当前位置与错误码]
    F --> G{用户按键}
    G -->|Enter| H[调用 set_motor_zero 写入硬件零位]
    G -->|空格| I[跳过当前电机]
    G -->|Ctrl+C| J[中断标定]
    H --> K[失能电机]
    I --> K
    K --> L{还有电机?}
    L -->|是| D
    L -->|否| M[输出标定结果摘要]

运行以下命令启动交互式标定:

python3 scripts/set_zero.py

脚本启动后会先打印配置摘要,包括电机 ID 列表、CAN 接口分配和电机型号。按下 Enter 开始后,第一个电机进入阻尼模式——此时你可以自由转动该关节。终端会实时刷新当前位置(单位:rad)和错误码,你只需将机器人关节摆到目标零位,按 Enter 确认即可。若该电机暂时不需要标定,按空格键跳过。

Sources: scripts/set_zero.py

配置文件说明

scripts/config/set_zero.yaml 定义了脚本需要通信的全部电机参数,各字段含义如下:

字段 示例值 说明
motor_id [1, 2, 3, ...] 所有电机的 CAN 节点 ID,顺序决定标定顺序
motor_interface_type "can" 通信接口类型,DM 电机通常为 can
motor_interface ["can0", "can1", ...] CAN 总线接口名
motor_num [6, 7, 5, 5] 每条 CAN 总线上的电机数量,与 motor_interface 一一对应
motor_type "DM" 电机品牌,可选 DM / EVO / LRO
motor_model [1, 1, 1, ...] 型号枚举,DM 电机中 0 代表 DM4340P-48V,1 代表 DM10010L-48V
master_id_offset 16 DM 电机主站 ID 偏移,用于 CAN 回包识别
motor_zero_offset [0.0, ...] 软件级零位偏置,标定时通常全填 0.0

在首次标定前,请核对该文件中的 motor_idmotor_interfacemotor_num 是否与你的实际硬件接线一致。若电机型号与示例不同,需同步修改 motor_model 项。

Sources: scripts/config/set_zero.yaml

脚本内部的控制逻辑

脚本对每个电机执行的标准流程由 calibrate_motor() 函数实现:先调用 motor.init_motor() 使能,再切换到 MIT 控制模式,随后在循环中持续发送 motor_mit_cmd(0.0, 0.0, 0.0, 1.0, 0.0) 指令。这条指令的含义是目标位置 0、目标速度 0、位置环增益 0、速度环增益 1.0、前馈力矩 0,等效于纯阻尼状态——关节像安装了缓降液压杆一样可以自由推动,但又不会快速晃动。当用户确认零位后,脚本调用 motor.set_motor_zero() 向电机发送达妙协议规定的「写零」CAN 帧(数据域前 7 字节为 0xFF,第 8 字节为 0xFE),电机收到后将当前机械位置固化为内部逻辑零位。

Sources: scripts/set_zero.py, src/motors/src/drivers/dm/dm_motor_driver.cpp

方式二:ROS2 服务批量标定

当机器人软件已经启动、电机已经完成初始化且推理节点未运行时,可以使用 /set_zeros ROS2 服务一次性将所有电机的当前姿态写为零点。这种方式适合软件运行过程中发现零点漂移后的快速修正,或者你已用夹具将机器人固定到标准零位后需要批量落零。

标定流程

flowchart TD
    A[启动机器人 ./tools/start_robot.sh] --> B[调用 /init_motors 使能电机]
    B --> C[将机器人摆到目标零位]
    C --> D[确认推理未运行]
    D --> E[调用 /set_zeros 服务]
    E --> F{电机已初始化?}
    F -->|否| G[返回失败: Motors are not initialized]
    F -->|是| H{推理正在运行?}
    H -->|是| I[返回失败: Inference is running]
    H -->|否| J[并行调用所有电机的 set_motor_zero]
    J --> K[返回成功]

具体操作命令如下:

source /opt/ros/humble/setup.bash
source install/setup.bash
./tools/start_robot.sh
ros2 service call /init_motors std_srvs/srv/Trigger
# 确认机器人处于目标零位且推理未运行
ros2 service call /set_zeros std_srvs/srv/Trigger

服务内部会先进行两个安全检查:首先确认电机已经初始化(robot_->is_init_),其次确认推理当前不在运行状态(is_running_)。任一条件不满足都会立即拒绝调用,防止在电机未使能或机器人正在运动时误写零位。通过检查后,InferenceNode 调用 RobotInterface::set_zeros(),后者通过 exec_motors_parallel() 并发地对所有电机执行 set_motor_zero()

Sources: src/inference/src/ros_interface.cpp, src/inference/src/robot_interface.cpp

理解「硬件零位」与「软件偏置」

初学者容易混淆的两个概念是电机硬件零位set_motor_zero 写入的值)和软件零位偏置motor_zero_offset)。它们在系统中位于不同层级,共同决定最终关节位置。

flowchart LR
    subgraph 硬件层
        A[机械关节实际角度] --> B[电机编码器读数]
        B --> C[电机内部硬件零位]
    end
    subgraph 软件层
        C --> D[驱动层反馈位置<br/>get_motor_pos]
        D --> E[motor_zero_offset<br/>软件偏置叠加]
        E --> F[推理节点观测值]
    end

硬件零位保存在电机驱动器的 Flash 或寄存器中,断电不丢失。调用 set_motor_zero()/set_zeros 修改的就是这一层。它的作用是让电机反馈的原始位置在机械零位时等于 0 rad。

软件零位偏置src/inference/config/robot.yaml 中的 motor_zero_offset 字段定义,在创建电机对象时传入 MotorDriver::create_motor(),并在驱动层的 can_rx_cbk() 中叠加到反馈位置上。典型应用场景是腰部 yaw 电机:如果你将腰部 yaw 转至限位块处进行标定,则保留默认值 2.093;如果你使用打印件将腰部 yaw 固定到机械正中再进行标定,则应将该值改为 0.0。软件偏置不改变电机内部的零位,仅在驱动层做坐标变换,使得上层推理看到的关节角度与 URDF 模型一致。

Sources: src/inference/config/robot.yaml, src/motors/src/drivers/dm/dm_motor_driver.cpp, src/inference/src/robot_interface.cpp

标定后的验证与排错

完成标定后,建议进行以下验证:重新上电或重新初始化电机,读取各关节位置,确认机械处于零位时反馈值接近 0 rad。如果某个电机标定后反馈值明显偏离 0(超过 ±0.01 rad),驱动层会输出 set zero error 警告,因为 DmMotorDriver::set_motor_zero() 在写零后会自动刷新状态并检查当前位置是否落在 judgment_accuracy_threshold(1e-2 rad)范围内。

常见故障排查:

现象 可能原因 解决方法
脚本提示「创建电机失败」 CAN 接口未 up 或 udev 规则未生效 检查 ip a 中是否有 can0~can3,参考 硬件连接与 CAN/IMU 映射
电机无阻尼、无法手动转动 电机未正确使能或存在错误码 观察终端错误码,调用 clear_motor_error() 后重试
set_zero 后位置仍不为 0 电机未响应写零指令 检查 CAN 接线,确认电机型号与 motor_model 一致
/set_zeros 返回失败 电机未初始化或推理正在运行 先调用 /init_motors,确认推理已停止
上电后零点漂移 电机内部零位未保存到 Flash 部分电机需额外调用 write_motor_flash()

Sources: src/motors/include/motor_driver.hpp, src/motors/src/drivers/dm/dm_motor_driver.cpp

下一步

完成零点标定后,请务必核对 src/inference/config/robot.yaml 中的 motor_zero_offset 是否与你的实际标定方式匹配,然后就可以启动机器人软件了。继续阅读 启动机器人与推理节点 了解如何使用 ./tools/start_robot.sh 运行推理和手柄控制。如果你想深入理解电机驱动内部如何实现 MIT 阻尼控制和 CAN 指令封装,可以参考 电机驱动模块与 MIT 控制;若对配置文件各字段的系统级含义感兴趣,可前往 配置文件系统详解