跳到主要内容

6. 策略训练

上一章的 trot 是我们编程让它走;这一章我们让它学会走。我们会把 Pupper 仿真包成一个 Gymnasium 环境,用 PPO 训练一条能向任意方向走的策略,并和第 5 章的开环步态对比。

本章目标

  • 能把 MuJoCo 仿真封装成标准 gymnasium.Env
  • 能独立设计观测 / 动作 / 奖励(至少 3 项奖励项)
  • 能用 stable-baselines3 跑完一轮 PPO 训练(典型 5–20 分钟)
  • 能解读 tensorboard 上的训练曲线

前置阅读

6.1 为什么能学

第 5 章的 trot 是把"哪条腿什么时候抬、抬多高、落哪里"全写死的脚本。改地形要重写,改速度要重调,改 Pupper 的腿长要从头来一遍——控制器和机器人是绑死的

RL 把这件事反过来做:把奖励写下来,让策略自己摸索哪条腿什么时候抬。好处不是 RL 一定比 trot 跑得快(在平地上多半还跑不过手写 trot),而是同一份训练流程可以:

  • 换地形(小坡、小石子、有摩擦的地毯)只要重训不改代码;
  • 换机器人(Pupper → Go1 → Anymal)只要换 URDF 和动作维度;
  • 推扰、负载变化、电池电压抖动这些手写 trot 难以全部覆盖的工况,靠域随机化一并放进训练分布。

类比(来自 CS123 Lab 5 slides):教小孩走路不是手把手安排每一步,而是给一个"看到目标就靠近 + 不摔倒"的内在奖励。但这套基础奖励远远不够——直接训出来的策略往往是"四肢狂甩往前冲"。下面 6.4 节会把这件事拆成"主奖励 + 四类辅助奖励"的标准结构。

代价也清楚:奖励工程要花时间、训练要花算力、sim2real 还要花一轮调参。这一章的目标是把这三笔账都摆到台面上。

6.2 Gymnasium 环境

Pupper 的 RL 环境本质就是 MuJoCo 仿真套一个 Gymnasium 标准接口,重点是把 reset / step / observation_space / action_space 四件套写干净:

import gymnasium as gym
from gymnasium import spaces
import mujoco
import numpy as np

class PupperEnv(gym.Env):
def __init__(self, xml='pupper.xml', dt=0.02, max_steps=1000):
self.model = mujoco.MjModel.from_xml_path(xml)
self.data = mujoco.MjData(self.model)
self.dt, self.max_steps = dt, max_steps

# 12 维连续动作:每个关节一个目标角(归一化到 [-1, 1])
self.action_space = spaces.Box(-1.0, 1.0, (12,), np.float32)

# 观测拼成一个一维向量,典型 ~50 维
obs_dim = (
3 + # base 角速度 ω
3 + # base 重力方向(在 base 系下) → 隐式编码 roll/pitch
12 + # 关节角
12 + # 关节速度
12 + # 上一步动作(对策略平滑很关键)
4 + # 4 个足端接触布尔
3 # 速度命令 (vx_cmd, vy_cmd, ωz_cmd)
)
self.observation_space = spaces.Box(-np.inf, np.inf, (obs_dim,), np.float32)

def reset(self, *, seed=None, options=None):
super().reset(seed=seed)
mujoco.mj_resetData(self.model, self.data)
self.data.qpos[:7] = [0, 0, 0.18, 1, 0, 0, 0]
self.data.qpos[7:] = STAND_POSE
self.last_action = np.zeros(12, np.float32)
self.cmd = self._sample_command() # 随机给一个速度命令
self.step_count = 0
return self._get_obs(), {}

def step(self, action):
target = STAND_POSE + 0.5 * action # PD 残差,见 6.3
for _ in range(int(self.dt / self.model.opt.timestep)):
tau = Kp * (target - self.data.qpos[7:]) - Kd * self.data.qvel[6:]
self.data.ctrl[:] = tau
mujoco.mj_step(self.model, self.data)

