Unitree RL Lab 官方案例训练教程

本文整理 unitree_rl_lab 官方仓库中 Unitree-G1-29dof-Velocity 官方案例的基础运行流程,目标是先把 G1 人形机器人的示例顺利跑起来,再继续做参数调优、策略导出和实体部署。

1. 目标

运行 G1 29 自由度人形机器人的官方速度跟踪案例,核心任务名为:

Unitree-G1-29dof-Velocity

跑通后的最小验收标准为:

  • 能正确加载 G1 机器人模型
  • 能启动训练 Unitree-G1-29dof-Velocity 任务
  • 能接续 checkpoint 继续训练

2. 重要前提

开始前建议先确认:Isaac LabIsaac Sim 版本匹配;若 Isaac SimIsaac Lab 还未安装,可以先参考安装教程

version_match

说明:Isaac Sim 是底层仿真平台(基于 PhysX),提供真实的物理世界,不负责训练;Isaac Lab 是构建在 Isaac Sim 之上的训练框架,在所提供的物理仿真环境中,负责定义任务并用强化学习训练策略生成 .pt;而 MuJoCo 是另一个独立的物理世界,用来加载导出的 ONNX + deploy.yaml,在不同物理规律下检验策略是否真正具备泛化能力,而非仅仅适应了 Isaac Sim 的物理特性。

3. 克隆官方仓库

git clone https://github.com/unitreerobotics/unitree_rl_lab.git
cd unitree_rl_lab

4. 安装 unitree_rl_lab

先激活 Isaac Lab 对应环境:

conda activate env_isaaclab

然后在 unitree_rl_lab 路径下执行:

./unitree_rl_lab.sh -i

安装完成后,重开一个 shell,确保环境变量和自动补全生效。

5. 下载机器人模型资源

官方提供两种方式:

  • 方式一:使用 USD 模型
  • 方式二:使用 URDF 模型

如果本机 Isaac Sim / Isaac Lab 版本已经比较新,官方更推荐 URDF 方案。常见做法是直接拉取 unitree_ros

git clone https://github.com/unitreerobotics/unitree_ros.git

当选择下载 unitree_model 时,请 务必 启用 git lfs

sudo apt update
sudo apt install git-lfs
git lfs install
git clone https://github.com/unitreerobotics/unitree_model.git

然后在 unitree_rl_lab 目录下修改文件 unitree.py

nano source/unitree_rl_lab/unitree_rl_lab/assets/robots/unitree.py

把里面的路径改成本机仓库的实际目录,例如:

UNITREE_ROS_DIR = "</home/your-name/repos/unitree_ros/unitree_ros>"
UNITREE_MODEL_DIR = "</home/your-name/repos/unitree_usd>"

unitree.py 文件中,可以选择不同任务模型的加载方式,例如:

UNITREE_G1_29DOF_CFG = UnitreeArticulationCfg(
    spawn=UnitreeUrdfFileCfg(
        asset_path=f"{UNITREE_ROS_DIR}/robots/g1_description/g1_29dof_rev_1_0.urdf",
    ),
    # spawn=UnitreeUsdFileCfg(
    #     usd_path=f"{UNITREE_MODEL_DIR}/G1/29dof/usd/g1_29dof_rev_1_0/g1_29dof_rev_1_0.usd",
    # ),

6. 先检查任务是否注册成功

安装和模型路径配置完后,先不要急着训练,建议先列任务,在 unitree_rl_lab 文件夹路径下执行:

./unitree_rl_lab.sh -l

正常情况下,应能在输出里看到多个 Unitree 机器人相关任务,其中本文关注的是:

Unitree-G1-29dof-Velocity

7. 运行 G1 官方训练案例

确认任务存在后,就可以直接启动训练,在 unitree_rl_lab 根目录下执行:

PYTHONPATH=$PWD/source/unitree_rl_lab python scripts/rsl_rl/train.py \
  --task Unitree-G1-29dof-Velocity \
  --headless

这里建议优先使用 headless 方式先跑通,因为它对图形界面要求更低,也更适合先检查训练链路是否正常。

训练成功时,终端将打印:

################################################################################
                         Learning iteration 3032/52300                           

                            Total steps: 72056832 
                       Steps per second: 85467 
                        Collection time: 1.083s 
                          Learning time: 0.067s 
                        Mean value loss: 0.0059
                    Mean surrogate loss: -0.0096
                      Mean entropy loss: 9.5192
                            Mean reward: 35.93
                    Mean episode length: 995.45
                        Mean action std: 0.35
        Episode_Reward/track_lin_vel_xy: 0.7915
         Episode_Reward/track_ang_vel_z: 0.2411
                   Episode_Reward/alive: 0.1496
    Episode_Reward/base_linear_velocity: -0.0144
   Episode_Reward/base_angular_velocity: -0.0342
               Episode_Reward/joint_vel: -0.1077
               Episode_Reward/joint_acc: -0.0405
             Episode_Reward/action_rate: -0.3637
          Episode_Reward/dof_pos_limits: -0.0013
                  Episode_Reward/energy: -0.0027
    Episode_Reward/joint_deviation_arms: -0.1064
  Episode_Reward/joint_deviation_waists: -0.0595
    Episode_Reward/joint_deviation_legs: -0.0833
     Episode_Reward/flat_orientation_l2: -0.0097
             Episode_Reward/base_height: -0.0004
                    Episode_Reward/gait: 0.5041
              Episode_Reward/feet_slide: -0.0308
          Episode_Reward/feet_clearance: 0.9713
      Episode_Reward/undesired_contacts: -0.0007
              Curriculum/terrain_levels: 0.0424
          Curriculum/lin_vel_cmd_levels: 0.4000
     Metrics/base_velocity/error_vel_xy: 0.4542
    Metrics/base_velocity/error_vel_yaw: 1.0218
           Episode_Termination/time_out: 0.9807
        Episode_Termination/base_height: 0.0000
    Episode_Termination/bad_orientation: 0.0193
--------------------------------------------------------------------------------
                         Iteration time: 1.15s
                           Time elapsed: 00:13:56
                                    ETA: 15:37:30

8. 日志与结果文件

训练完成后,相关输出一般会落在仓库根目录下的 logs/rsl_rl/ 目录中,按任务名和时间戳分类保存。

9. MuJoCo 仿真启动命令

启动 MuJoco 前需要将训练完成的 pt 文件转换为 onnx 文件,本文不再赘述;并将 onnx 文件与 deploy.yaml 文件分别放入指定文件夹

  • onnx 放入 unitree_rl_lab/deploy/robots/g1_29dof/config/policy/velocity/v0/exported
  • deploy.yaml 放入 unitree_rl_lab/deploy/robots/g1_29dof/config/policy/velocity/v0/params

9.1 unitree_mujoco 配置

当前实际使用的 MuJoCo 配置文件:unitree_mujoco/simulate/config.yaml

推荐配置:

robot: "g1"
robot_scene: "scene_29dof.xml"
domain_id: 0
interface: "lo"
use_joystick: 0
joystick_type: "xbox"
joystick_device: "/dev/input/js0"
joystick_bits: 16
print_scene_information: 1
enable_elastic_band: 1

说明:

  • robot 必须是 g1
  • robot_scene 建议用 scene_29dof.xml
  • 当前复现用的是键盘,不是手柄,所以 use_joystick: 0
  • 如何将手柄修改为键盘,本文不再说明

9.2 启动 MuJoCo

cd /home/your-name/repos/unitree_mujoco/simulate/build
./unitree_mujoco

9.3 启动控制器

另开一个终端:

cd /home/your-name/repos/unitree_rl_lab/deploy/robots/g1_29dof/build
./g1_ctrl --network lo

如果通信正常,g1_ctrl 终端应看到类似:

Connected to robot.
FSM: Start FixStand

9.4 启动后怎么操作

这是最容易混淆的部分,必须分清楚“哪个按键在哪个窗口生效”。

9.5 MuJoCo 窗口中的按键

这些键只在 MuJoCo 窗口获得焦点时有效:

  • 8 或方向下键 Down
    • 放长弹性带,让机器人往下落
  • 9
    • 开关弹性带

说明:

  • 8 不是一次性“直接落地”,而是每按一次增加弹性带长度
  • 如果机器人还没真正承重就按 9,它会直接摔下去

9.6 g1_ctrl 终端中的按键

这些键不是在 MuJoCo 窗口里按,而是在运行 ./g1_ctrl 的那个终端里按:

  • W 向前
  • S 向后
  • A 向左
  • D 向右
  • Q 左转
  • E 右转

10. 常见问题

10.1 任务列表里没有 Unitree-G1-29dof-Velocity

优先检查是不是没有激活 Isaac Lab 对应环境,或者 unitree_rl_lab 根本没有装进当前 Python 环境。

10.2 机器人模型加载失败

优先检查 UNITREE_ROS_DIRUNITREE_MODEL_DIR。这类问题大部分不是代码错,而是路径错。

10.3 第一轮启动特别慢

首次运行 Isaac Lab / Isaac Sim 相关任务时,着色器缓存、资源初始化和扩展加载都可能比较慢,先不要急着判断卡死。

11. 踩坑记录

11.1 训练入口目录错误

误以为需要在 source/.../__init__.py 所在目录运行训练命令,但这里实际上是环境注册位置,不是运行入口。

训练、回放和任务列表命令都应在 unitree_rl_lab 仓库根目录执行,也就是同时包含 unitree_rl_lab.shscripts/source/ 的目录:

cd unitree_rl_lab

11.2 -p 参数使用错误

如果执行:

./unitree_rl_lab.sh -p scripts/rsl_rl/train.py

结果会报类似错误:

play.py: error: unrecognized arguments

在官方仓库里,-p 用于 play 模式,不是给脚本传路径参数。训练脚本应直接使用 Python 调用:

python scripts/rsl_rl/train.py --headless --task Unitree-G1-29dof-Velocity

11.3 unitree_rl_lab 包未正确加载

如果直接运行脚本时报:

ModuleNotFoundError: No module named 'unitree_rl_lab'

这通常说明当前 Python 环境没有正确找到 unitree_rl_lab 包。

处理方式如下。优先执行可编辑安装:

pip install -e source/unitree_rl_lab

11.4 unitree_rl_lab.tasks 模块加载失败

如果继续报:

No module named 'unitree_rl_lab.tasks'

这通常不是包不存在,而是 PYTHONPATH 指到了错误层级。

处理方式如下。对于这个仓库,临时运行时更合理的写法是:

PYTHONPATH=$PWD/source/unitree_rl_lab python scripts/rsl_rl/train.py --headless --task Unitree-G1-29dof-Velocity

如果需要长期使用,仍然建议优先采用可编辑安装,而不是长期依赖手动设置 PYTHONPATH

11.5 UNITREE_MODEL_DIR 路径配置错误

配置 G1 资产路径时,如果把 UNITREE_MODEL_DIR 写成具体的 .usd 文件路径,就会出现路径拼接错误,报错信息通常类似:

...g1_29dof_rev_1_0.usd/G1/29dof/...

原因是代码内部还会基于 UNITREE_MODEL_DIR 继续拼接子路径,因此这里必须填写模型根目录,而不是单个文件路径。

11.6 USD 文件报错

11.6.1 接触传感器相关报错

加载自定义 USD 时,还可能遇到:

No contact sensors added to the prim

这个报错虽然出现在接触传感器相关逻辑中,但结合当前环境来看,更接近根因的是 unitree_rl_lab 训练脚本与 rsl-rl 5.0.1 之间存在版本和接口不匹配。处理方式是针对当前使用的 rsl-rl 5.0.1 做兼容。这里需要修改两处。

步骤一:train.py 中补充旧配置兼容转换。

路径:scripts/rsl_rl/train.py

也就是在 """Rest everything follows.""" 下方、AppLauncher 启动之后,改为:

app_launcher = AppLauncher(args_cli)
simulation_app = app_launcher.app

# 添加以下内容
from isaaclab_rl.rsl_rl import (
    RslRlOnPolicyRunnerCfg,
    RslRlVecEnvWrapper,
    handle_deprecated_rsl_rl_cfg,
)

然后在 main() 中下面这行之后:

agent_cfg = cli_args.update_rsl_rl_cfg(agent_cfg, args_cli)

# 添加以下内容
agent_cfg = handle_deprecated_rsl_rl_cfg(agent_cfg, installed_version)

步骤二:rsl_rl_ppo_cfg.py 中补充 obs_groups

路径:source/unitree_rl_lab/unitree_rl_lab/tasks/locomotion/agents/rsl_rl_ppo_cfg.py

BasePPORunnerCfg 中加入以下一行:

obs_groups = {"actor": ["policy"], "critic": ["policy"]}

这一行放在 experiment_namepolicy 附近即可,例如:

@configclass
class BasePPORunnerCfg(RslRlOnPolicyRunnerCfg):
    num_steps_per_env = 24
    max_iterations = 50000
    save_interval = 100
    experiment_name = ""
    empirical_normalization = False
    obs_groups = {"actor": ["policy"], "critic": ["policy"]}
    policy = RslRlPpoActorCriticCfg(
        init_noise_std=1.0,
        actor_hidden_dims=[512, 256, 128],
    )
11.6.2 动作分布的标准差报错

问题描述:该问题仅出现在 5090 显卡训练 go1-velocity 任务中,四足狗机器人采用相同配置可正常训练。以下方案可尝试,但无法保证一定解决。

训练过程中,可能遇到标准差小于 0 导致报错。

RuntimeError: normal expects all elements of std >= 0.0
Set the environment variable HYDRA_FULL_ERROR=1 for a complete stack trace.

默认配置为 noise_std_type="scalar",迁移到 rsl_rl 5.0.1 后 PPO 训练过程中这个参数可能被梯度更新到 0 以下,一旦小于 0,torch.normal 就报 std >= 0.0。

路径:source/unitree_rl_lab/unitree_rl_lab/tasks/locomotion/agents/rsl_rl_ppo_cfg.py

BasePPORunnerCfg 中替换原有 policy

    policy = RslRlPpoActorCriticCfg(
      init_noise_std=1.0,
      noise_std_type="log",
      actor_obs_normalization=False,
      critic_obs_normalization=False,
      actor_hidden_dims=[512, 256, 128],
      critic_hidden_dims=[512, 256, 128],
      activation="elu",
      )

提示:若在训练过程中报错标准差小于 0,则更新 policy 后无法恢复训练,需从头开始;或将 checkpoint 转成新格式可接续训练。

12. 补充说明:任务启动、GPU 指定与断点续训

12.1 常规启动方式

如果只是正常启动 Unitree-G1-29dof-Velocity 任务,可以直接执行:

PYTHONPATH=$PWD/source/unitree_rl_lab python scripts/rsl_rl/train.py \
  --task Unitree-G1-29dof-Velocity
  --headless

如果本机图形界面可用,并且需要观察训练界面,可以不加 --headless

12.2 指定 GPU 运行

如果机器上有多张显卡,可以通过 CUDA_VISIBLE_DEVICES 指定当前进程实际使用的物理 GPU。例如:

CUDA_VISIBLE_DEVICES=0 PYTHONPATH=$PWD/source/unitree_rl_lab python scripts/rsl_rl/train.py \
  --task Unitree-Go2-Velocity \
  --headless \
  --device cuda:0 

CUDA_VISIBLE_DEVICES=1 PYTHONPATH=$PWD/source/unitree_rl_lab python scripts/rsl_rl/train.py \
  --task Unitree-G1-29dof-Velocity \
  --headless \
  --device cuda:0

这里需要注意:

  • CUDA_VISIBLE_DEVICES=1 表示把物理上的第 1 张 GPU 暴露给当前进程
  • --device cuda:0 不可修改,表示在当前进程可见设备列表中使用第 0 张设备

这类写法适合在多卡机器上手动指定训练任务运行在哪一张显卡上,但它本质上仍然是单进程、单卡训练,不是分布式多卡训练。

12.3 断点续训

如果训练中断,或者需要从已有权重继续训练,可以使用 --resume--load_run--checkpoint。例如:

CUDA_VISIBLE_DEVICES=1 PYTHONPATH=$PWD/source/unitree_rl_lab python scripts/rsl_rl/train.py \
  --task Unitree-G1-29dof-Velocity \
  --headless \
  --device cuda:0 \
  --resume \
  --load_run "2026-03-27_21-17-37" \
  --checkpoint "model_2300.pt"

这几个参数的作用分别是:

  • --resume:表示从已有训练结果继续训练
  • --load_run:指定要加载的运行目录
  • --checkpoint:指定要恢复的模型文件

通常可以在 logs/rsl_rl/<任务名>/<时间戳目录>/ 下找到对应的运行目录和模型文件。

12.4 其他任务的续训方式

同样的方式也适用于其他任务。例如继续训练 Unitree-Go2-Velocity

CUDA_VISIBLE_DEVICES=0 PYTHONPATH=$PWD/source/unitree_rl_lab python scripts/rsl_rl/train.py \
  --task Unitree-Go2-Velocity \
  --headless \
  --device cuda:0 \
  --resume \
  --load_run "2026-03-27_20-59-40" \
  --checkpoint "model_300.pt"

需要注意的是,--task--load_run--checkpoint 必须相互对应,不能混用不同任务下的训练结果。

参考资料: