🤖 roboto_origin_03 Wiki
首页 / 项目根 / Python SDK与二次开发

Atom01的部署框架不仅提供了基于ROS2 C++的实时推理节点,还通过pybind11将底层硬件驱动封装为原生Python模块,使开发者能够在Python生态中直接控制电机、读取IMU、执行动作序列,乃至构建自定义的上层算法。这一设计在保留C++高性能硬件交互的同时,充分利用了Python在快速原型、数据处理和算法验证方面的优势。本章面向具备高级开发能力的工程师,系统阐述Python SDK的三层架构、API语义、典型开发范式及与ROS2推理节点的协作边界。

Sources: pybind_module.cpp, pybind_module.cpp, pybind_module.cpp

SDK架构与模块边界

Python SDK采用分层解耦的设计哲学,由三个独立编译的pybind11模块构成,分别对应硬件抽象层中的电机驱动、惯性测量单元和高层机器人接口。这种划分允许开发者根据场景灵活选择切入层级:仅需调试单个电机时可只导入motors_py,开发全身控制算法时则使用robot_py

下图展示了三个Python模块与底层C++架构的映射关系。所有模块均基于同一套C++驱动库编译,这意味着Python接口与ROS2推理节点inference_node共享完全一致的硬件协议实现、 ankle解耦算法和线程池调度逻辑。

graph TD
    subgraph Python_Runtime["Python运行时"]
        A["motors_py<br/>电机原生控制"]
        B["imu_py<br/>IMU数据读取"]
        C["robot_py<br/>全身统一接口"]
    end
    
    subgraph C++_Core["C++硬件抽象层"]
        D["MotorDriver<br/>+ DM/EVO/LRO协议"]
        E["IMUDriver<br/>+ HIPNUC协议"]
        F["RobotInterface<br/>+  ankle解耦 + 线程池"]
    end
    
    subgraph Hardware["物理硬件"]
        G["CAN/CANFD总线<br/>23关节执行器"]
        H["串口 /dev/ttyUSB0<br/>HIPNUC IMU"]
    end
    
    A -->|pybind11| D
    B -->|pybind11| E
    C -->|pybind11| F
    F --> D
    F --> E
    D -->|SocketCAN| G
    E -->|termios| H

Sources: CMakeLists.txt, CMakeLists.txt, CMakeLists.txt, robot_interface.cpp

环境依赖与编译安装

三个Python模块随部署仓库一同编译,不依赖ROS2运行时即可导入使用(尽管编译过程会检测ament_cmake以支持ROS2工作流)。编译产物会被安装到系统Python的site-packages目录,因此安装后可在任意Python脚本中直接import

编译前需确保主控已安装基础依赖。根据部署仓库说明,除ROS2 Humble外,还需准备ccachelibfmt-devlibspdlog-devlibeigen3-dev以及python3-dev。若使用仓库中的Python示例脚本(如set_zero.pymotion_player.py),还需额外安装python3-yamlpython3-numpy

# 1. 安装系统依赖
sudo apt install -y ccache libfmt-dev libspdlog-dev libeigen3-dev python3-dev python3-yaml python3-numpy

# 2. 进入部署工作空间编译
cd ~/atom01_deploy
colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release

# 3.  source 环境后即可导入
source install/setup.bash
python3 -c "import motors_py, imu_py, robot_py; print('SDK加载成功')"

motors_pyimu_py的CMake配置体现了双模式分发策略:当检测到ament_cmake时导出ROS2包元数据;否则通过自定义Config.cmake支持独立Debian包构建。robot_py则严格依赖ROS2生态,因为它在内部链接了roboto_motors::roboto_motorsroboto_imu::roboto_imu两个导出目标。

Sources: README_CN.md, CMakeLists.txt, CMakeLists.txt

motors_py:电机驱动模块

motors_py是面向单个电机或电机组进行精细控制的基础模块。它通过工厂方法MotorDriver.create_motor()统一封装了达妙(DM)、京对准能(EVO)、乐聚(LRO)等多种电机的协议差异,对Python层暴露一致的API。当前支持的通信接口包括标准CAN 2.0和CAN-FD。

电机控制模式通过枚举MotorControlMode暴露,包含三种核心模式:MIT阻抗控制(同时指定位置、速度、刚度、阻尼与前馈力矩)、位置模式POS,指定目标位置与运动速度)以及速度模式SPD,指定目标转速)。其中MIT模式是强化学习策略部署中的主要控制模式,因为它允许策略网络直接输出目标位置并由电机驱动器内部的PD环跟踪。

下表汇总了MotorDriver类在Python侧暴露的全部方法及其典型用途。

方法 参数 返回值 语义说明
create_motor motor_id, interface_type, interface, motor_type, motor_model, master_id_offset=0, motor_zero_offset=0.0 MotorDriver实例 工厂方法,根据motor_type字符串自动分派到对应驱动子类
init_motor int 使能电机,完成内部初始化
deinit_motor 失能电机并释放总线资源
set_motor_control_mode mode: MotorControlMode 切换MIT/POS/SPD模式
motor_mit_cmd f_p, f_v, f_kp, f_kd, f_t 发送单电机MIT指令
motor_pos_cmd pos, spd, ignore_limit=False 位置模式指令
motor_spd_cmd spd 速度模式指令
get_motor_pos float 当前转子位置(rad)
get_motor_spd float 当前转速(rad/s)
get_motor_current float 当前电流(A)
get_motor_temperature float 当前温度(°C)
get_error_id int 错误码,非零表示存在故障
clear_motor_error 清除电机错误状态
set_motor_zero bool 将当前位置标定为机械零位
write_motor_flash bool 将当前内存参数烧录至Flash持久化
refresh_motor_status 主动查询电机最新 telemetry 数据
get_can_name str 返回该电机绑定的CAN接口名

Sources: pybind_module.cpp, motor_driver.hpp

imu_py:惯性测量单元模块

imu_py模块提供对HIPNUC系列IMU的串口访问封装。与motors_py类似,它也采用工厂模式IMUDriver.create_imu(),允许通过统一的字符串参数指定接口类型(如"serial")、设备路径(如"/dev/ttyUSB0")及传感器型号。模块内部通过spdlog输出彩色日志,便于调试物理连接问题。

IMU数据在Python侧以list[float]形式返回,具体语义如下:get_quat()返回[w, x, y, z]顺序的四元数;get_ang_vel()返回[x, y, z]顺序的角速度,单位为rad/s;get_lin_acc()返回[x, y, z]顺序的线加速度,单位为m/s²。这些数据与ROS2推理节点中obs_manager使用的观测数据同源,因此Python层采集的数据可直接用于离线策略训练或数据标注。

Sources: pybind_module.cpp, imu_driver.hpp

robot_py:高层机器人统一接口

robot_py是整个Python SDK中最关键的模块,它将23个电机、IMU、 ankle闭链解耦、URDF到电机的映射、外参旋转矩阵等复杂配置,收敛为一个YAML驱动的RobotInterface类。对于二次开发者而言,这意味着无需手动管理23个电机实例和CAN总线细节,只需加载一份与ROS2推理节点共享语义的配置文件,即可通过apply_action()向全身发送动作指令。

RobotInterface在C++层实现了以下关键机制,这些机制在Python调用时完全透明但至关重要。首先,电机按照所属CAN总线被分组,通过线程池实现总线级并行下发,降低多电机控制延迟。其次,对于Atom01的 ankle闭链结构(左右腿各一对),apply_action()内部会自动执行正运动学解耦与逆运动学耦合:读取电机编码器时,将并联关节电机空间转换到独立关节空间;下发指令时,将独立关节空间的力矩目标反解回电机空间。最后,IMU数据会经过extrinsic_R外参旋转矩阵校正,输出与机体坐标系对齐的四元数和角速度。

下表列出了RobotInterface暴露的Python API。

方法 参数 返回值 语义说明
RobotInterface(config_file) config_file: str 实例 构造函数,解析YAML并初始化所有硬件
init_motors 批量使能全部电机,设置is_inittrue
deinit_motors 批量失能全部电机
apply_action action: list[float] 发送23维动作向量,内部执行反馈读取、 ankle解耦、MIT指令下发
reset_joints joint_default_angle: list[float] 以渐进刚度方式将所有关节归位到默认角度
set_zeros 批量标定所有电机零位
clear_errors 批量清除所有电机错误
refresh_joints 手动触发一次全关节状态刷新
get_joint_q list[float] 获取23维关节位置(已应用motor_sign和 ankle解耦)
get_joint_vel list[float] 获取23维关节速度
get_joint_tau list[float] 获取23维关节力矩/电流
get_quat list[float] 获取校正后的机体四元数[w,x,y,z]
get_ang_vel list[float] 获取校正后的机体角速度
is_init (只读属性) bool 电机是否已完成初始化

Sources: pybind_module.cpp, robot_interface.hpp, robot_interface.cpp

典型开发示例

示例一:单电机MIT模式调试

