本文主要想把这次双足机器人强化学习训练里的 sim-to-real 过程尽量完整地复盘出来,里面会涉及奖励设计、域随机化策略,以及最后真实部署时的一些实现细节。

这次 sim-to-real 能跑通,最核心的原因还是域随机化做对了。整个过程中,我们并没有去构建足端接触力模型,也没有使用 actuator network、teacher-student 这类方法,真正起主要作用的还是域随机化本身。这里面哪些随机化是关键、具体怎么起作用的,后面都会详细展开。

如果只从工程实用性的角度来看,域随机化其实是个很好用的方法。很多场景下,不靠特别复杂的建模,只靠比较扎实的随机化设计,也能把问题解决掉。但它的问题也很明显:这种方法本质上是在拿最优性换鲁棒性。换句话说,它未必是在逼近全局最优解,而更像是在更大的不确定性里,去找一个能稳定收敛、也足够可靠的局部解。

所以,域随机化虽然有效,但也不能把它理解成万能方案。尤其当机器人面临更大的负载扰动,或者系统模型误差已经大到一定程度时,单纯依赖域随机化,可能就找不到可行解了。从这个角度看,系统辨识仍然是不能轻易放弃的一条路。

不过,不管怎么说,这次 sim-to-real 最终做成了,还是一次很宝贵的经验。它既来自很多次在黑暗里的摸索试错,也确实证明了域随机化在实际工程里的有效性。接下来就把整个过程详细复盘一下。

一、机器人基本配置

1.1 关节结构与默认姿态

X2 腿部共 12 个自由度,左右完全对称,每侧 6 个关节:

1
2
3
4
5
6
7
骨盆 (pelvis)
├── 左髋 hip_pitch / hip_roll / hip_yaw
│ └── 左膝 knee
│ └── 左踝 ankle_pitch / ankle_roll
└── 右髋 hip_pitch / hip_roll / hip_yaw
└── 右膝 knee
└── 右踝 ankle_pitch / ankle_roll

默认站立角度(action=0 时的目标角):

关节名称 角度(rad) 说明
hip_pitch (L/R) -0.2480 髋关节微屈(往前倾约 14°)
hip_roll (L/R) 0.0000 髋关节无侧倾
hip_yaw (L/R) 0.0000 髋关节无内外旋
knee (L/R) 0.5303 膝关节弯曲约 30°
ankle_pitch (L/R) -0.2823 踝关节背屈(往上翘约 16°)
ankle_roll (L/R) 0.0000 踝关节无侧倾

初始骨盆高度为 0.67 m。这套默认姿态是一个”微蹲”站立姿,髋屈 + 膝屈 + 踝背屈的组合使得重心稳定,同时给膝关节留出向下压缩的缓冲空间,是双足机器人训练的标准初始化策略。

关节在代码中的顺序(索引 0~11):

1
2
3
4
0: left_hip_pitch    1: left_hip_roll    2: left_hip_yaw
3: left_knee 4: left_ankle_pitch 5: left_ankle_roll
6: right_hip_pitch 7: right_hip_roll 8: right_hip_yaw
9: right_knee 10: right_ankle_pitch 11: right_ankle_roll

这个顺序在后续奖励函数中会频繁用到。

1.2 PD 控制器

控制模式为 control_type = 'P',即标准位置-速度(PD)控制器。策略网络每步输出 12 维动作 ,经缩放后得到目标关节角度:

PD 增益设置:

关节组 Kp(N·m/rad) Kd(N·m·s/rad) 设计依据
hip_pitch 120 5.0 对应 URDF 额定扭矩 120 Nm
hip_roll 120 5.0 同上
hip_yaw 120 5.0 同上
knee 150 5.0 膝关节承载更大,刚度更高
ankle_pitch 40 3.0 踝关节扭矩小(36 Nm 级别)
ankle_roll 30 2.0 踝侧倾刚度最小

关键参数:

  • action_scale = 0.2:动作缩放系数。策略输出范围通常在 [-1, 1],乘以 0.2 后最大关节偏移为 ±0.2 rad(约 ±11.5°)。这个限制防止训练初期策略输出大动作导致机器人剧烈抖动。
  • decimation = 10:控制频率降采样。例如控制仿真频率为 500 Hz,则策略运行频率为 50 Hz。每个策略步内,PD 控制器以 500 Hz 运行,策略目标角度保持不变。

1.3 安全限制

1
2
3
4
class safety:
pos_limit = 1.0 # 关节位置软限制系数(1.0 = 使用 URDF 全范围)
vel_limit = 1.0 # 关节速度软限制系数
torque_limit = 0.85 # 扭矩上限系数(只用额定扭矩的 85%)

实际扭矩上限为额定值的 85%,留出 15% 的安全余量,防止真实电机长时间满负荷运行会造成损坏。

1.4 地形配置

1
2
3
4
5
class terrain:
mesh_type = 'plane' # 当前使用平面地形
static_friction = 0.6
dynamic_friction = 0.6
restitution = 0. # 无弹性(接触不反弹)

当前训练阶段使用平面地形(mesh_type = 'plane'),代码中已预留 trimesh 粗糙地形的支持(注释掉),后续可以开启。地形摩擦系数 0.6 是正常地板的中等摩擦值,但域随机化会在此基础上大幅扰动(见第五章)。


二、观测空间(Observation Space)

2.1 单帧观测向量(47 维)

每个时间步,环境计算一个 47 维的原始观测向量 current_obs,构成如下:

1
2
3
4
5
6
7
8
9
10
current_obs = torch.cat((
self.base_ang_vel * self.obs_scales.ang_vel, # [0:3] 3 维
self.projected_gravity, # [3:6] 3 维
self.commands[:, :3] * self.commands_scale, # [6:9] 3 维
(self.dof_pos - self.default_dof_pos) * self.obs_scales.dof_pos, # [9:21] 12 维
self.dof_vel * self.obs_scales.dof_vel, # [21:33] 12 维
self.actions, # [33:45] 12 维
sin_phase, # [45] 1 维
cos_phase, # [46] 1 维
), dim=-1)

逐项说明:

[0:3] 机体角速度(Body Angular Velocity)

  • 坐标系:机体坐标系(body frame)下的三轴角速度
  • 归一化:乘以 obs_scales.ang_vel
  • 物理意义:反映机体当前的翻滚/俯仰/偏航角速度,是平衡控制的核心反馈
  • 噪声尺度:0.5(相对较大,模拟 IMU 陀螺仪的测量噪声)

[3:6] 投影重力向量(Projected Gravity)

  • 世界坐标系的重力向量 经机体姿态四元数旋转到机体坐标系后的结果
  • 机体完全竖直时值为 ,XY 分量为 0
  • 物理意义:编码了机体的倾斜方向和程度,是姿态估计的简洁表达——不需要显式欧拉角
  • 噪声尺度:0.5(模拟 IMU 加速度计的倾斜估计误差)

