跳到主要内容宇树 G1 人形机器人强化学习训练实战指南 | 极客日志PythonAI算法
宇树 G1 人形机器人强化学习训练实战指南
基于 Isaac Gym 与 RSL-RL 框架,本文详细阐述了宇树 G1 人形机器人的强化学习训练流程。涵盖 12 自由度基础环境搭建、23 自由度模型扩展配置、观测维度计算及 PD 控制参数调整。重点解析了模块化奖励函数架构,包括轨迹跟踪、稳定性约束及动作平滑性设计,揭示了_prepare_reward_function 动态注册机制与 compute_reward 执行逻辑,为高自由度机器人运动控制提供实战参考。
雪落无声0 浏览 前言
人形机器人的运动控制一直是领域内的核心挑战,而强化学习为此提供了强有力的解决方案。本教程将基于宇树 G1 人形机器人,从基础的强化学习环境搭建开始,逐步深入到高自由度模型的训练配置、奖励函数设计与优化,最终实现复杂动作的训练控制。我们将使用 Isaac Gym 物理仿真环境和 RSL-RL 强化学习框架作为基础工具。
强化学习训练环境配置
基础环境搭建
在开始训练之前,我们需要确保 Isaac Gym 和 RSL-RL 框架正确安装。通过简单的命令即可启动 12 自由度 G1 机器人的基础训练:
python legged_gym/scripts/train.py --task=g1
这个命令背后依赖于任务注册系统。在 legged_gym/envs/__init__.py 文件中,可以看到各种机器人任务的注册逻辑:
from legged_gym import LEGGED_GYM_ROOT_DIR, LEGGED_GYM_ENVS_DIR
from legged_gym.envs.go2.go2_config import GO2RoughCfg, GO2RoughCfgPPO
from legged_gym.envs.h1.h1_config import H1RoughCfg, H1RoughCfgPPO
from legged_gym.envs.h1.h1_env import H1Robot
from legged_gym.envs.h1_2.h1_2_config import H1_2RoughCfg, H1_2RoughCfgPPO
from legged_gym.envs.h1_2.h1_2_env import H1_2Robot
from legged_gym.envs.g1.g1_config import G1RoughCfg, G1RoughCfgPPO
from legged_gym.envs.g1.g1_env import G1Robot
from base.legged_robot import LeggedRobot
from legged_gym.utils.task_registry import task_registry
task_registry.register("go2", LeggedRobot, GO2RoughCfg(), GO2RoughCfgPPO())
task_registry.register("h1", H1Robot, H1RoughCfg(), H1RoughCfgPPO())
task_registry.register("h1_2", H1_2Robot, H1_2RoughCfg(), H1_2RoughCfgPPO())
task_registry.register("g1", G1Robot, G1RoughCfg(), G1RoughCfgPPO())
G1 机器人 12 自由度配置解析
标准的 G1 机器人配置文件位于 legged_gym/envs/g1/g1_config.py 中,这里定义了机器人的各项关键参数。让我们深入分析其中的核心配置:
from legged_gym.envs.base.legged_robot_config import LeggedRobotCfg, LeggedRobotCfgPPO
class G1RoughCfg(LeggedRobotCfg):
class init_state(LeggedRobotCfg.init_state):
pos = [0.0, 0.0, 0.8]
default_joint_angles = {
'left_hip_yaw_joint': 0.,
'left_hip_roll_joint': 0,
'left_hip_pitch_joint': -0.1,
'left_knee_joint': 0.3,
'left_ankle_pitch_joint': -0.2,
'left_ankle_roll_joint': 0,
'right_hip_yaw_joint': 0.,
'right_hip_roll_joint': 0,
'right_hip_pitch_joint': -0.1,
'right_knee_joint': 0.3,
'right_ankle_pitch_joint': -0.2,
'right_ankle_roll_joint': 0,
'torso_joint': 0
}
class env(LeggedRobotCfg.env):
num_observations = 47
num_privileged_obs = 50
num_actions = 12
pos: 机器人在仿真环境中的初始位置
default_joint_angles: 各关节的默认角度,对应机器人的自然站立姿态
num_observations: 观测空间维度,包含身体姿态、关节状态等信息
num_actions: 动作空间维度,对应可控制的关节数量
扩展到 23 自由度模型
高自由度模型的挑战
当我们将 G1 机器人从 12 自由度扩展到 23 自由度时,增加的 11 个自由度主要分布在上肢:
- 腰部:3 个自由度(yaw, pitch, roll)
- 左右肩部:各 3 个自由度(pitch, roll, yaw)
- 左右肘部:各 1 个自由度(pitch)
- 左右手腕:各 1 个自由度(roll)
这种扩展带来了显著的复杂性增加,不仅仅是参数数量的增长,更重要的是动作空间的指数级扩展和训练难度的显著提升。
创建 23 自由度配置
为了不破坏现有的 G1 训练任务,我们在 legged_gym/envs/g1/ 目录下创建新的配置文件 g1_config_23.py:
from legged_gym.envs.base.legged_robot_config import LeggedRobotCfg, LeggedRobotCfgPPO
class G1_23RoughCfg(LeggedRobotCfg):
class init_state(LeggedRobotCfg.init_state):
pos = [0.0, 0.0, 0.8]
default_joint_angles = {
'left_hip_yaw_joint': 0.,
'left_hip_roll_joint': 0,
'left_hip_pitch_joint': -0.1,
'left_knee_joint': 0.3,
'left_ankle_pitch_joint': -0.2,
'left_ankle_roll_joint': 0,
'right_hip_yaw_joint': 0.,
'right_hip_roll_joint': 0,
'right_hip_pitch_joint': -0.1,
'right_knee_joint': 0.3,
'right_ankle_pitch_joint': -0.2,
'right_ankle_roll_joint': 0,
'waist_yaw_joint': 0,
'left_shoulder_pitch_joint': 0.,
'left_shoulder_roll_joint': 0,
'left_shoulder_yaw_joint': 0.,
'left_elbow_joint': 0.,
'left_wrist_roll_joint': 0.,
'right_shoulder_pitch_joint': 0.,
'right_shoulder_roll_joint': 0.0,
'right_shoulder_yaw_joint': 0.,
'right_elbow_joint': 0.,
'right_wrist_roll_joint': 0.
}
观测维度的重新计算
观测维度的计算是强化学习配置中的关键环节。对于足式机器人,标准的观测包括:
- 基座角速度:3 维
- 重力投影:3 维
- 运动命令:3 维
- 关节位置偏差:关节数量维(23 维)
- 关节速度:关节数量维(23 维)
- 上一步动作:关节数量维(23 维)
- 相位信息:2 维(sin 和 cos)
因此,23 自由度 G1 机器人的观测维度为:3 + 3 + 3 + 23×3 + 2 = 80 维。通过查看 /unitree_rl_gym/legged_gym/envs/g1/g1_env.py 中的 privileged_obs_buf 和 obs_buf,我们发现多了 base_lin_vel(线速度)(3 维)。
class env(LeggedRobotCfg.env):
num_observations = 80
num_privileged_obs = 83
num_actions = 23
控制参数配置
针对新增的关节,需要配置相应的 PD 控制参数。不同类型的关节需要不同的刚度和阻尼设置:
class control(LeggedRobotCfg.control):
control_type = 'P'
stiffness = {
'hip_yaw': 100,
'hip_roll': 100,
'hip_pitch': 100,
'knee': 150,
'ankle': 40,
'waist_yaw': 250,
'shoulder': 100,
'elbow': 50,
'wrist': 50
}
damping = {
'hip_yaw': 2,
'hip_roll': 2,
'hip_pitch': 2,
'knee': 4,
'ankle': 2,
'waist_yaw': 6,
'shoulder': 2,
'elbow': 2,
'wrist': 2,
}
action_scale = 0.25
decimation = 4
资源文件更新
class asset(LeggedRobotCfg.asset):
file = '{LEGGED_GYM_ROOT_DIR}/resources/robots/g1_description/g1_23dof_rev_1_0.urdf'
name = "g1"
foot_name = "ankle_roll"
penalize_contacts_on = ["hip", "knee"]
terminate_after_contacts_on = ["pelvis"]
self_collisions = 0
flip_visual_attachments = False
完成配置后,在 __init__.py 中注册新任务:
from legged_gym.envs.g1.g1_config_23 import G1_23RoughCfg, G1_23RoughCfgPPO
task_registry.register("g1_23", G1Robot, G1_23RoughCfg(), G1_23RoughCfgPPO())
python legged_gym/scripts/train.py --task=g1_23
奖励函数架构深度解析
奖励函数的核心作用
在强化学习中,奖励函数是算法学习的唯一指导信号。对于足式机器人,一个良好的奖励函数设计需要平衡多个目标:稳定性、任务完成度、能耗效率、动作自然性等。
宇树的强化学习框架采用了模块化的奖励函数设计,每个奖励组件专注于机器人行为的特定方面。这种设计使得我们可以精细调节每个行为特征的重要性。
G1 机器人奖励函数配置详解
在 G1 机器人的配置类 G1RoughCfg(LeggedRobotCfg) 中,奖励函数的配置采用继承和重写的方式:
class G1RoughCfg(LeggedRobotCfg):
class rewards(LeggedRobotCfg.rewards):
soft_dof_pos_limit = 0.9
base_height_target = 0.78
class scales(LeggedRobotCfg.rewards.scales):
tracking_lin_vel = 1.0
tracking_ang_vel = 0.5
lin_vel_z = -2.0
ang_vel_xy = -0.05
orientation = -1.0
base_height = -10.0
dof_acc = -2.5e-7
dof_vel = -1e-3
action_rate = -0.01
feet_air_time = 0.0
contact = 0.18
contact_no_vel = -0.2
feet_swing_height = -20.0
collision = 0.0
dof_pos_limits = -5.0
alive = 0.15
hip_pos = -1.0
soft_dof_pos_limit = 0.9: 设置为 URDF 限制的 90%,当关节接近极限位置时开始惩罚,保护机械结构
base_height_target = 0.78: G1 机器人的理想身体高度(米),用于维持稳定的站立姿态
class LeggedRobotCfg:
class rewards:
class scales:
termination = -0.0
torques = -0.00001
feet_stumble = -0.0
stand_still = -0.
only_positive_rewards = True
tracking_sigma = 0.25
soft_dof_vel_limit = 1.
soft_torque_limit = 1.
max_contact_force = 100.
奖励函数的初始化机制
在 LeggedRobot 类的初始化过程中,_prepare_reward_function() 方法负责构建奖励函数列表:
def _prepare_reward_function(self):
"""准备奖励函数列表,查找所有非零权重的奖励函数"""
for key in list(self.reward_scales.keys()):
scale = self.reward_scales[key]
if scale == 0:
self.reward_scales.pop(key)
else:
self.reward_scales[key] *= self.dt
self.reward_functions = []
self.reward_names = []
for name, scale in self.reward_scales.items():
if name == "termination":
continue
self.reward_names.append(name)
function_name = '_reward_' + name
self.reward_functions.append(getattr(self, function_name))
self.episode_sums = {
name: torch.zeros(self.num_envs, dtype=torch.float, device=self.device, requires_grad=False)
for name in self.reward_scales.keys()
}
这个机制的巧妙之处在于动态函数查找:通过 getattr(self, '_reward_' + name) 自动找到对应的奖励函数,这意味着我们只需要定义函数并在配置中设置权重,系统就会自动将其纳入训练过程。
奖励计算的执行机制
每个仿真步骤都会调用 compute_reward() 方法来计算总奖励:
def compute_reward(self):
"""计算总奖励,调用所有非零权重的奖励函数"""
self.rew_buf[:] = 0.
for i in range(len(self.reward_functions)):
name = self.reward_names[i]
rew = self.reward_functions[i]() * self.reward_scales[name]
self.rew_buf += rew
self.episode_sums[name] += rew
if self.cfg.rewards.only_positive_rewards:
self.rew_buf[:] = torch.clip(self.rew_buf[:], min=0.)
if "termination" in self.reward_scales:
rew = self._reward_termination() * self.reward_scales["termination"]
self.rew_buf += rew
self.episode_sums["termination"] += rew
核心奖励函数解析
def _reward_tracking_lin_vel(self):
"""线速度跟踪奖励 - 鼓励机器人按指令移动"""
lin_vel_error = torch.sum(torch.square(
self.commands[:, :2] - self.base_lin_vel[:, :2]), dim=1)
return torch.exp(-lin_vel_error / self.cfg.rewards.tracking_sigma)
def _reward_tracking_ang_vel(self):
"""角速度跟踪奖励 - 鼓励机器人按指令转向"""
ang_vel_error = torch.square(
self.commands[:, 2] - self.base_ang_vel[:, 2])
return torch.exp(-ang_vel_error / self.cfg.rewards.tracking_sigma)
这两个函数使用指数衰减的奖励机制:误差越小,奖励越接近 1;误差增大,奖励快速衰减至 0。
def _reward_orientation(self):
"""姿态稳定性奖励 - 惩罚身体倾斜"""
return torch.sum(torch.square(self.projected_gravity[:, :2]), dim=1)
def _reward_base_height(self):
"""高度控制奖励 - 保持目标高度"""
base_height = self.root_states[:, 2]
return torch.square(base_height - self.cfg.rewards.base_height_target)
def _reward_action_rate(self):
"""动作变化率惩罚 - 鼓励平滑控制"""
return torch.sum(torch.square(self.last_actions - self.actions), dim=1)
def _reward_dof_acc(self):
"""关节加速度惩罚 - 避免剧烈动作"""
return torch.sum(torch.square((self.last_dof_vel - self.dof_vel) / self.dt), dim=1)
相关免费在线工具
- 加密/解密文本
使用加密算法(如AES、TripleDES、Rabbit或RC4)加密和解密文本明文。 在线工具,加密/解密文本在线工具,online
- RSA密钥对生成器
生成新的随机RSA私钥和公钥pem证书。 在线工具,RSA密钥对生成器在线工具,online
- Mermaid 预览与可视化编辑
基于 Mermaid.js 实时预览流程图、时序图等图表,支持源码编辑与即时渲染。 在线工具,Mermaid 预览与可视化编辑在线工具,online
- 随机西班牙地址生成器
随机生成西班牙地址(支持马德里、加泰罗尼亚、安达卢西亚、瓦伦西亚筛选),支持数量快捷选择、显示全部与下载。 在线工具,随机西班牙地址生成器在线工具,online
- Gemini 图片去水印
基于开源反向 Alpha 混合算法去除 Gemini/Nano Banana 图片水印,支持批量处理与下载。 在线工具,Gemini 图片去水印在线工具,online
- curl 转代码
解析常见 curl 参数并生成 fetch、axios、PHP curl 或 Python requests 示例代码。 在线工具,curl 转代码在线工具,online