atom01_description 是 Atom01 机器人从物理设计走向智能控制的桥梁。该模块以 URDF(Unified Robot Description Format)为核心,完整定义了 24 个刚体连杆(link)与 23 个旋转关节(joint)的运动学链、质量-惯性张量、视觉与碰撞几何,并同步提供 MuJoCo MJCF 模型与 IsaacLab 接口配置。无论你是要在仿真器中训练强化学习策略,还是将训练好的策略部署到真实硬件,都需要先理解这份描述文件如何精确刻画机器人的运动学与动力学特性。
Sources: README.md, atom01.urdf
运动学拓扑与关节架构
Atom01 的 URDF 采用树状结构,以 base_link 为根节点,向下分叉为躯干(torso)、左腿与右腿三条运动链;躯干再延伸出左臂与右臂。整条运动链共包含 23 个主动关节,总质量约 33.8 kg,构成了双足人形机器人特有的高自由度欠驱动系统。其中 base_link 在 URDF 中固定为地面参考系下的根连杆,而在 MuJoCo 与 Isaac Sim 中则会额外引入浮动基座(free joint)以支持六自由度空间运动。
下图展示了从 base_link 到末端连杆的完整关节层级:
graph TD
base_link -->|torso_joint| torso_link
base_link -->|left_thigh_yaw_joint| LTY[left_thigh_yaw_link]
LTY -->|left_thigh_roll_joint| LTR[left_thigh_roll_link]
LTR -->|left_thigh_pitch_joint| LTP[left_thigh_pitch_link]
LTP -->|left_knee_joint| LK[left_knee_link]
LK -->|left_ankle_pitch_joint| LAP[left_ankle_pitch_link]
LAP -->|left_ankle_roll_joint| LAR[left_ankle_roll_link]
base_link -->|right_thigh_yaw_joint| RTY[right_thigh_yaw_link]
RTY -->|right_thigh_roll_joint| RTR[right_thigh_roll_link]
RTR -->|right_thigh_pitch_joint| RTP[right_thigh_pitch_link]
RTP -->|right_knee_joint| RK[right_knee_link]
RK -->|right_ankle_pitch_joint| RAP[right_ankle_pitch_link]
RAP -->|right_ankle_roll_joint| RAR[right_ankle_roll_link]
torso_link -->|left_arm_pitch_joint| LAp[left_arm_pitch_link]
LAp -->|left_arm_roll_joint| LR[left_arm_roll_link]
LR -->|left_arm_yaw_joint| LY[left_arm_yaw_link]
LY -->|left_elbow_pitch_joint| LEP[left_elbow_pitch_link]
LEP -->|left_elbow_yaw_joint| LEY[left_elbow_yaw_link]
torso_link -->|right_arm_pitch_joint| RAp[right_arm_pitch_link]
RAp -->|right_arm_roll_joint| RR[right_arm_roll_link]
RR -->|right_arm_yaw_joint| RY[right_arm_yaw_link]
RY -->|right_elbow_pitch_joint| REP[right_elbow_pitch_link]
REP -->|right_elbow_yaw_joint| REY[right_elbow_yaw_link]
在运动学层面需要特别关注髋关节的偏置设计。左右腿的 thigh_yaw_joint 与 thigh_roll_joint 的旋转轴并非与机体坐标轴对齐,而是分别取 (-0.5, 0, -0.86603) 与 (0.86603, 0, -0.5) 作为关节轴。这种非正交布置源自机械结构中的斜向连杆布局,使得膝关节在俯仰运动的同时伴随一定的外展/内收耦合,从而在人类行走步态中提供更自然的落足点调节。开发者在进行正运动学解析或雅可比矩阵计算时,必须严格使用 URDF 中给出的 axis 向量,而不能假设为纯 XYZ 正交关节。
Sources: atom01.urdf, atom01.urdf
动力学参数与质量分布
URDF 中每个 link 都包含 <inertial> 块,记录了由 CAD 软件自动计算的质量、质心(CoM)偏移与惯性张量。这些参数直接决定了仿真中的重力补偿、接触冲量响应以及强化学习奖励函数中的能量惩罚项。
下表汇总了关键连杆的动力学参数,这些数据在 IsaacLab 的 ArticulationCfg 中被直接读取并用于物理积分:
| 连杆名称 | 质量 (kg) | 质心偏移 (m) | Ixx (kg·m²) | Iyy (kg·m²) | Izz (kg·m²) |
|---|---|---|---|---|---|
base_link |
5.513 | (-0.047, ~0, -0.009) | 0.0305 | 0.0154 | 0.0301 |
torso_link |
7.582 | (-0.002, ~0, 0.098) | 0.0690 | 0.0568 | 0.0389 |
left_thigh_pitch_link |
2.346 | (~0, -0.019, -0.199) | 0.0202 | 0.0216 | 0.0030 |
left_knee_link |
1.702 | (~0, -0.013, -0.152) | 0.0101 | 0.0098 | 0.0011 |
left_ankle_roll_link |
0.335 | (0.015, 0.003, -0.029) | 0.0001 | 0.0005 | 0.0006 |
从表中可以观察到两个关键设计特征。第一,torso_link 的质心相对其几何原点向上偏移约 9.8 cm,且质量达到 7.58 kg,是整机最重的部件之一;这意味着躯干俯仰对整机零力矩点(ZMP)有显著影响,也是控制算法中必须重点补偿的上半身惯性载荷。第二,大腿与小腿连杆的惯性张量呈现出明显的细长杆特征——Izz 远小于 Ixx 与 Iyy,这与沿肢体长轴的旋转惯量较小的物理直觉一致。强化学习训练时,这些精确参数保证了策略迁移到真实硬件时的动力学一致性。
Sources: atom01.urdf, atom01.urdf, atom01.urdf, atom01.urdf
碰撞几何的工程取舍
URDF 中视觉网格(<visual>)统一引用 ../meshes/ 目录下的 24 个 STL 文件,用于仿真器渲染与可视化。然而碰撞检测(<collision>)的处理则采用了更具工程实用性的分层策略:绝大部分连杆的 STL 碰撞体被注释掉,转而使用简化的盒体(box)或圆柱体(cylinder)替代。例如,left_thigh_pitch_link 使用 0.08 × 0.1 × 0.22 m 的盒体,torso_link 使用 0.16 × 0.16 × 0.22 m 的盒体,手臂关节则使用半径 0.03 m 的圆柱体。
这种简化并非精度妥协,而是基于以下工程考量。首先,高面数 STL 网格在接触动力学求解中会产生大量碰撞点,显著增加 position/velocity iteration 的计算负担;对于需要并行上千环境的强化学习训练,这直接决定了 GPU 显存占用与训练吞吐量。其次,简化几何体在大多数情况下足以捕捉自碰撞与足地接触的物理行为,尤其是下肢的盒体碰撞包裹与原始外形高度吻合。唯一保留原始 STL 碰撞的是 left_ankle_roll_link 与 right_ankle_roll_link,因为足部几何形状对接触力分布和摩擦锥建模具有决定性作用,任何过度简化都可能导致仿真中足部打滑或穿透失稳。
Sources: atom01.urdf, atom01.urdf, atom01.urdf
从 URDF 到仿真与部署
atom01_description 的价值不仅在于静态描述,更在于它为下游仿真与部署提供了单一可信源(single source of truth)。在 IsaacLab 中,roboparty.py 通过 UrdfFileCfg 直接加载 atom01.urdf,并在此基础上覆盖执行器参数与初始位姿;在 MuJoCo 中,atom01.xml 则基于同一套 mesh 与惯性数据重新组织为 MJCF 格式,增加了浮动基座、IMU 站点与丰富的传感器定义。
IsaacLab 接口配置
IsaacLab 使用 ArticulationCfg 描述机器人资产。ATOM01_CFG 配置中,URDF 的 effort 与 velocity limit 被保留,但刚度(stiffness)与阻尼(damping)在仿真侧被重新分组定义,以匹配真实电机的 PD 控制特性:
| 执行器分组 | 包含关节模式 | 力矩限制 (N·m) | 速度限制 (rad/s) | 刚度 | 阻尼 |
|---|---|---|---|---|---|
legs |
thigh_yaw/roll/pitch, knee, torso | 120.0 | 25.0 | 100–150 | 3.3–5.0 |
feet |
ankle_pitch, ankle_roll | 27.0 | 8.0 | 40.0 | 2.0 |
shoulders |
arm_pitch, arm_roll, arm_yaw | 27.0 | 8.0 | 40.0 | 2.0 |
arms |
elbow_pitch, elbow_yaw | 27.0 | 8.0 | 30–20 | 1.5–1.0 |
初始位姿将机器人放置在 z = 0.75 m 处,膝关节预弯曲约 0.3 rad,踝关节 -0.2 rad,使重心投影落在支撑多边形内,避免训练开始时即刻倾倒。activate_contact_sensors=True 与 enabled_self_collisions=True 的开启则确保足地接触与肢体间碰撞能够被强化学习奖励函数正确感知。
Sources: roboparty.py
MuJoCo 模型与传感器
MJCF 文件 atom01.xml 在拓扑上与 URDF 完全一致,但做了三项关键扩展。第一,在 base_link 上添加 floating_base_joint,将系统从 URDF 的固定根节点转换为 29 自由度(6 + 23)的浮动基座系统。第二,为所有 23 个关节配置 motor 执行器,统一输出限制为 ±200 N·m,并附加 leg_joint_param、arm_joint_param 与 waist_joint_param 三类默认参数,分别设置阻尼 0.01、摩擦损耗 0.01 与等效惯量 0.01。第三,在 sensor 块中注册了 69 个传感器通道,覆盖关节位置、速度、力矩以及 IMU 的角速度、线加速度、方向四元数等,为 Sim2Sim 验证与 MuJoCo 独立仿真提供完整的观测接口。
Sources: atom01.xml, atom01.xml, atom01.xml
部署端的关节映射与参数对齐
在真实硬件部署时,modules/atom01_deploy/src/inference/config/robot.yaml 承担起了 URDF 抽象到物理电机 ID 的映射职责。urdf2motor 数组给出了从 URDF 关节索引(0 起始)到 CAN 总线电机 ID(1 起始)的一一对应关系,共 23 个元素,顺序与 URDF 中关节声明顺序完全一致。kp 与 kd 数组则复现了 IsaacLab 中 DelayedPDActuatorCfg 的分组参数,例如 thigh_pitch 对应 100/3.3,knee 对应 150/5.0,elbow_yaw 对应 20/1.0。
此外,motor_sign 字段记录了部分关节的旋转方向反转。例如右侧大腿俯仰、右侧膝关节、右侧脚踝关节以及部分右臂关节的符号为 -1,这补偿了机械装配中电机输出轴与 URDF 关节轴方向相反的情况。close_chain_motor_id 则标识了踝部并联闭链所对应的电机,提示控制程序需要进行额外的运动学校正。这种从 URDF → 仿真参数 → 部署配置的严格一致性,是 Sim2Real 成功迁移的基础。
Sources: robot.yaml
文件目录结构
modules/atom01_description/
├── urdf/
│ └── atom01.urdf # 主 URDF 描述文件(23 关节 / 24 连杆)
├── mjcf/
│ ├── atom01.xml # MuJoCo 模型(含浮动基座与传感器)
│ └── atom01_terrain.xml # 带地形变体的 MuJoCo 场景
├── meshes/
│ ├── base_link.STL # 24 个可视化/碰撞网格
│ ├── left_thigh_pitch_link.STL
│ ├── ...
│ └── torso_link.STL
└── terrain_assets/
└── terrain_hfield.png # 地形高度场纹理
当你需要修改机器人的物理参数(如加装新传感器导致质量分布变化)时,应当优先更新 atom01.urdf 中的 <inertial> 块,并同步验证 roboparty.py 中的初始位姿与 robot.yaml 中的 kp/kd 是否仍然适用。
Sources: get_dir_structure 输出
下一步阅读
理解 URDF 的运动学与动力学描述后,你可以继续深入以下主题:
- 若需在 MuJoCo 或 Isaac Sim 中配置更复杂的仿真场景与接触参数,请参阅 MuJoCo与Isaac Sim模型配置。
- 若准备基于 IsaacLab 开展强化学习训练,请阅读 IsaacLab环境搭建与训练流程。
- 若关注如何将训练策略映射到真实电机并理解
robot.yaml中的电机型号与零位标定,请参阅 电机驱动与CAN总线通信。