self.last_action = action
self.step_count += 1
reward, info = self._compute_reward(action)
terminated = self._is_fallen()
truncated = self.step_count >= self.max_steps
return self._get_obs(), reward, terminated, truncated, info

几个细节比看起来重要得多:

  • 观测里塞"上一步动作"。少了它,策略经常学出高频抖动——因为它无法知道自己刚才输出了什么。
  • 观测里用 base 系下的重力方向而不是世界系下的四元数。这样可以让策略对绝对朝向不敏感,转一圈也不会失忆——sim2real 时这个细节救命。
  • step 里跑多个物理步。仿真器 timestep 一般 0.5–2 ms(数值稳定),策略决策 20–50 Hz 已足够,二者解耦。

6.3 动作设计

12 维连续动作直接喂给关节 PD 的目标角,写法上有三档:

方案公式优点缺点
直接目标角target = a * scale + offset简单直观探索一开始就把腿甩飞
PD 残差(推荐)target = stand_pose + scale * a训练初期就能"站住",从站姿出发学走多一行代码
增量target_t = target_{t-1} + step * a平滑容易飘,训练后期会越走越偏

scale = 0.3 ~ 0.5 rad 是经验值——大到能学出步态,小到不会一上来就翻。先 stand 再 walk 是这条选择背后真正的动机:环境一上来不"立即崩盘",奖励信号才有梯度可以爬。

6.4 奖励设计

这一节是整章的核心,也是 CS123 Lab 5 slides 反复强调的一句话:只奖励"跟随速度命令"是远远不够的。直接训出来的策略会用"上半身狂甩 + 四肢乱踢"的方式跑出 vx,但你绝不想把它接到真机上。

业内通用的做法是把奖励拆成一个主奖励 + 四类辅助奖励

主奖励:速度跟随

exp 的好处是它在 cmd 附近平滑、远离时不爆炸,比直接 -||·||² 训练更稳。

辅助:电机效率

r_torque = -‖τ‖² # 力矩平方惩罚
r_act_rate = -‖a_t - a_{t-1}‖² # 动作变化率惩罚

这两项是把"不要乱抖"写成数学。r_act_rate 是出现优雅步态的关键——没有它,6.7 节那个暴走策略永远收敛不到 6.8 节的 trot。

辅助:稳定性

r_ori = -‖roll‖² - ‖pitch‖² # 别歪
r_height = -(z_base - 0.18)² # 别趴
r_yaw = -‖ωz - ωz_cmd‖² # 朝向跟随命令

辅助:接触管理

r_body_contact = -1 if 身体/膝盖触地 else 0 # 直接判负
r_air_time = +Σ (T_swing - 0.5)² # 摆动相要够长,鼓励"抬腿走"而不是"擦地走"

辅助:地形鲁棒

r_foot_clearance = +Σ ‖p_foot,z‖ * |v_foot,xy| # 摆动腿水平移动时鼓励抬高

写成一份配置

REWARD_WEIGHTS = {
'vel': 1.5,
'torque': 2e-4,
'action_rate': 1e-2,
'orientation': 1.0,
'height': 5.0,
'yaw': 0.5,
'body_contact': 1.0,
'air_time': 1.0,
'foot_clearance': 1.0,
'alive': 0.1, # 每步存活奖励,缓解早期"摔了就 0 reward"
}

调参顺序:先把 vel 单独训出来看暴走策略(实验 1);再加 torque + action_rate 看步态是否变规整(实验 2);再加稳定性、接触、地形三组看是否能在不平地形跑。一次只加一类,否则训练曲线变了也不知道是哪一项的功劳。

6.5 域随机化

策略只在"理想 Pupper"上训练,到真机上必崩——质量误差 5%、地板摩擦 0.6 而不是 0.8、电池电压掉了 10%,这些都会让策略找不到熟悉的状态分布。**域随机化(DR)**就是在仿真里把这些参数随机抖一抖,强迫策略对它们不敏感:

def randomize(model):
# 1. 质量在 ±20% 范围抖
for i in range(model.nbody):
model.body_mass[i] *= np.random.uniform(0.8, 1.2)

# 2. 地板摩擦 0.5 ~ 1.2
floor_id = mujoco.mj_name2id(model, mujoco.mjtObj.mjOBJ_GEOM, 'floor')
model.geom_friction[floor_id, 0] = np.random.uniform(0.5, 1.2)

# 3. 初始关节角 ±0.1 rad 抖动 (在 reset 里)
# 4. 每 1~3 秒给 base 一个随机外力 (在 step 里)

DR 加上之后训练会变慢 30%~50%,但 sim2real 几乎是必须的代价。CS123 Lab 5 slides 把它单列为整个工作流的一步,原因就是这个。

6.6 PPO 训练脚本

新手友好的路径是 stable-baselines3

import gymnasium as gym
from stable_baselines3 import PPO
from stable_baselines3.common.vec_env import SubprocVecEnv

def make_env(seed):
def _thunk():
env = PupperEnv()
env.reset(seed=seed)
return env
return _thunk

vec_env = SubprocVecEnv([make_env(i) for i in range(8)]) # 8 个并行 env

model = PPO(
'MlpPolicy', vec_env,
n_steps=2048, batch_size=512, n_epochs=10,
learning_rate=3e-4, gamma=0.99, gae_lambda=0.95,
clip_range=0.2, ent_coef=0.005,
tensorboard_log='./tb/', verbose=1,
)
model.learn(total_timesteps=2_000_000)
model.save('pupper_ppo.zip')

CPU 上 8 路并行训 2M 步大约 20–40 分钟,能学出一个看得过去的步态。

想再快 10–100 倍 就要换到 GPU 版的 MJX(JAX 版 MuJoCo),CS123 Lab 5 官方就是这条路。MJX 把 4096 个并行 env 跑在一张显卡上,训练时间可以从小时压到分钟级。代价是 JAX 学习曲线 + 没有 SB3 那么多现成轮子,第一次训练建议先用上面的 SB3 路线把整条管线跑通,再切到 MJX 加速

打开 tensorboard 主要盯三条曲线:

  • rollout/ep_rew_mean:总奖励,应当稳步上升;下跌就是奖励项打架。
  • train/clip_fraction:裁剪比例,长期 < 0.3 算稳;> 0.5 说明 lr 偏大。
  • train/explained_variance:value head 学得好不好,> 0.7 算不错。

6.7 速度奖励实验

只保留主奖励 vel,其它权重全部置 0:

REWARD_WEIGHTS = {'vel': 1.5, 'alive': 0.1}

训 5 分钟(约 300k 步)后看视频:

  • 前向速度大概率能拉到 0.6 m/s 以上,比第 5 章手写 trot 还快
  • 但样子很难看:四条腿不分相位地乱踢,base 上下蹦得像在 pogo stick 上。
  • 力矩曲线一路顶到 ctrlrange 上限——这是真机的电机杀手。

这条策略的存在价值只有一个:给 6.8 节做对照组。它说明"只跟随速度"不够。

6.8 能量惩罚实验

在实验 1 基础上加两项:

REWARD_WEIGHTS = {
'vel': 1.5, 'alive': 0.1,
'torque': 2e-4, 'action_rate': 1e-2,
}

同样训 5 分钟,对照看:

  • 视觉上自动出现规整的对角步态——RL 自己"发现"了 trot;
  • 速度可能从 0.8 降到 0.5 m/s,但能耗(mean(τ²))下降 60% 以上;
  • 训练曲线在前 50k 步上升较慢(先要学会"少抖"),之后追上实验 1。

