tensorboard --logdir=logs --reload_interval=5 ..\IsaacLab\isaaclab.bat -p scripts\train.py --task MMRobot-Reach-v0 --headless --num_envs 4096 --max_iterations 3000 --resume --log_root 2
强化学习训练框架,基于 Isaac Lab 2.2.1(out-of-tree Extension) + Isaac Sim 5.0, 实现机器人技能挑战 C 级科技核心装配任务的 6-DOF 机械臂末端达到目标点训练。
- 底盘:4 轮 Caster 差速底盘(8 个关节:
front/rear_left/right_str/drive) → 训练时全部锁死(stiffness=1e10, damping=1e6),不参与控制 → 底盘 不固定 于世界坐标(fix_root_link=False),臂的反力矩会引起底盘被动运动 - 机械臂:6 关节串联臂(
joint1–joint6),末端为gripper_vacuum_1(真空吸盘) → 唯一控制自由度,动作空间维度 = 6 - 臂最大可达半径:约 0.97 m(从 base_link 原点计算,基于 URDF 连杆尺寸)
| 关节 | 相对父关节偏移 (x, y, z) | 说明 |
|---|---|---|
| joint1 | (0.125, 0, 0.255) | 肩部偏移 |
| joint2 | (0.05, 0.019, 0.103) | 肩旋转 |
| joint3 | (-0.35, 0, 0) | 上臂 0.35 m |
| joint4 | (-0.114, -0.019, 0.070) | 肘部过渡 |
| joint5 | (0, 0, 0.246) | 前臂 0.246 m |
| joint6 | (0, -0.105, 0) | 腕部 0.105 m |
机械臂末端执行器(EE)到达随机采样的目标点
- Manager-based:
ManagerBasedRLEnvCfg+ManagerBasedRLEnv - 算法:PPO(
rsl_rl,OnPolicyRunner) - 观测维度:22(关节位置 6 + 关节速度 6 + EE→target 向量 3 + 目标位置 3 + 目标四元数 4)
- 动作维度:6(关节位置 setpoint,单位 rad)
| 软件 | 版本 |
|---|---|
| Isaac Sim | 5.0 |
| Isaac Lab | 2.2.1(isaaclab 包名,非 omni.isaac.lab) |
| Python | ≥ 3.10 |
| CUDA | ≥ 12.x |
# 1. 激活 Isaac Lab 配套的 conda 环境
conda activate env_isaaclab
# 2. 安装 rm_tasks 子包(editable install)
cd d:\aim_ws\ISAAC\rl_mmrobot
pip install -e source/rm_tasks
# 3. 验证安装
python -c "import rm_tasks; print('rm_tasks OK')"机器人 USD 文件路径由 robot_cfg.py 自动解析:
<workspace_root>/MyArm/my_arm.usd
若 my_arm.usd 不存在,需先用 Isaac Lab URDF 转换器生成:
# 在 Python 环境中运行一次即可
from isaaclab.sim.converters import UrdfConverter, UrdfConverterCfg
cfg = UrdfConverterCfg(
asset_path="MyArm/MMRobot.urdf",
usd_dir="MyArm",
fix_base=False,
make_instanceable=True,
convex_decompose_mesh=True,
default_drive_type="position",
)
UrdfConverter(cfg)rl_mmrobot/
├── setup.py # 根包安装入口
├── README.md # 本文档
├── MyArm/
│ ├── MMRobot.urdf # 原始 URDF(14 关节:8 底盘 + 6 臂)
│ ├── my_arm.usd # URDF 转换后的 USD(训练时实际加载)
│ └── configuration/ # USD 分层配置(physics/sensor/robot/base)
│ ├── my_arm_base.usd
│ ├── my_arm_physics.usd
│ ├── my_arm_robot.usd
│ └── my_arm_sensor.usd
├── scripts/
│ ├── train.py # 训练入口(AppLauncher → OnPolicyRunner)
│ └── play.py # 推理预览入口(OnPolicyRunner 加载 checkpoint)
└── source/
└── rm_tasks/
├── setup.py # rm_tasks 包安装配置
└── rm_tasks/
├── __init__.py
├── config/
│ ├── __init__.py
│ └── mmrobot/
│ ├── __init__.py # 导出 MMROBOT_CFG
│ └── robot_cfg.py # ★ ArticulationCfg(底盘锁死 + 臂 PD 参数)
└── tasks/
├── __init__.py
└── reach/
├── __init__.py # gym.register 注册两个 env id
├── reach_params.py # ★ 所有可调参数集中于此
├── reach_env_cfg.py # ★ ManagerBasedRLEnvCfg 主配置
└── mdp/
├── __init__.py # 统一导出所有 mdp 函数
├── observations.py # 5 个观测函数(全 NaN 保护)
├── rewards.py # 7 个奖励函数(全 NaN 保护)
├── terminations.py # 3 个终止函数(time_out + base_tilt + reaching_success)
└── events.py # reset 逻辑(机器人 + 目标点)
★ 标注的 3 个文件是日常开发中最常修改的文件。
MMReachEnvCfg (ManagerBasedRLEnvCfg)
│
├── scene (MMReachSceneCfg)
│ ├── ground : AssetBaseCfg → 地面平面
│ ├── dome_light : AssetBaseCfg → 环境光
│ ├── robot : ArticulationCfg (MMROBOT_CFG)
│ ├── ee_frame : FrameTransformerCfg → 追踪 gripper_vacuum_1 世界位姿
│ └── target_marker : RigidObjectCfg (kinematic sphere) → 红色目标球标记
│
├── observations → ObservationManager → 拼接 22 维向量喂给 PPO actor
├── actions → ActionManager → 6 维 JointPositionAction
├── rewards → RewardManager → 每步计算 3 层距离+成功+3 项正则 = 7 个奖励项
├── terminations → TerminationManager → 超时 / 底盘倾翻
└── events → EventManager → reset 时采样新目标 + 重置关节
reset(env_ids)
│
├─ reset_scene_to_default() # PhysX 根位姿、关节归零
├─ reset_robot_joints(env_ids) # 臂关节加 ±0.15 rad 噪声,底盘保持 0
└─ reset_target_pose(env_ids)
│
├─ 在 OXYZ 系中采样 P_local (base_x, base_y, base_z)
├─ P_rel_base = P_local + [0.25, 0, 0] (坐标系偏移)
├─ 采样 ZYZ 球坐标角 (theta, phi, alpha) → 四元数 q_target_base
└─ combine_frame_transforms(robot_root_pose, P_rel_base, q_target)
→ 目标的世界位姿,写入 kinematic target_marker prim
step(actions)
│
├─ ActionManager: actions → joint position setpoints → PhysX
├─ sim.step() × decimation (4 次,共模拟 0.04 s)
├─ scene.update()
│ ├─ FrameTransformer 更新 ee_frame.data.target_pos_w
│ └─ RigidObject 更新 target_marker.data.root_pos_w
├─ ObservationManager: 拼接 22 维 obs
├─ RewardManager: 计算 7 项奖励
└─ TerminationManager: 判断是否结束(超时 or 底盘倾翻)
其中 isaaclab.utils.math.combine_frame_transforms,自动处理任意机器人朝向。
ImplicitActuatorCfg(
joint_names_expr=["front_left_str", "front_right_str", ...],
stiffness=1.0e10, # 位置弹簧极大 → 关节被钉在 init_state 的 0 rad
damping=1.0e6,
)底盘关节初始位置为 0,JointPositionActionCfg 只包含 joint1–joint6,
PhysX 物理引擎会用极大 stiffness 保持底盘不动,策略无法(也不需要)控制底盘。
注意:底盘虽然锁死但未固定于世界 (
fix_root_link=False)。 臂运动产生的反力矩会导致底盘被动摆动/倾斜,需通过base_motion_penalty和base_tilt终止条件来管理。
v3 架构——三层指数距离奖励,避免单一 sigma 的梯度消失/饱和问题:
| 项目 | 类型 | 公式 | 权重 | 有效范围 |
|---|---|---|---|---|
coarse_distance |
Dense | +5.0 | 远距离引导(~1.5 m 内有梯度) | |
end_effector_distance |
Dense | +4.0 | 中距离精化(~0.5 m 内有梯度) | |
close_proximity |
Dense | +3.0 | 近距离精确(~0.15 m 内有梯度) | |
reaching_success |
Sparse | +15.0 | 每步处于 8 cm 内得 15 分 | |
action_rate |
正则 | −0.005 | 平滑动作 | |
joint_velocity |
正则 | −0.0005 | 抑制高速 | |
base_motion |
正则 | −0.2 | Phase 1 轻惩罚;Phase 2 加至 −1.0 |
三层指数相比单一 Gaussian
$\exp(-d^2/2\sigma^2)$ 的优势:
- 指数函数在
$d=0$ 处有最大梯度$1/\sigma$ ,精度最需要的地方信号最强- 粗/中/细三个 sigma 覆盖从远到近的全距离范围,不存在梯度盲区
- 奖励 bounded in
$[0, \text{weight}]$ ,PPO value 估计稳定
| 条件 | 类型 | 默认参数 | 说明 |
|---|---|---|---|
time_out |
time_out=True | 200 步 (8.0s × 25Hz) | episode 正常结束,保留 bootstrap |
base_tilt |
terminal | max_tilt_rad=0.5 (~29°) | 底盘倾翻立即终止,防止 NaN 物理 |
reaching_success终止函数已定义但未启用(不在MMReachTerminationsCfg中使用)。 到达目标后 episode 仍继续,让策略学会保持在目标位置以持续获得 success bonus。
训练中 PhysX 可能产生 NaN 状态(物体穿透、数值溢出等),本项目实现了完整的四层 NaN 防御:
| 层级 | 位置 | 机制 |
|---|---|---|
| Layer 1: 观测 | observations.py 所有 5 个函数 |
torch.nan_to_num(result, nan=0.0) |
| Layer 2: 奖励 | rewards.py 所有函数 |
NaN 位置 → dist=10.0m 回退;速度 nan_to_num |
| Layer 3: 梯度 | train.py gradient hooks |
所有参数的 NaN/Inf 梯度替换为 zero |
| Layer 4: 分布 | train.py monkey-patch |
ActorCritic.update_distribution 的 log_std 原位修复 + clamp [-14, 1] |
| 量 | 维度 | 函数 | clip |
|---|---|---|---|
| 臂关节位置 (相对 home) | 6 | joint_pos_rel |
±5.0 |
| 臂关节速度 (相对默认) | 6 | joint_vel_rel |
±5.0 |
| EE→target 向量 (世界坐标) | 3 | ee_pos_relative_to_target |
±5.0 |
| 目标位置 (base_link 坐标) | 3 | target_pos_in_robot_frame |
±5.0 |
| 目标四元数 (base_link 坐标) | 4 | target_quat_in_robot_frame |
±5.0 |
| 合计 | 22 |
每个
ObservationTermCfg上单独设置clip=(-5.0, 5.0)。 启用empirical_normalization=True,自动归一化运行统计。
所有命令均须在已激活
env_isaaclab的终端中执行,并已安装rm_tasks。
# 基础训练(4096 并行环境,无界面,3000 次迭代)
python scripts/train.py --task MMRobot-Reach-v0 --headless --max_iterations 3000
# 或通过 isaaclab.bat 启动
..\IsaacLab\isaaclab.bat -p scripts\train.py --task MMRobot-Reach-v0 --headless --num_envs 4096 --max_iterations 3000
# GPU 内存不足时减少 env 数
python scripts/train.py --task MMRobot-Reach-v0 --num_envs 1024 --headless --max_iterations 5000
# 续训(从最新 checkpoint 继续,用于 Phase 2 切换)
python scripts/train.py --task MMRobot-Reach-v0 --resume --headless日志和 checkpoint 保存到:logs/rsl_rl/mmrobot_reach/<timestamp>/
tensorboard --logdir logs/rsl_rl/mmrobot_reach关键指标含义:
Train/mean_reward:每 episode 总回报均值Episode_Reward/reaching_success:每 episode 在 8cm 成功阈值内的步数 × 15.0Episode_Reward/coarse_distance:远距离引导奖励的 episode 总和Train/mean_episode_length:平均 episode 长度(被 base_tilt 终止 → 偏短)
# 用 16 个 env 做可视化预览
python scripts/play.py --task MMRobot-Reach-v0 --num_envs 16 \
--checkpoint logs/rsl_rl/mmrobot_reach/<run>/model_3000.pt
# 用 4 个 env 方便截图
python scripts/play.py --task MMRobot-Reach-v0 --num_envs 4 \
--checkpoint <path>
play.py使用OnPolicyRunner+runner.load(checkpoint)加载权重, 自动处理 obs dict / obs groups / empirical normalization 等。RslRlVecEnvWrapper.step()返回 4 个值(obs, rewards, dones, extras)。
编辑 reach_params.py:
NUM_ENVS_TRAIN: int = 2048 # 改这里
NUM_ENVS_PLAY: int = 8 # 改这里重新运行时自动生效,无需重新安装(editable install)。
所有可调参数均集中在一个文件:
source/rm_tasks/rm_tasks/tasks/reach/reach_params.py
| 参数 | 当前值 | 说明 | 调整建议 |
|---|---|---|---|
NUM_ENVS_TRAIN |
4096 | 训练时并行 env 数 | GPU OOM → 减半;RTX 4090 可开到 4096 |
NUM_ENVS_PLAY |
16 | 预览时并行 env 数 | 方便截图可改 4;想看满屏改 64 |
SIM_DT |
0.01 s | PhysX 步长(100 Hz) | 不建议改;改后须重新调 PD 增益 |
DECIMATION |
4 | 策略每 N 物理步执行一次 | 降低 → 更高控制频率(更难训练) |
EPISODE_LENGTH_S |
8.0 s | episode 时长(200 步) | 臂较慢时加长;成功率高后可缩短 |
ENV_SPACING |
2.5 m | env 间距 | 机器人更大时需增大,避免碰撞拼接 |
目标在 OXYZ 装配坐标系中采样,OXYZ 原点 O 在 base_link 前方 0.25 m。
| 参数 | 当前值 | 含义 | 实际 base_link 距离 |
|---|---|---|---|
BASE_X_MIN/MAX |
0.30 / 0.50 m | OXYZ 深度范围 | X: 0.55 ~ 0.75 m |
BASE_Y_MIN/MAX |
−0.10 / 0.10 m | OXYZ 水平偏移 | Y: ±0.10 m |
BASE_Z_MIN/MAX |
0.20 / 0.55 m | OXYZ 高度范围 | Z: 0.20 ~ 0.55 m |
THETA_MIN/MAX |
−π/2 / π/2 | 水平偏角(方位角) | |
PHI_MIN/MAX |
0 / π/2 | 仰角(0=平推,π/2=俯冲) | |
ALPHA_MIN/MAX |
−π/4 / π/4 | 末端自转(roll 容差) |
目标距离 base_link 最远约
$\sqrt{0.75^2+0.10^2+0.55^2} \approx 0.94$ m, 在臂最大可达半径 ~0.97 m 范围内,确保所有目标均可物理到达。
| 参数 | 当前值 | 说明 |
|---|---|---|
SUCCESS_THRESHOLD_M |
0.08 m | EE 与目标距离 < 8 cm 视为成功 |
训练初期可放宽到 0.10 m,收敛后可收紧到 0.05 或 0.03 m。
| 参数 | 当前值 | 调整方向 |
|---|---|---|
REWARD_COARSE_DIST_WEIGHT |
5.0 | 粗引导,sigma=0.50 m |
REWARD_COARSE_DIST_SIGMA |
0.50 m | 增大 → 更远处有信号 |
REWARD_DISTANCE_WEIGHT |
4.0 | 中程精化,sigma=0.15 m |
REWARD_DISTANCE_SIGMA |
0.15 m | |
REWARD_CLOSE_BONUS_WEIGHT |
3.0 | 近程精调,sigma=0.05 m |
REWARD_CLOSE_BONUS_SIGMA |
0.05 m | |
REWARD_SUCCESS_WEIGHT |
15.0 | 每步在阈值内的 bonus(最大奖励项) |
REWARD_ACTION_RATE_WEIGHT |
−0.005 | 增大绝对值 → 更平滑动作 |
REWARD_JOINT_VEL_WEIGHT |
−0.0005 | 增大绝对值 → 更低速 |
REWARD_BASE_MOTION_WEIGHT |
−0.2 | Phase 1: 轻惩罚;Phase 2 改为 −1.0 |
REWARD_BASE_LIN_VEL_SCALE |
1.0 | base 线速度归一化 (m/s) |
REWARD_BASE_ANG_VEL_SCALE |
0.5 | base 角速度归一化 (rad/s) |
在 robot_cfg.py 中配置:
"arm_joints": ImplicitActuatorCfg(
effort_limit=87.0,
velocity_limit=2.175,
stiffness={"joint1": 80, "joint2": 80, "joint3": 60, "joint4": 40, "joint5": 30, "joint6": 20},
damping= {"joint1": 8, "joint2": 8, "joint3": 6, "joint4": 4, "joint5": 3, "joint6": 2},
)关键约束:effort_limit / stiffness = PD 控制器不饱和的最大误差角度。
当前 87/80 = 1.09 rad (62°),正常运动范围内不会饱和。
⚠️ 若stiffness远大于effort_limit(如 stiffness=120, effort=40), 饱和角仅 0.33 rad (19°),策略微小误差即触发力矩截断,导致 bang-bang 控制和震荡。
stiffness增大 → 响应更快,但注意饱和约束damping增大 → 更平稳,响应稍慢- 经验比例:
damping ≈ stiffness / 10
在 scripts/train.py 中 _build_runner_cfg() 函数里修改:
| 参数 | 当前值 | 说明 |
|---|---|---|
num_steps_per_env |
24 | rollout 长度;增大 → 更好的 advantage 估计 |
num_learning_epochs |
5 | 每次 rollout 重复学习次数 |
learning_rate |
3e-4 | 初始学习率;"adaptive" 调度自动调整 |
clip_param |
0.2 | PPO clip 系数 |
entropy_coef |
0.02 | 熵正则;增大 → 更多探索 |
gamma |
0.99 | 折扣因子 |
lam |
0.95 | GAE lambda |
max_grad_norm |
1.0 | 梯度裁剪范数 |
init_noise_std |
0.3 | 初始探索噪声标准差 |
noise_std_type |
"log" | 对数空间参数化(防止 std < 0) |
empirical_normalization |
True | 自动归一化观测统计 |
actor_hidden_dims |
[256, 128, 64] | Actor 网络隐藏层 |
critic_hidden_dims |
[256, 128, 64] | Critic 网络隐藏层 |
activation |
"elu" | 激活函数 |
由于底盘不固定,臂的运动会引起底盘被动位移。为避免底盘惩罚干扰到达学习, 采用两阶段训练策略:
REWARD_BASE_MOTION_WEIGHT = -0.2 # 轻惩罚,不影响臂学习目标:策略学会可靠地到达目标点。
切换到 Phase 2 的判据(以 TensorBoard 为准):
| 指标 | 阈值 | 含义 |
|---|---|---|
mean_reward |
> 2500 且稳定 200+ iteration | 手臂可靠到达多数目标 |
Episode_Reward/reaching_success |
> 1200 | 平均每 episode 在 8cm 内停留 80+ 步 |
| 奖励曲线形态 | 连续 200+ iteration 无大幅升降 | 已收敛到平台期 |
理论分析:
- 每步理论最大奖励 = 5+4+3+15 = 27.0
- Episode 长度 200 步,理论最大 return = 5400
- 手臂约 40-80 步到达目标,剩余 120-160 步保持 → 预期 return 约 3000-4000
- 阈值 2500 代表手臂能到达大部分目标并维持一段时间
三步操作:
# 1. 修改 reach_params.py
REWARD_BASE_MOTION_WEIGHT = -1.0 # 强惩罚
# 2. 续训(从 Phase 1 checkpoint 继续)
python scripts/train.py --task MMRobot-Reach-v0 --resume --headless --max_iterations 5000
# 3. 监控 TensorBoard
tensorboard --logdir logs/rsl_rl/mmrobot_reach预期行为:
- 切换后
mean_reward会短暂下降(底盘惩罚增大) - 约 500-1000 iteration 后策略学会更轻柔的运动策略
Episode_Reward/base_motion的绝对值显著下降reaching_success保持或略降但不崩溃
- 收紧成功阈值:
SUCCESS_THRESHOLD_M从 0.08 → 0.05 → 0.03 - 扩大目标范围:逐步增大
BASE_X/Y/Z范围到完整 C 级规范(注意不超过臂可达半径 0.97 m) - 缩短 episode:
EPISODE_LENGTH_S从 8.0 → 5.0(促进更快到达)
# 使用训练好的 checkpoint 推理
python scripts/play.py --task MMRobot-Reach-v0 --num_envs 16 \
--checkpoint <path/to/model_xxx.pt>若要在没有 checkpoint 的情况下只看环境,可临时修改 play.py:
# 替换 policy(obs) 为零动作
actions = torch.zeros(env.num_envs, 6, device=env.device)- 机器人在地面上正常生成,不穿模
- 底盘基本静止(锁死正常,但允许微小被动运动)
- 红色球标记(target_marker)在机械臂前方可达区域内出现
- 每次 reset 后目标位置随机变化
-
FrameTransformer显示末端坐标符合常识 - 底盘倾翻时 episode 正确终止
Q: ImportError: cannot import name ...
A: 确认 Isaac Lab 2.2.1 — 包名为 isaaclab / isaaclab_tasks / isaaclab_rl,不是 omni.isaac.lab。
Q: USD not found: MyArm/my_arm.usd
A: 需先运行 URDF 转换器(见 2. 环境配置)生成 USD 文件。
Q: 训练时 GPU OOM
A: 减小 reach_params.py 中的 NUM_ENVS_TRAIN,从 1024 开始递增。
Q: AppLauncher 必须第一个 import
A: train.py 和 play.py 中所有 omni.* import 都在 app_launcher = AppLauncher(args) 之后,这是 Isaac Lab 硬性要求,不能修改顺序。
以下是开发过程中遇到并解决的关键技术问题:
1. RuntimeError: std < 0 崩溃
- 原因:rsl_rl 的
noise_std_type="scalar"模式下 std 参数可能通过梯度下降变为负值 - 解决:改为
noise_std_type="log"(对数空间参数化),并在train.py中 monkey-patchActorCritic.update_distribution,加入nan_to_num+clamp(-14, 1)双重保护
2. NaN 梯度导致权重损坏
- 原因:PhysX 在碰撞/穿透时产生 NaN 状态,传播到 loss → 梯度 → 权重
- 解决:四层 NaN 防御(见 4.7 节)
3. 底盘倾翻
- 原因:
fix_root_link=False时,臂的 effort_limit=87Nm 反力矩超过底盘抗翻力矩 - 解决:添加
base_tilt终止条件(倾斜 > 29° 终止)+base_motion_penalty惩罚底盘运动
4. PD 控制器饱和导致 bang-bang 震荡
- 原因:
effort_limit / stiffness过小时(如 40/120=0.33 rad),关节误差 > 19° 即饱和,PD 输出恒为 ±effort_limit → bang-bang 控制 - 解决:确保
effort_limit / stiffness > 1.0 rad,当前 87/80=1.09 rad
5. 目标物理不可达
- 原因:目标采样范围超过臂最大可达半径(旧范围最远约 1.17 m > 臂 0.97 m)
- 解决:缩小目标范围,使最远目标约 0.94 m < 0.97 m
6. 单一 sigma 的梯度盲区
- 原因:Gaussian
$\exp(-d^2/2\sigma^2)$ 在$d \gg \sigma$ 时梯度为 0;单一指数$\exp(-d/\sigma)$ 在$\sigma=0.1$ 时 0.57m 处梯度仅 3e-3 - 解决:采用三层 sigma(0.50/0.15/0.05)覆盖全距离范围
7. play.py 加载 checkpoint 崩溃
- 原因:rsl_rl 新版
ActorCritic.__init__接收(obs, obs_groups, num_actions)dict 格式,直接实例化无法匹配 - 解决:使用
OnPolicyRunner+runner.load(checkpoint)加载,自动处理参数匹配
8. ObservationGroupCfg 上设置 clip 报错
- 原因:
clip属性只能放在ObservationTermCfg上,不能放在ObservationGroupCfg上 - 解决:将
clip=(-5.0, 5.0)移到每个ObservationTermCfg
9. RslRlVecEnvWrapper.step() 返回值数量
- 原因:
step()返回 4 个值(obs, rewards, dones, extras),而非 gymnasium 的 5 元组 - 解决:
obs, _, dones, _ = env.step(actions)