[6:9] 速度指令(Commands)

  • 内容:,即前向速度、侧向速度、偏航角速度指令
  • 归一化:乘以 commands_scale
  • 噪声尺度:0(指令信号不加噪声,策略需要精确知道目标)
  • 当前配置:,仅前向速度有效

[9:21] 关节位置偏差(DOF Position Error)

  • 内容:当前关节角度减去默认角度 ,12 维
  • 归一化:乘以 obs_scales.dof_pos
  • 物理意义:策略看到的是”偏离站立姿态多少”,而非绝对角度,这样表示与默认姿态无关,泛化性更好
  • 噪声尺度:0.05(关节编码器精度高,噪声小)

[21:33] 关节速度(DOF Velocity)

  • 内容:12 个关节的当前角速度
  • 归一化:乘以 obs_scales.dof_vel
  • 噪声尺度:0.5(关节速度通过微分估计,噪声较大)

[33:45] 上一步动作(Previous Actions)

  • 内容:上一时间步策略输出的 12 维动作向量(未经 action_scale 缩放的原始输出)
  • 噪声尺度:0(动作是策略自身的输出,不需要加噪)
  • 作用:让策略感知自身的历史动作,有助于生成连贯平滑的动作序列

[45:47] 步态相位信号(Gait Phase)

这是整个观测设计中很值得展开详细说明的部分。

1
2
sin_phase = torch.sin(2 * np.pi * self.phase).unsqueeze(1)
cos_phase = torch.cos(2 * np.pi * self.phase).unsqueeze(1)

什么是 gait phase

首先要明确一点:这里的 gait phase 并不是某个传感器直接测出来的”真实腿部相位”,它更像是一个人为构造出来的节律参考信号,或者说是一个步态时钟

双足行走本身是一个很强的周期运动。如果完全不给策略任何相位信息,策略就需要从关节状态、机身姿态、接触信息以及历史观测中隐式推断”当前处在步态周期的哪个阶段”。这件事理论上可以做到,但在强化学习里会明显增加训练难度,尤其是在训练初期随机化较强的时候,策略很容易学成纯反应式控制,而不容易形成清晰、稳定、对称的周期步态。

因此显式给一个 gait phase,本质上是在告诉策略:当前大致处在步态周期的哪一段。它更像一个节拍器,而不是一个真实测量量。

为什么 phase 用 0~1 表示

步态相位本质上是一个周期变量,可以写成 ,也可以写成归一化形式 ,关系为

代码中用归一化写法,因为它更直观地表达”当前周期进行了百分之多少”:

其中 是当前步态周期。这个式子含义清楚:当前时间 在一个周期 里走到了百分之多少,因此 天然落在 内。这只是把角度归一化了,与角度表示本质等价。

为什么不直接把 phase 输入网络,而要转成 sin/cos

虽然 很方便,但它不能被简单地当成普通实数变量,因为它本质上是一个周期变量

例如 从步态意义上非常接近(都在周期起点附近),但如果直接当成普通数输入网络,数值上却差了将近 1,网络会误以为这两个状态差别很大。

因此常见的做法是把相位映射到单位圆上:

这样周期首尾自然连接,表示连续,更适合网络学习。可以把 phase 想成”圆上的位置”,而不是”线段上的一个数”。直接输入 phase,等于硬把一个圆周变量摊成一条线;输入 sin/cos,则是把它作为圆周变量本来的样子保留下来。

为什么要同时用 sin 和 cos,而不是只用一个

只用一个三角函数会有歧义,例如只用 sin 时:

的 sin 值相同,但对应的步态阶段并不相同。只用 cos 也有类似问题。

同时使用 sin 和 cos,相位在一个周期内对应单位圆上唯一一个点,同时解决了两个问题:

  1. 消除了周期首尾不连续的问题
  2. 避免了单个三角函数的相位歧义

可以理解为:单独一个值只能告诉网络圆上的某个投影,sin 和 cos 两个值一起才能唯一确定当前在圆上的哪个位置。

2.2 步态相位的计算(自适应周期)

步态相位在 _post_physics_step_callback 中每步更新:

1
2
3
4
cmd_xy = torch.norm(self.commands[:, :2], dim=1)
period = 0.52 + 0.55 * torch.exp(-cmd_xy / 0.18)
t = self.episode_length_buf.float() * self.dt
self.phase = torch.remainder(t, period) / period

为什么步态周期要随速度自适应

walking 的节律本来就和速度密切相关。慢走时步频低、周期长,快走时步频高、周期短。如果无论什么速度都用同一个固定周期,节律和动作就会错位。

例如低速时若 phase 时钟转得很快,策略会被迫更快地切换左右腿角色,结果可能是还没完成稳定支撑就提前换腿,接触奖励与实际接触时机错位,出现碎步、抖动、多余摆腿等问题。反过来高速时若时钟太慢,则摆腿不及时、支撑切换滞后。

所以 gait phase 虽然是人为构造的参考信号,但它不能和机器人当前的运动意图脱节——让周期随着指令速度变化,本质上就是让这个步态时钟匹配当前运动节律。

周期公式解析

这三个常数各司其职:

  • 0.52(高速极限,步态周期下限):当速度很大时,指数项趋近于 0,因此 s。无论速度再快,步态周期都不会短于 0.52 秒。
  • 0.55(周期变化幅度):当速度为 0 时, s。这个 0.55 决定了从慢走节律到快走节律之间的周期跨度(1.07 s → 0.52 s)。
  • 0.18(速度尺度参数):控制指数衰减的快慢,决定步态周期主要在哪个速度区间发生明显过渡。

这三个参数不是从理论公式推导出来的,而是根据仿真效果和真机表现反复调出来的经验参数,但各自的作用是明确的。

为什么用指数函数而不是线性函数? 真实 walking 在低速到中速区间步态节律变化明显,在高速区间步频趋于饱和,不可能无限增加。指数函数在低速区间变化敏感,在高速区间平滑饱和,比线性映射更符合实际控制需求。

指令速度 步态周期
0 m/s(静止) s
0.18 m/s s
0.5 m/s s
高速极限 s(下限)

左右腿相位的关系:

1
2
3
self.phase_left  = self.phase
self.phase_right = (self.phase + 0.5) % 1.0
self.leg_phase = torch.cat([phase_left.unsqueeze(1), phase_right.unsqueeze(1)], dim=-1)

为什么左右腿固定相差 0.5

+0.5 意味着右腿相位相对左腿始终偏移半个周期,对应 180°。

从数学上看,半周期偏移天然让许多周期量变成反相关系。对于正弦函数有:

这和双足 walking 中左右腿交替承担摆动与支撑角色的关系是完全一致的。

这个设计并不是在精确描述机器人腿部真实相位,而是在给策略显式注入一个最基本的交替步态先验

  1. 大幅降低学习难度:如果不提供这个先验,策略需要同时学习”怎样走”和”左右腿该如何配合”,搜索空间明显更大,训练中更容易出现左右不同步、碎步、双脚同时做出不合理动作的情况。
  2. 诱导稳定对称步态:交替步态本来就是平地 walking 最自然、最稳妥的解,把这个结构直接体现在 phase 设计里是典型的工程做法。
  3. 让奖励信号更有效:很多奖励项隐含了”谁该支撑、谁该摆动”的时序逻辑,有了左右腿半周期错开的参考,奖励信号的意义会更明确。