把两条策略并排录视频做对比,就是 CS123 Lab 5 slides 里那一句"基础奖励不够"最直观的注脚

进一步想做"接触感强、能跨台阶"的步态,把 6.4 里稳定性 + 接触管理 + 地形鲁棒性三组奖励一组组加进去重训,每加一组录 30 秒视频归档——这就是动手任务里"对比手写 trot vs RL 步态"的素材库。

6.9 评估与录屏

加载训练好的模型用 viewer 跑一段,标准做法:

import mujoco.viewer
from stable_baselines3 import PPO

env = PupperEnv()
model = PPO.load('pupper_ppo.zip', env=env)

obs, _ = env.reset(seed=42)
with mujoco.viewer.launch_passive(env.model, env.data) as v:
while v.is_running() and env.step_count < 1500:
action, _ = model.predict(obs, deterministic=True)
obs, _, term, trunc, _ = env.step(action)
v.sync()
if term or trunc:
obs, _ = env.reset()

评估指标至少给三条:

  1. 直线速度 vx 实际值 vs 命令 vx:在 (0.2, 0.5, 0.8) m/s 三档命令下分别跑 30 秒,画跟踪误差曲线。
  2. 能耗mean(‖τ‖²),和第 5 章手写 trot 在同样速度下对比。
  3. 抗扰动:在 step 里给 base 一个 5 N·s 的横向冲量,记录恢复时间。

这三条加上一段 side-by-side 对比视频,就是动手任务里"和上游预训策略对比"的素材。下一章我们会在 RL 策略上面再架一层 LLM——让 Pupper 听懂自然语言指令。

动手任务

§6.6 跑通了 PPO 训练、§6.7–6.8 看到了"暴走"和"优雅"两种策略的差异。但到目前为止我们只盯着自己训出来的策略看——它和 CS123 Lab 5 官方提供的上游预训策略(test_policy.json,用 MJX 在 GPU 上训了数十亿步)比起来到底差多少?本章动手任务把整条管线端到端跑一遍:封装环境、训练 2M 步 PPO、加载上游 checkpoint 做 side-by-side 对比,最后用速度跟踪曲线量化差距。

Ch6 成果预览:我们的 PPO vs 上游预训策略

同一段命令序列(stand → forward 0.5 m/s → turn left → backward → stand)下的 side-by-side 对比。左:我们用 SB3 PPO 在 CPU 上训 2M 步(~20 分钟)得到的策略——能跟随命令但步态偏僵,前进时身体前倾明显。右:上游 test_policy.json——在 MJX 上训了数十亿步,步态流畅、转弯平稳,同样的 forward 命令下身体几乎不倾斜。差距是真实的,但左边那条策略是你从零开始、20 分钟训出来的——这就是 §6.1 说的"同一份训练流程可以换机器人、换地形"的起点。

要做的四件事:

  • PupperEnv(gymnasium.Env):obs = base 角速度 + 重力方向 + 关节角/速 + 上一步动作 + 足端接触 + 速度命令;action = 12 维 PD 残差(§6.3);reward 至少包含 vel + torque + action_rate 三项(§6.4)
  • train_ppo():8 路 SubprocVecEnv,PPO 超参照 §6.6,训 2M 步存 pupper_ppo.zip;tensorboard 日志写到 tb/,训完后导出 reward_curve.png(ep_rew_mean / clip_fraction / explained_variance 三栏)
  • render_command_demo() + render_upstream_demo():加载上游 test_policy.json(RTNeural 格式,用 shared/rl/fetch_policies.sh 拉取),两条策略跑同一段命令序列,拼成 side-by-side comparison.gif
  • render_velocity_tracking():在 m/s 三档命令下各跑 8 秒,画实际速度 vs 命令的跟踪曲线 velocity_tracking.png

完整 starter / 测试 / 交付清单(含 Stretch:域随机化 + 抗扰动测试)见 exercises/lab_6_rl_pupper/

参考资料