以下脚本演示了如何使用motors_py直接控制单个电机进入MIT阻抗模式。这种模式常用于验证单个关节的机械安装方向、刚度范围及零位偏移。代码中master_id_offset=16是因为达妙电机协议中主控ID通常偏移16以避免与电机基础ID冲突。

#!/usr/bin/env python3
import motors_py
import time

def example_can_motor():
    motor = motors_py.MotorDriver.create_motor(
        motor_id=1,
        interface_type="can",
        interface="can0",
        motor_type="DM",
        motor_model=0,
        master_id_offset=16,
    )
    motor.init_motor()
    motor.set_motor_control_mode(motors_py.MotorControlMode.MIT)
    
    # 发送MIT指令:目标位置-0.5rad,kp=5.0, kd=1.0
    motor.motor_mit_cmd(-0.5, 0.0, 5.0, 1.0, 0.0)
    time.sleep(1)
    
    pos = motor.get_motor_pos()
    vel = motor.get_motor_spd()
    print(f"位置: {pos:.4f} rad, 速度: {vel:.4f} rad/s")
    motor.deinit_motor()

Sources: motors_py_example.py

示例二:IMU数据流采集

以下脚本以100Hz频率读取IMU数据。注意get_quat()等方法是直接从内存中读取最新缓存值,不涉及串口阻塞;若需要强制刷新IMU寄存器,取决于具体IMU驱动实现。

#!/usr/bin/env python3
import imu_py
import time

imu = imu_py.IMUDriver.create_imu(
    imu_id=8,
    interface_type="serial",
    interface="/dev/ttyUSB0",
    imu_type="HIPNUC",
    baudrate=921600
)

for _ in range(1000):
    quat = imu.get_quat()      # [w, x, y, z]
    omega = imu.get_ang_vel()  # [x, y, z] rad/s
    acc = imu.get_lin_acc()    # [x, y, z] m/s^2
    print(f"四元数: {quat}")
    time.sleep(0.01)

Sources: imu_py_example.py

示例三:交互式零位标定

set_zero.py是实际部署中高频使用的工具脚本。它将所有电机逐个置于纯阻尼模式(kp=0, kd=1.0),允许工程师手动拖动关节到机械零位后按Enter确认。脚本通过termios实现非阻塞键盘读取,并支持空格键跳过特定电机。该脚本直接操作motors_py,不依赖ROS2,适合在无图形界面的终端环境中执行。

# 核心逻辑:将电机设为MIT模式纯阻尼,等待用户确认
motor.set_motor_control_mode(motors_py.MotorControlMode.MIT)
while True:
    motor.motor_mit_cmd(0.0, 0.0, 0.0, 1.0, 0.0)  # 纯阻尼
    pos = motor.get_motor_pos()
    print(f"\r当前位置: {pos:+.6f} rad | [Enter]标零 / [空格]跳过", end='')
    
    key = read_key_nonblocking(0.05)
    if key == '\r':
        motor.set_motor_zero()
        break
    elif key == ' ':
        break

Sources: set_zero.py

示例四:动作序列回放

motion_player.py展示了robot_py在复杂场景下的使用方式。它读取.npz格式的动作文件(包含joint_posjoint_velfps),通过RobotInterface以200Hz控制周期逐帧驱动机器人。脚本支持--usd2urdf参数,用于在USD关节顺序与URDF关节顺序不一致时进行重映射,这一特性在将Isaac Sim训练数据迁移到实机时尤为重要。

class MotionPlayer:
    def __init__(self, motion_file, config_file, speed=1.0):
        self.robot = robot_py.RobotInterface(config_file)
        self.robot.init_motors()
        self.robot.reset_joints(self.default_angles)
        
    def step_once(self):
        self.robot.apply_action(self.positions)

Sources: motion_player.py

配置系统与YAML语义

robot_py的配置文件采用与ROS2推理节点完全兼容的YAML格式,通常位于src/inference/config/robot.yaml。理解该配置文件的语义对于二次开发至关重要,因为它同时定义了硬件拓扑和控制增益。

motors字段描述电机总线拓扑。motor_interface列出所有CAN接口名,motor_num按顺序声明每个接口上挂载的电机数量。例如["can0", "can1", "can2", "can3"]配合[6, 7, 5, 5]表示can0有6个电机,can1有7个,以此类推,总计23个。motor_id按遍历顺序依次编号,必须与物理接线一致。master_id_offset是CAN主控ID偏移量,达妙电机通常设为16。

robot字段描述运动学和控制参数。motor_sign用于修正电机安装方向导致的符号反转;close_chain_motor_id声明 ankle闭链中涉及的4个电机ID;urdf2motor定义URDF关节索引到电机遍历索引的映射;extrinsic_R是3×3旋转矩阵(行优先),用于将IMU坐标系对齐到机体坐标系;kpkd是MIT模式下的默认位置增益和速度增益,按关节独立配置。

以下是一段简化的配置示意:

imu:
    imu_id: 8
    imu_interface_type: "serial"
    imu_interface: "/dev/ttyUSB0"
    imu_type: "HIPNUC"
    baudrate: 921600

motors:
    motor_id: [1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23]
    motor_interface_type: "can"
    motor_interface: ["can0", "can1", "can2", "can3"]
    motor_num: [6, 7, 5, 5]
    motor_type: ["DM", "DM", "DM", "DM"]
    master_id_offset: 16

robot:
    kp: [100.0, 100.0, ...]   # 23维
    kd: [3.3, 3.3, ...]       # 23维
    motor_sign: [1, 1, 1, ...] # 23维
    close_chain_motor_id: [5, 6, 11, 12]
    urdf2motor: [0, 1, 2, ..., 22]
    extrinsic_R: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]

Sources: robot.yaml

二次开发范式与进阶主题

范式一:纯Python实时控制循环

对于不需要ROS2中间件的极简场景(如单机演示、教学实验),可直接基于robot_py构建200Hz控制循环。注意apply_action()内部已包含反馈读取和并行下发,因此单次调用耗时在亚毫秒级,Python层面的循环频率主要受GIL和系统调度影响。

import robot_py
import time

robot = robot_py.RobotInterface("robot.yaml")
robot.init_motors()
robot.reset_joints(default_angles)

period = 1.0 / 200
while True:
    t0 = time.time()
    action = my_policy(obs)   # 自定义策略
    robot.apply_action(action.tolist())
    elapsed = time.time() - t0
    time.sleep(max(0, period - elapsed))

范式二:与NumPy/SciPy生态集成

由于robot_pyget_joint_q()等方法返回Python原生list,可无缝转换为numpy.ndarray进行矩阵运算。motion_player.py中的MotionLoader类即是这种范式的典型:利用np.load()读取动作数据集,通过tolist()转换为Python列表后传入apply_action()。反向路径同样成立——可将IMU和关节数据批量采集为.npz文件,用于后续的Sim2Real校准或数据集构建。

范式三:自定义电机协议扩展

若需接入新型号电机,应在C++层实现MotorDriver纯虚接口,并在motor_driver.cpp的工厂方法中注册新类型,随后重新编译motors_py。Python绑定层通常无需修改,因为pybind_module.cpp只绑定基类MotorDriver的虚函数表。这种设计使得硬件扩展集中在C++层,Python API保持稳定。

Sources: motor_driver.cpp

与ROS2推理节点的关系澄清

robot_py与ROS2节点inference_node底层共享同一RobotInterface C++类,但二者是互斥使用的关系:inference_node作为长期运行的守护进程独占硬件总线,而robot_py脚本在运行时同样会尝试打开CAN套接字和串口。因此,切勿在inference_node启动的同时运行基于robot_py的脚本,否则会导致总线冲突。推荐的开发流程是:先使用robot_py脚本完成硬件验证和零位标定,确认无误后再启动inference_node进行策略部署。若需在ROS2框架内以Python编写上层节点,更推荐通过ROS2 Topic和Service与inference_node交互,而非直接导入robot_py

Sources: README_CN.md

故障排查与注意事项

现象 可能原因 排查方法
ImportError: motors_py not found 未source环境或编译未安装到当前Python 执行source install/setup.bash,检查python3 -c "import motors_py"
电机无响应,get_error_id()非零 CAN接口未启动或电机未使能 检查ip link show can0,确认init_motor()已调用
robot_pyMotor offline 某路CAN通信丢包严重 检查USB转CAN是否插在USB 3.0接口,减少总线负载
IMU数据全零或异常 串口波特率不匹配或udev规则未生效 确认robot.yaml中波特率与IMU上位机配置一致,检查/dev/ttyUSB0权限
apply_action抛出异常 is_initfalseaction维度不为23 确保已调用init_motors(),检查len(action)==23

Sources: README_CN.md

下一步

掌握Python SDK后,你已经具备了不依赖ROS2即可驱动Atom01全身关节和读取传感器数据的能力。如果你希望将训练好的策略模型部署到实机并接入手柄遥控、命令速度输入等完整功能,请继续阅读推理节点与ONNX策略部署。若你希望从零开始训练自己的 locomotion 策略,则应回到IsaacLab环境搭建与训练流程查阅训练侧文档。