当然,策略仍然需要结合当前姿态、速度、关节状态、接触反馈等观测来决定实际的关节动作,phase 只提供节律框架,而不是固定轨迹。

这套设计的本质

把以上细节放在一起,gait phase 做了以下几件事:

设计选择 解决的问题
归一化 直观表达周期进度
sin/cos 双值编码 保留周期连续性,消除相位歧义
左右腿相差 0.5 显式注入交替步态先验,降低搜索难度
周期随速度自适应 让步态时钟与当前运动节律匹配

目标并不是让 gait phase 完美描述真实步态,而是降低强化学习在双足 walking 上的搜索难度,让策略更容易收敛到稳定、可用、能落地的步态解。

2.3 帧堆叠(Frame Stack,15帧)

1
2
frame_stack = 15
num_observations = 47 * frame_stack # = 705

系统维护一个观测历史缓冲区:

1
2
3
4
self.obs_history = torch.zeros(
self.num_envs, self.frame_stack, self.single_obs_dim, # (N, 15, 47)
dtype=torch.float, device=self.device
)

每步更新:

1
2
3
self.obs_history = torch.roll(self.obs_history, shifts=-1, dims=1)  # 旧帧向前移
self.obs_history[:, -1, :] = current_obs # 最新帧填入末尾
self.obs_buf = self.obs_history.reshape(self.num_envs, -1) # 展平为 705 维

帧堆叠的作用:

策略网络(MLP)本身没有记忆,输入 705 维观测相当于把过去 15 步的完整状态都给它看。这样网络可以:

  • 估计关节加速度(从多帧速度差分)
  • 感知步态节律(从历史相位和接触状态)
  • 检测速度趋势(判断是在加速还是减速)
  • 识别外部扰动(突然的姿态变化)

以 50 Hz 控制频率计算,15 帧 = 0.3 秒的历史窗口,足以覆盖大约半个步态周期。

噪声在帧堆叠中的处理:

噪声在写入历史缓冲区之后叠加,意味着缓冲区中存储的是带噪声的历史:

1
2
3
4
5
6
7
# 先写入干净观测
self.obs_history[:, -1, :] = current_obs
# 再加噪声(直接修改缓冲区最新帧)
noise = (2 * rand - 1) * self.single_noise_scale_vec
self.obs_history[:, -1, :] += noise
# 从带噪声的缓冲区读取
self.obs_buf = self.obs_history.reshape(...)

每帧噪声独立采样,多帧间无相关性,这比”只对最新帧加噪声”更符合真实传感器特性。

2.4 特权观测(Privileged Observations,50 维)

Critic 网络在训练时使用特权观测,不做帧堆叠:

1
2
3
4
5
6
7
8
9
10
11
self.privileged_obs_buf = torch.cat((
self.base_lin_vel * self.obs_scales.lin_vel, # 新增:真实线速度 3 维
self.base_ang_vel * self.obs_scales.ang_vel, # 3 维
self.projected_gravity, # 3 维
self.commands[:, :3] * self.commands_scale, # 3 维
(self.dof_pos - self.default_dof_pos) * self.obs_scales.dof_pos, # 12 维
self.dof_vel * self.obs_scales.dof_vel, # 12 维
self.actions, # 12 维
sin_phase, # 1 维
cos_phase, # 1 维
), dim=-1) # 总计 50 维

与 Actor 观测的唯一区别:加入了真实线速度 base_lin_vel(3 维)。在真实机器人上,线速度需要通过 IMU 积分或外部定位系统估计,误差较大;在仿真中 Critic 可以直接读取真值,帮助它更准确地评估状态价值。

这是 Asymmetric Actor-Critic 框架的标准做法:Critic 利用仿真特权信息提供更准确的价值估计,从而给 Actor 提供更好的梯度信号;Actor 本身只用可部署的真实观测,保证 Sim-to-Real 迁移。


三、奖励函数(Reward Functions)

系统共设计 16 项奖励/惩罚,分 5 大类。总奖励为各项加权求和:

下面逐一解析每一项的数学表达、代码实现和设计意图。


3.1 速度跟踪类

tracking_lin_vel(权重 +1.0

作用: 鼓励机器人以指令速度行走,是整个训练的主要驱动力。

计算: 高斯核函数形式

其中 tracking_sigma)。实际速度与指令完全一致时 ,偏差越大越趋近于 0。

关键设计: 远小于常见设置(如 0.25)。这意味着即使速度只差 0.08 m/s,奖励就降至约 0.37。这迫使策略在低速(0.1 m/s)指令下也必须精确跟踪,不能通过”轻微偏差”换取其他奖励。 这正是防止策略在 0.1 m/s 指令时退化成站立的关键。


tracking_ang_vel(权重 +0.8

作用: 跟踪偏航角速度指令(转向)。

计算:tracking_lin_vel 相同的高斯核,但作用于偏航角速度误差。

当前状态: 训练配置中 ang_vel_yaw = [0, 0],即始终为 0 指令,此奖励主要保证策略在扩展到转向任务时能直接迁移,当前阶段实际贡献有限。


lin_vel_z(权重 -2.0

作用: 惩罚骨盆的垂直速度,抑制弹跳。

骨盆上下跳动会导致步态不稳定、能量浪费。此惩罚直接作用于速度平方,对大幅弹跳惩罚更重(二次关系)。


ang_vel_xy(权重 -0.16

作用: 惩罚机体绕 X 轴(侧倾)和 Y 轴(俯仰)的角速度晃动。

权重较小(-0.16),因为行走时骨盆的少量俯仰摆动是正常的,过强惩罚会限制步态自然度。


3.2 姿态稳定类

orientation(权重 -1.0

作用: 惩罚机体倾斜,维持躯干竖立。

projected_gravity 的 XY 分量反映了机体的倾斜程度。完全竖立时 XY 分量为 0,惩罚为 0;机体前倾/侧倾时 XY 分量增大,惩罚增加。


base_height(权重 -3.0

作用: 强制骨盆维持在目标高度 0.62 m 附近,是所有姿态类惩罚中权重最大的。

为什么目标高度是 0.62 而非初始化高度 0.67?

  • 0.67 m 是静止站立高度
  • 行走时重心会因步态周期性下沉,合理行走高度约 0.62 m
  • 如果目标设为 0.67,策略会因为行走时自然下沉而持续受惩,导致学会”踮脚走”等异常步态

权重 -3.0 是整个奖励体系中绝对值最大的惩罚之一,说明维持骨盆高度是硬性约束。


3.3 关节控制类

dof_acc(权重 -2.5e-7

作用: 惩罚关节加速度,使动作平顺。

权重极小(-2.5e-7)是因为关节加速度数值通常很大(量级在 rad/s² 以上),小权重配合大数值保证这一项对总奖励的贡献在合理范围内。减小关节加速度的物理含义是减少机械冲击,延长电机寿命。


dof_vel(权重 -1e-3

作用: 惩罚关节速度幅度,鼓励低速运动。

dof_acc 配合,共同约束关节运动的”激烈程度”。


dof_pos_limits(权重 -5.0

作用: 惩罚关节超出软限制(URDF 硬限制的 90%)。

1
soft_dof_pos_limit = 0.9  # 软限制 = 硬限制 × 0.9

当关节角度超过软限制时,惩罚等于超出量的平方。这比直接硬限位(关节卡死)更平滑,给策略一个”靠近边界就有惩罚”的梯度信号,防止关节打到物理极限。


hip_pos(权重 -0.5

作用: 专门惩罚髋关节侧倾(hip_roll)和偏航(hip_yaw)偏离零位。

1
2
# 关节索引: hip_roll_L(1), hip_yaw_L(2), hip_roll_R(7), hip_yaw_R(8)
r = -sum(dof_pos[[1,2,7,8]]²)

设计意图: 直行时不需要髋关节侧倾或内外旋,这两个方向的偏离通常意味着:

  • 外八/内八姿态(影响行走效率)
  • 代偿性动作(策略用髋部扭转来补偿其他失衡)

ankle_pos 相比权重更小(-0.5 vs -1.0),因为髋关节运动自由度更大,少量侧倾是可以接受的。


ankle_pos(权重 -1.0

作用: 惩罚踝关节(pitch + roll,共 4 个)偏离默认位置。

1
2
3
# 踝关节索引: ankle_pitch_L(4), ankle_roll_L(5), ankle_pitch_R(10), ankle_roll_R(11)
ankle_deviation = dof_pos[:, [4,5,10,11]] - default_dof_pos[:, [4,5,10,11]]
r = -sum(ankle_deviation²)

踝关节是离地面最近的关节,直接影响接地质量和平衡控制。踝关节偏离默认值往往意味着接触不稳定。权重 -1.0 比 hip_pos 更严格。


action_rate(权重 -0.01

作用: 惩罚相邻步动作变化率,产生平滑动作序列。

这与 dof_acc 的区别:

  • action_rate 惩罚策略输出的变化(网络层面的平滑性)
  • dof_acc 惩罚实际关节加速度(物理层面的平滑性)
  • 两者互补:策略可能输出平滑动作但因 PD 控制响应导致关节抖动,也可能动作跳变但关节因阻尼而平滑

3.4 步态与足端接触类

这一类是整个奖励体系的核心和难点,直接塑造步态行为。

feet_air_time(权重 +5.0

作用: 鼓励足端有足够的腾空时间,是权重最大的正向步态奖励。

代码逻辑(完整版):

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
def _reward_feet_air_time(self):
contact = self.contact_forces[:, self.feet_indices, 2] > 1.0
contact_filt = torch.logical_or(contact, self.last_contacts) # 防止单步抖动
self.last_contacts = contact
first_contact = (self.feet_air_time > 0.0) * contact_filt # 刚落地的脚

self.feet_air_time += self.dt # 腾空计时器累加
rew_air_time = torch.sum(
(self.feet_air_time - 0.38) * first_contact, dim=1
)
# 速度门控:低速时缩减但不清零
cmd_xy = torch.norm(self.commands[:, :2], dim=1)
scale = torch.where(
cmd_xy < 1e-5,
torch.zeros_like(cmd_xy),
torch.clamp(cmd_xy / 0.12, 0.52, 1.0),
)
rew_air_time *= scale
self.feet_air_time *= ~contact_filt # 落地后重置计时器
return rew_air_time

详细解析:

  1. 奖励时机:只在落地瞬间first_contact)计算奖励,不是每步都给。这确保了奖励与完整腾空过程对应,而不是鼓励频繁短暂腾空。

  2. 偏置 0.38 s:腾空时间超过 0.38 s 得正奖励,低于 0.38 s 得负奖励(惩罚”踏步”)。基类使用 0.5 s,这里改为 0.38 s,让步幅较短的训练早期也能获得正信号。

  3. 速度门控(关键设计)

    • cmd_xy < 1e-5(静止):scale = 0,不奖励腾空(避免原地抬腿)
    • cmd_xy = 0.1 m/s:scale = clamp(0.833, 0.52, 1.0) = 0.833,保留 83% 的奖励
    • cmd_xy ≥ 0.12 m/s:scale = 1.0,全额奖励

    下界 0.52(而非 0)确保低速时策略仍有步行动机,这是整个低速训练的关键。

  4. contact_filt(接触滤波):用 OR(contact, last_contact) 避免因仿真帧率导致的单帧虚假离地。


feet_swing_height(权重 -30.0

作用: 强制摆动相足端高度接近 0.1 m,是权重绝对值最大的惩罚项。

1
2
3
4
def _reward_feet_swing_height(self):
contact = torch.norm(self.contact_forces[:, self.feet_indices, :3], dim=2) > 1.
pos_error = torch.square(self.feet_pos[:, :, 2] - 0.1) * ~contact # 只惩罚腾空脚
return torch.sum(pos_error, dim=1)

为什么权重这么大(-30)?

这不只是控制抬腿高度,更核心的作用是消除”拖脚”行为

  • 若策略学会拖脚(feet_z ≈ 0),接触力为 0(腾空),~contact = True,误差 = ,惩罚 = (每脚每步)
  • 若策略抬腿至目标高度 0.1 m,误差 = 0,惩罚 = 0

-30 的权重让”拖脚 0.01 m 的偏差”就能产生 0.3 的惩罚,而 alive 奖励每步只有 0.15,这意味着拖脚的代价远大于存活收益,策略必须主动抬腿。


contact(权重 +0.5

作用: 基于步态相位引导正确的支撑/摆动时序,是步态同步的核心机制。

1
2
3
4
5
6
7
8
9
10
11
12
13
def _reward_contact(self):
cmd_gate = torch.where(
command_vel_norm < 1e-5,
torch.zeros_like(command_vel_norm),
torch.clamp(command_vel_norm / 0.12, 0.50, 1.0),
)
res = torch.zeros(...)
for i in range(self.feet_num):
is_stance = self.leg_phase[:, i] < 0.55 # 相位 0~0.55 = 支撑相(55%时间)
contact = self.contact_forces[:, self.feet_indices[i], 2] > 1
mismatch = contact ^ is_stance # XOR:状态不匹配
res += ((~mismatch).float() - mismatch.float()) * cmd_gate
return res

详细解析:

  1. 支撑相定义:相位 [0, 0.55) 为支撑相,[0.55, 1.0) 为摆动相。55% 的时间在支撑,45% 在摆动,对应较为保守的步态(高速跑步时支撑比可降至 40%)。

  2. 奖惩逻辑(用 XOR 实现):

    | 相位状态 | 接触状态 | mismatch | 奖励贡献 |
    |—-|—-|—-|—-|
    | 支撑相 | 有接触(正确) | False | +1 × cmd_gate |
    | 摆动相 | 无接触(正确) | False | +1 × cmd_gate |
    | 支撑相 | 无接触(错误) | True | -1 × cmd_gate |
    | 摆动相 | 有接触(错误) | True | -1 × cmd_gate |

    这个设计对错误时序显式惩罚(-1),而不仅仅是”不给奖励”,防止”双脚一直着地”等规避步态。

  3. 速度门控(下界 0.50):与 feet_air_time 的 0.52 一致,低速时保留 50%+ 的接触奖励。


contact_no_vel(权重 -0.1

作用: 惩罚接触状态下足端滑动(”滑步”行为)。

1
2
3
4
5
def _reward_contact_no_vel(self):
contact = torch.norm(self.contact_forces[:, self.feet_indices, :3], dim=2) > 1.
contact_feet_vel = self.feet_vel * contact.unsqueeze(-1) # 只取接触脚的速度
penalize = torch.square(contact_feet_vel[:, :, :3])
return torch.sum(penalize, dim=(1, 2))

支撑相脚应该固定在地面,任何水平速度都意味着打滑或步态不稳。注意这里用接触力的三轴范数(而非只用 Z 轴),对斜面接触也有效。


stand_still(权重 0

当前权重为 0,未激活。原本用于零速度指令时奖励静止,但因速度指令范围 lin_vel_x = [0.1, 0.5] 中没有零速,此项在当前阶段不需要。


3.5 对称性与安全类

feet_lateral_deviation(权重 -10.0

作用: 惩罚足端朝向偏离机体前进方向(外八/内八脚)。

1
2
3
4
5
6
7
8
9
def _reward_feet_lateral_deviation(self):
# 机体朝向(世界坐标系)
body_forward_world = quat_apply(base_quat, [1,0,0])
# 足端朝向(世界坐标系)
foot_forward_world = quat_apply(feet_quat, [1,0,0])
# 在 XY 平面比较 yaw 角差异
yaw_diff = foot_yaw - body_yaw
yaw_diff = atan2(sin(yaw_diff), cos(yaw_diff)) # 规范化到 [-π, π]
r = -sum(yaw_diff²)

几何含义: 要求足端的朝向(足部坐标系 X 轴)始终与机体前进方向对齐。当脚出现外旋/内旋时(脚尖偏离前方),yaw_diff 增大,惩罚增加。

权重 -10 较大,说明脚的朝向对步态质量影响显著,偏转会导致侧向力分量和不对称步态。


roll_outward(权重 -0.05

作用: 惩罚腿部”外翻”站姿(髋外展 + 踝外翻的组合)。

1
2
3
4
5
6
7
8
def _reward_roll_outward(self):
# 左腿:hip_roll > 0 为外展(向左),ankle_roll > 0 为外翻
left_outward = relu(hip_roll_l) + 0.5 * relu(ankle_roll_l)
# 右腿:hip_roll < 0 为外展(向右),ankle_roll < 0 为外翻
right_outward = relu(-hip_roll_r) + 0.5 * relu(-ankle_roll_r)
sq = left_outward² + right_outward²
quartic = left_outward⁴ + right_outward⁴
return sq + 0.08 * quartic

三个设计细节:

  1. relu 的使用:只惩罚外翻方向(relu 保留正值),内翻方向不惩罚,因为髋关节内收(向中线靠拢)是可接受甚至有益的姿态。

  2. 踝关节权重 0.5:踝关节对外翻的”贡献”打五折,因为踝的运动范围小,少量外翻影响相对小。

  3. 平方 + 四次方

    • 平方项:对小偏差也有惩罚梯度(不存在死区)
    • 四次方项(系数 0.08):大偏差时额外加重惩罚,形成非线性约束——轻微外翻可以接受,严重外翻受到严厉惩罚

collision(权重 -1.0

作用: 惩罚非足端部位的接触碰撞。

配置中 penalize_contacts_on = ["hip", "knee"],即髋部和膝盖不能碰地/碰障碍物。这防止策略学会”跪地行走”或”蹲伏前进”等投机行为。


alive(权重 +0.15

实现:

1
2
def _reward_alive(self):
return 1.0 # 每步恒定返回 1.0

每步奖励 =

配合终止条件(terminate_after_contacts_on = ["pelvis", "torso"]):

骨盆或躯干触地时立即终止 episode,此后不再获得 alive 奖励。这形成了”摔倒代价”:

  • 20 s episode 完整存活 = 大量累积 alive 奖励
  • 提前摔倒 = 损失剩余时间的所有 alive 奖励

存活奖励让策略在权衡”冒险换取短期高奖励”时倾向于保守,增强了整体稳定性。


3.6 奖励汇总表

奖励项 权重 核心作用
tracking_lin_vel +1.0 主驱动:跟踪前向速度
tracking_ang_vel +0.8 跟踪转向指令
lin_vel_z -2.0 抑制弹跳
ang_vel_xy -0.16 抑制躯干晃动
orientation -1.0 维持躯干竖立
base_height -3.0 维持骨盆高度(最强姿态约束)
dof_acc -2.5e-7 平滑动作(减少冲击)
dof_vel -1e-3 抑制高速关节运动
dof_pos_limits -5.0 防止关节超限
hip_pos -0.5 保持髋关节中立位
ankle_pos -1.0 保持踝关节稳定
action_rate -0.01 平滑动作输出
feet_air_time +5.0 保证足够腾空(核心步态奖励)
feet_swing_height -30.0 强制抬腿(最强单项惩罚)
contact +0.5 相位同步步态时序
contact_no_vel -0.1 防止支撑脚滑动
feet_lateral_deviation -10.0 防止外八/内八脚
roll_outward -0.05 防止腿部外翻
collision -1.0 防止髋膝碰地
alive +0.15 鼓励全程存活

四、域随机化(Domain Randomization)

域随机化是 Sim-to-Real 迁移的核心技术。仿真环境与真实物理世界之间必然存在”仿真间隙”(sim-to-real gap)——摩擦系数估计不准、电机刚度有误差、质量分布与 URDF 有偏差……如果策略只在单一仿真参数下训练,一旦部署到真机,细微的参数差异就会导致策略失效。

域随机化的核心思想: 在训练时随机化大量物理参数,让策略学会在参数分布上鲁棒,而非只在一个参数点上最优。

本项目设计了 9 大类、15 个随机化维度,涵盖从接触物理到初始化状态的完整 sim-to-real gap。


4.1 摩擦力随机化

1
2
randomize_friction = True
friction_range = [0.12, 2.0]

随机化方式: 每个环境在 episode 开始时从 均匀采样一个摩擦系数,应用于机器人脚与地面的接触。

范围分析:

摩擦系数 对应物理场景
0.12 湿地板、冰面(极度光滑)
0.3~0.5 瓷砖地面
0.6 普通室内地板(基础值)
1.0~1.5 橡胶地垫、地毯
2.0 粗糙摩擦面(极度粗糙)

范围跨度近 17 倍,是整个系统中变化幅度最大的域随机化项。这迫使策略学会在极端摩擦条件下的适应性步态控制。

对步态的影响: 低摩擦下支撑脚容易打滑,需要减小关节力矩;高摩擦下可以更激进地推蹬。策略必须通过观测(接触力、速度误差等)隐式感知当前摩擦系数,并调整步态。


4.2 机体质量随机化

1
2
randomize_base_mass = True
added_mass_range = [-8., 8.]

随机化方式: 在骨盆 link 上叠加一个 kg 的随机质量(可以是负值,即减重)。

物理意义: 模拟机器人搭载不同质量上肢/载荷的场景:

  • +8 kg:携带较重的上半身或背包
  • -8 kg:轻量化版本(减轻腿部重量假设)

质量变化直接影响重心高度和惯性,对平衡控制有根本性影响。策略需要在不知道当前质量的情况下(质量不在观测中)仅通过动态响应来适应。


4.3 质心位置随机化(两层粒度)

第一层:骨盆质心偏移(粗粒度)

1
2
randomize_base_com = True
base_com_range = [-0.02, 0.02] # 各轴 ±2 cm

骨盆质心在 X、Y、Z 三个轴各独立随机偏移 ±2 cm。这模拟了机器人上半身重心前后/左右偏移(如脊柱弯曲、载荷偏心)对整体平衡的影响。

第二层:其他连杆质心偏移(细粒度)

1
2
randomize_other_com = True
other_com_range = [-0.001, 0.001] # ±1 mm

对大腿、小腿、脚等所有其他连杆各自随机偏移 ±1 mm 的质心位置。范围极小,模拟机械加工精度误差和内部走线/电机位置的细微偏差。

两层分离的设计意图: 骨盆承载整个上半身,质心偏移影响最大(±2 cm);四肢连杆单个质量小、位移小,只需小范围扰动(±1 mm)。分层设计避免了”所有连杆都大范围随机化”导致的训练不稳定。


4.4 连杆质量缩放

1
2
randomize_other_mass = True
other_mass_scaling_range = [0.995, 1.005] # ±0.5% 缩放

对非骨盆连杆的质量进行乘法缩放(multiplicative scaling),范围 ±0.5%。

与质心偏移的区别:

  • 质心偏移改变质量分布(重心位置)
  • 质量缩放改变质量大小(惯性大小)

两者共同覆盖了 URDF 模型与真实机器人之间的质量参数差异。±0.5% 的范围保守,适合训练初期不引入过大干扰。


4.5 关节 PD 参数随机化

刚度(Stiffness)随机化:

1
2
randomize_dof_stiffness = True
dof_stiffness_scale_range = [0.99, 1.01] # ±1%

阻尼(Damping)随机化:

1
2
randomize_dof_damping = True
dof_damping_scale_range = [0.99, 1.01] # ±1%

两者都是乘法缩放,对每个关节的 Kp、Kd 分别独立随机缩放 ±1%。

物理意义: 真实电机的阻抗特性与仿真 PD 参数存在系统性偏差(电机摩擦、电流环延迟等),这里模拟这种偏差。

范围保守(±1%)的原因: 训练初期 PD 参数大幅变化会导致机器人不稳定。±1% 在保证训练稳定的前提下引入了必要的鲁棒性。


4.6 初始化状态随机化

Episode 开始时对初始状态施加扰动,防止策略”过拟合”完美初始条件:

关节初始位置扰动:

1
2
3
randomize_init_dof_pos = True
init_dof_pos_range = [0.0, 0.01] # 叠加 0~0.01 rad 偏移
dof_pos_scale_range = [0.99, 1.01] # 同时乘以缩放系数

两种扰动叠加:加法偏移(0~0.01 rad)和乘法缩放(±1%),使初始关节角度在默认值附近随机抖动。

机体初始位置扰动:

1
2
randomize_init_base_pos_xy = True
init_base_pos_xy_range = [-0.05, 0.05] # XY 方向 ±5 cm

机体初始 XY 位置随机偏移 ±5 cm,使机器人不总是从相同位置出发。

初始速度扰动:

1
2
base_lin_vel_range = [-0.05, 0.05]   # 初始线速度 ±0.05 m/s
base_ang_vel_range = [-0.02, 0.02] # 初始角速度 ±0.02 rad/s

机体开始时已有微小速度,模拟”机器人已在运动中”的场景,增加策略对非零初始条件的鲁棒性。


4.7 周期性推力扰动(Push Robots)

1
2
3
push_robots = True
push_interval_s = 4 # 每 4 秒推一次
max_push_vel_xy = 1.5 # 最大推力速度 1.5 m/s

实现机制:

1
2
3
4
5
6
7
def _push_robots(self):
env_ids = episode_buf % push_interval == 0 # 找到需要推的环境
max_vel = self.push_vel_xy # 当前推力幅度(课程控制)
self.root_states[push_env_ids, 7:9] = torch_rand_float(
-max_vel, max_vel, (len, 2)
) # 直接修改根节点线速度的 XY 分量
self.gym.set_actor_root_state_tensor_indexed(...)

推力通过直接修改根节点速度实现(而非施加力),这是 IsaacGym 中模拟冲击扰动的标准方式。推力方向和大小均在 m/s 均匀随机,可以向任意水平方向推。

推力强度量化: 1.5 m/s 的速度突变对一个 ~30 kg 的机器人相当于约 的瞬时冲击力,是一个较大的扰动。策略需要在 4 秒内从速度突变中恢复到正常行走状态,再迎接下一次推力。


4.8 推力课程学习(Push Curriculum)

虽然当前 curriculum = False(关闭),但代码中实现了完整的自适应课程逻辑:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
def update_push_curriculum(self, env_ids):
# 每 100 个 episode 评估一次
if self.push_curriculum_counter % 100 != 0:
return

# 从 episode 统计中读取表现指标
avg_tracking = mean(tracking_lin_vel reward) / max_episode_length
avg_alive = mean(alive reward) / max_episode_length

# 调整阈值(基于奖励权重)
increase_threshold = 0.85 * reward_scales["tracking_lin_vel"] # = 0.85
decrease_threshold = 0.40 * reward_scales["tracking_lin_vel"] # = 0.40
alive_increase_threshold = 0.90 * reward_scales["alive"] # = 0.135
alive_decrease_threshold = 0.50 * reward_scales["alive"] # = 0.075

# 双指标同时满足才增加难度
if avg_tracking > 0.85 AND avg_alive > 0.135:
push_vel_xy += 0.1 # 每次增加 0.1 m/s
elif avg_tracking < 0.40 OR avg_alive < 0.075:
push_vel_xy -= 0.1 # 每次减少 0.1 m/s

# 限制在初始值和最大值之间
push_vel_xy = clip(push_vel_xy, 0.2, 1.5)

课程逻辑设计:

  1. 双指标联合评估:只有速度跟踪和存活率同时达到阈值,才增加推力。防止策略只会在低推力下走得快,不考虑稳定性。

  2. 宽容的降档条件:跟踪低于 40% 或存活低于 50% 时才降档,不会因为偶发性表现下降就立即降低难度,保留一定的训练韧性。

  3. 细粒度调节(±0.1 m/s):每次只调整 0.1 m/s,从初始 0.2 m/s 到最大 1.5 m/s 需要 13 次升档,保证平滑过渡。

  4. 历史滑动窗口push_performance_history 保存最近 5 次评估结果(虽然当前决策未完全使用历史,但框架已准备好)。


4.9 高频微扰动 Kick

1
2
3
4
kick_robots = True
kick_interval_s = 2.0 # 每 2 秒 kick 一次(比 push 更频繁)
kick_lin_vel_range = [0.0, 0.02] # 线速度扰动 0~0.02 m/s
kick_ang_vel_range = [0.0, 0.005] # 角速度扰动 0~0.005 rad/s

Kick 与 Push 的对比:

特性 Push Kick
间隔 4 s 2 s
幅度 最大 1.5 m/s 最大 0.02 m/s
目的 模拟大冲击(被推) 模拟微扰动(地面不平、传感器噪声)
策略响应 需要主动恢复 隐式抵抗(感知不到单次 kick)

Kick 的速度扰动极小(0.02 m/s),策略不需要(也无法)对单次 kick 作出显式响应,但大量高频 kick 累积效果与真实地面微小不规则性类似,提高策略的被动鲁棒性。


4.10 接触形状参数随机化

1
2
3
4
5
randomize_shape_compliance = True
shape_compliance_range = [0.0, 0.002] # 接触合规性(柔软度)

randomize_shape_restitution = True
shape_restitution_range = [0.0, 0.01] # 弹性恢复系数(弹跳性)

接触合规性(Compliance): 模拟接触面的”柔软度”——橡胶底座在接触时有轻微形变,而非完全刚性。范围 [0, 0.002] 非常小,仅引入微小的接触柔软度变化。

弹性恢复系数(Restitution): 控制接触碰撞的弹跳比例(0 = 完全非弹性,1 = 完全弹性)。范围 [0, 0.01] 接近完全非弹性,模拟橡胶底鞋的轻微弹性。

这两个参数的随机化范围都很小,属于对接触物理模型的”精细调优”,主要覆盖不同地面材质(硬地板 vs. 软垫)的接触特性差异。


4.11 域随机化汇总

类别 参数 随机化范围 随机化方式
地面摩擦 friction_range [0.12, 2.0] 每 episode 均匀采样
机体质量 added_mass_range [-8, 8] kg 叠加到骨盆
骨盆质心 base_com_range ±2 cm(各轴) 偏移骨盆质心
连杆质心 other_com_range ±1 mm 偏移各连杆质心
连杆质量 other_mass_scaling_range [0.995, 1.005] 乘法缩放
PD 刚度 dof_stiffness_scale_range [0.99, 1.01] 乘法缩放
PD 阻尼 dof_damping_scale_range [0.99, 1.01] 乘法缩放
初始关节角 init_dof_pos_range [0, 0.01] rad 加法偏移
初始位置 init_base_pos_xy_range ±5 cm 偏移 XY 位置
初始速度 base_lin_vel_range ±0.05 m/s 赋初始线速度
初始角速度 base_ang_vel_range ±0.02 rad/s 赋初始角速度
推力扰动 max_push_vel_xy 最大 1.5 m/s 每 4 s 修改速度
Kick 微扰 kick_lin_vel_range 0~0.02 m/s 每 2 s 微扰速度
接触柔软度 shape_compliance_range [0, 0.002] 接触形状参数
接触弹性 shape_restitution_range [0, 0.01] 接触形状参数

五、速度指令设计

5.1 指令范围与重采样

1
2
3
4
5
6
7
8
9
10
class commands:
curriculum = True # 指令课程学习:开启
resampling_time = 8. # 每 8 秒重新采样
heading_command = False # 不使用朝向指令模式

class ranges:
lin_vel_x = [0.1, 0.5] # 前向速度:0.1~0.5 m/s
lin_vel_y = [0, 0] # 侧向速度:0(直行训练)
ang_vel_yaw = [0, 0] # 偏航角速度:0(直行训练)
heading = [-3.14, 3.14] # 朝向(仅 heading_command 模式使用)

当前阶段专注于纯前向直行训练:侧向速度和偏航角速度固定为 0,仅前向速度在 [0.1, 0.5] m/s 范围内随机。

为什么最小速度是 0.1 m/s 而不是 0?

这是一个刻意的设计决策:

  1. 避免学习”站立即可”的捷径:若指令包含 0 速,策略可能发现”静止不动”是损失最小的策略,因为静止时几乎所有惩罚都接近 0
  2. 保证步行行为始终被激励:0.1 m/s 的最小速度保证策略在整个训练过程中都必须走动
  3. 与低速奖励设计配合:所有步态奖励的速度门控(scale = clamp(cmd/0.12, 0.5, 1.0))在 0.1 m/s 时仍给出 ~0.83 的缩放,保证低速步行有足够奖励信号

5.2 死区处理

1
2
3
4
5
6
def _resample_commands(self, env_ids):
# 采样后施加死区:速度幅度 < 0.05 m/s 则清零
deadzone = 0.05
self.commands[env_ids, :2] *= (
torch.norm(self.commands[env_ids, :2], dim=1) > deadzone
).unsqueeze(1)

由于指令范围 lin_vel_x = [0.1, 0.5],最小值 0.1 m/s > 死区 0.05 m/s,死区在当前配置下实际上不会触发。但它的存在是防御性编程——如果未来扩展指令范围包含接近 0 的值,死区会清除这些噪声级别的微小指令,避免策略在”接近零速但非零”的指令下行为混乱。

5.3 指令课程学习

curriculum = True 开启了指令课程学习。legged_gym 基类的实现通常是:

  • 训练初期从较小的速度范围开始
  • 随着策略能力提升,逐步扩大到完整范围 [0.1, 0.5] m/s
  • 扩大时机基于跟踪奖励的阈值判断

每 8 秒(resampling_time)重新采样一次指令,让策略在单个 episode(20 s)内经历 2~3 次指令变化,训练其对速度切换的响应能力。


六、PPO 训练超参数

6.1 神经网络结构

1
2
3
4
5
class policy:
init_noise_std = 1.0
actor_hidden_dims = [512, 256, 128]
critic_hidden_dims = [512, 256, 128]
activation = 'elu'

网络架构: 两个独立的 3 层 MLP:

1
2
Actor:  705 → 512 → 256 → 128 → 12   (动作输出,12 个关节)
Critic: 50 → 512 → 256 → 128 → 1 (价值估计,标量)

激活函数 ELU(Exponential Linear Unit):

相比 ReLU,ELU 在负值区域有非零梯度,避免了”神经元死亡”问题。在强化学习中,ELU 通常比 ReLU 收敛更稳定,在连续控制任务(如机器人运动)中广泛使用。

初始动作噪声 init_noise_std = 1.0 训练开始时策略输出加标准差为 1.0 的高斯噪声,提供足够的探索。随训练进展,噪声通常会通过 adaptive 调度逐渐减小。

6.2 PPO 核心超参数

1
2
3
4
5
6
7
8
9
10
class algorithm:
learning_rate = 1.e-4
schedule = 'adaptive'
desired_kl = 0.003
clip_param = 0.08
entropy_coef = 0.001
gamma = 0.99
lam = 0.95
num_learning_epochs = 3
num_mini_batches = 8

逐项分析:

learning_rate = 1e-4(自适应)

学习率 1e-4 是强化学习中较保守的值。配合 schedule = 'adaptive':当 KL 散度偏离 desired_kl 时,学习率会自动调节:

  • KL > desired_kl:降低学习率(步子太大)
  • KL < desired_kl / 2:提高学习率(可以更大胆)

这是一种自适应信赖域方法,比固定学习率更稳定。

desired_kl = 0.003(目标 KL 散度)

标准 PPO 通常设 0.01~0.02。这里设为 0.003,远比常规保守。

这意味着每次策略更新,新旧策略分布的 KL 散度不超过 0.003——策略”变化很小”。这对本任务的合理性:

  • 705 维观测 + 复杂奖励体系 → 策略空间维度极高
  • 过大的策略更新容易导致不稳定(策略突然”跑偏”)
  • 0.003 的 KL 约束确保每步只做小幅修正,牺牲速度换稳定

clip_param = 0.08(PPO 截断系数)

PPO 的重要性采样截断,标准 ε = 0.2,这里设为 0.08,截断区间 [0.92, 1.08] 更窄。与小 KL 目标配合,从两个角度限制了策略更新幅度,形成双重保守约束。

entropy_coef = 0.001(熵正则化)

在损失中加入熵奖励,鼓励策略保持一定随机性(探索)。系数很小(0.001),主要作用是防止策略过早收敛到确定性行为,而非主导探索。

gamma = 0.99(折扣因子)

意味着未来 100 步(约 2 s)的奖励仍有约 0.37 的权重。这让策略能考虑到一个完整步态周期(约 0.5~1 s)内的延迟奖励,避免只优化即时奖励。

lam = 0.95(GAE lambda)

GAE(Generalized Advantage Estimation)的偏差-方差权衡系数。 接近 Monte Carlo,偏差方差平衡,是 PPO 的常用设置。

num_learning_epochs = 3num_mini_batches = 8

每次收集数据后,对同一批数据训练 3 个 epoch,每 epoch 分 8 个 mini-batch。相比标准 PPO(通常 4~10 epochs),3 个 epochs 偏少,与保守的 KL 约束一致——宁可少训几次,不要过拟合当前数据。

6.3 训练流程参数

1
2
3
4
5
6
7
8
class runner:
num_steps_per_env = 32 # 每次收集 32 步数据
max_iterations = 5000 # 最多 5000 个迭代
save_interval = 100 # 每 100 个迭代保存一次

use_wandb = True
wandb_project = 'pnd_x2_legs_only_locomotion'
wandb_tags = ['x2_legs_only', 'rough_terrain', 'mlp', 'frame_stack_15']

num_steps_per_env = 32

每个并行环境每次收集 32 步,以 50 Hz 控制频率计算 = 0.64 秒的经验。这个窗口短于一个步态周期(0.52~1.07 s),意味着单次收集可能不覆盖完整步态。但多个并行环境提供了大量多样性,弥补了单环境窗口短的问题。

WandB 集成:

训练指标自动上传到 WandB 项目 pnd_x2_legs_only_locomotion,标签记录了关键配置(帧堆叠 15、MLP 架构、rough terrain 标签),方便多次实验的对比分析。


七、观测噪声配置

1
2
3
4
5
6
7
8
9
class noise:
add_noise = True
noise_level = 1.0 # 总体噪声缩放

class noise_scales:
dof_pos = 0.05 # 关节位置噪声
dof_vel = 0.5 # 关节速度噪声
ang_vel = 0.5 # 角速度噪声(IMU)
gravity = 0.5 # 重力向量噪声(倾斜估计)

噪声模型为均匀白噪声,每帧独立采样,每帧各自独立,无相关性,贴近真实传感器特性。

各观测项噪声尺度设计逻辑:

观测项 噪声尺度 理由
关节位置 0.05(小) 磁编码器精度高,典型误差 < 0.01 rad
关节速度 0.5(大) 由位置微分估计,受编码器分辨率和采样率限制
角速度 0.5(大) IMU 陀螺仪有明显漂移和噪声
重力向量 0.5(大) 由 IMU 加速度计估计,受振动影响显著
速度指令 0(无) 来自上层控制器,无传感器噪声
动作历史 0(无) 策略自身输出,精确已知

八、设计总结与亮点

回顾整个 X2 腿部训练系统,以下几个设计是值得重点记录的技术亮点:

8.1 自适应步态周期时钟

1
period = 0.52 + 0.55 * exp(-cmd_xy / 0.18)

这个简洁的公式让步态时钟频率随指令速度自动调节,解决了”固定步态周期在低速下奖励错配”的根本问题。不需要任何手工调参,只需确定两个渐近值(高速极限 0.52 s、低速极限 1.07 s)和过渡速度(0.18 m/s)。

8.2 速度自适应奖励门控

步态相关奖励(feet_air_timecontact)全部使用:

1
scale = clamp(cmd_xy / 0.12, min_val, 1.0)

而非常见的”低于阈值直接清零”。下界 min_val 非零(0.50~0.52)确保了低速训练的有效性。这个细节在论文中很少被提及,但对低速步行训练至关重要。

8.3 双重保守 PPO 设置

clip_param = 0.08 + desired_kl = 0.003,两个参数都远比标准值保守,形成”双保险”的策略更新限制。对于 705 维高维观测和多目标奖励体系,这种保守设置显著提高了训练稳定性。

8.4 帧堆叠替代 LSTM

用 15 帧观测历史(0.3 s 窗口)替代 LSTM 的时序建模能力,避免了 RNN 在强化学习中常见的梯度消失、截断 BPTT 偏差等问题。MLP + 帧堆叠在速度和稳定性上通常优于 LSTM,在 IsaacGym 大规模并行训练中尤为明显。

8.5 分层域随机化策略

从大尺度(质量 ±8 kg、摩擦 0.12~2.0)到中尺度(骨盆质心 ±2 cm)再到小尺度(PD 增益 ±1%、连杆质心 ±1 mm),三个量级的随机化系统性覆盖了不同来源的 sim-to-real gap,同时避免了”所有参数都大范围随机化导致训练不稳定”的问题。

8.6 足端几何约束的精细设计

feet_lateral_deviation(权重 -10)和 roll_outward(权重 -0.05 但带四次方项)两个奖励项的组合,从”足端朝向”和”腿部姿态”两个维度共同约束了走路的”外观质量”——这在基础 legged_gym 框架中通常没有,是针对 X2 机器人 URDF 特性的专项优化。