flowchart LR AG["에이전트 (정책 πθ)"] -->|"행동 a"| EN["환경 (IsaacLab)"] EN -->|"보상 r, 다음 상태 s'"| AG classDef ag fill:#e8f5e9,stroke:#2e7d32,stroke-width:2px; classDef en fill:#e3f2fd,stroke:#1565c0,stroke-width:2px; class AG ag; class EN en;
PPO & Actor-Critic — 보행 정책 학습
DreamWaQ on IsaacLab — 2차시
강의 로드맵
| 회차 | 주제 |
|---|---|
| 1차시 | 4족 보행 로봇 & IsaacLab 환경 구성 |
| 2차시 (오늘) | PPO & Actor-Critic — 보행 정책 학습 |
| 3차시 | VAE & DreamWaQ — 지형 인식 없이 걷기 (CENet) |
| 4차시 | Gazebo Sim2Sim — 배포 전 검증 |
1차시 환경 위에서, 로봇이 명령 속도로 걷도록 정책을 학습시킵니다. 알고리즘은 PPO, 라이브러리는 rsl_rl입니다.
- 강화학습의 기본 개념부터 PPO-clip과 GAE를 직관으로 이해한다.
- DreamWaQ의 PPO 설정(
rsl_rl_ppo_cfg.py)을 코드로 읽는다. - 롤아웃→갱신 학습 루프와 실행 명령을 따라간다.
이 강의는 강화학습이 처음이어도 따라올 수 있게 직관 → 비유 → 수식 순서로 풉니다. 수식의 모든 기호는 바로 옆에서 풀어 설명합니다.
1. 강화학습과 PPO — 직관부터
강화학습이 뭔가요?
강화학습(RL)은 시행착오로 배우는 방식입니다. 강아지에게 간식으로 “앉아”를 가르치듯, 로봇 (에이전트)이 환경에서 여러 행동을 해 보고, 잘했을 때 보상을 받으며 점점 더 나은 행동을 익힙니다. 지도학습처럼 정답 라벨이 주어지는 게 아니라, 오직 보상이라는 점수만 있습니다.
매 순간 아래 고리가 돕니다 — 로봇이 상태(관측)를 보고 → 행동하면 → 환경이 보상과 다음 상태를 돌려줍니다. 이 고리를 수없이 반복하며 “어떤 상황에서 어떤 행동을 하면 점수가 큰지”를 배웁니다.
정책 · 가치 · 어드밴티지
학습의 주인공인 정책(policy) \pi_\theta는 “상황을 보고 행동을 고르는 전략”입니다 (\theta는 신경망 파라미터). 걷기처럼 행동이 연속값일 때는 하나의 값이 아니라 확률분포를 출력합니다 — 가우시안(정규분포)으로 평균 \mu_\theta(s)와 표준편차 \sigma를 냅니다.
\pi_\theta(a\mid s)=\mathcal{N}\big(\mu_\theta(s),\,\sigma^2\big)
쉽게 말하면 — \mu는 “지금 상황에서 내 최선의 행동”, \sigma는 “얼마나 모험을 해 볼지”입니다. \sigma가 크면 다양한 행동을 시도(탐험)하고, 학습이 끝나갈수록 작아지며 확신에 찬 행동을 합니다.
행동을 평가하려면 두 개념이 더 필요합니다.
- 가치 V(s) — “이 상황은 앞으로 받을 보상까지 따지면 얼마나 좋은가”. 즉 상황의 점수.
- 어드밴티지 A(s,a)=Q(s,a)-V(s) — “그 상황에서 이 행동이 평균보다 얼마나 더 좋았나”. A>0이면 평소보다 잘한 행동, A<0이면 못한 행동. 이 값이 학습의 방향키입니다.
정책을 어떻게 개선하나 — 그리고 PPO가 푸는 문제
기본 아이디어는 한 문장입니다: 어드밴티지가 양수였던 행동은 더 자주, 음수였던 행동은 덜 하도록 정책을 살짝 민다. 문제는 얼마나 미느냐입니다. 한 번의 경험으로 정책을 너무 크게 바꾸면 학습이 무너집니다.
비유 — 한 판 이겼다고 전략을 통째로 갈아엎으면, 그게 운이었을 때 다음 판을 망칩니다. 조금씩 신중하게 바꿔야 합니다.
PPO는 이 “조금씩”을 강제합니다. 새 정책이 옛 정책보다 그 행동을 몇 배 더(혹은 덜) 하려는지를 확률비 r_t로 재고, 이 비율이 [1-\epsilon,\,1+\epsilon]를 벗어나면 더 이상 이득을 주지 않도록 잘라(clip) 버립니다. 즉 “한 번에 ε(=20%)까지만 바꿔”라는 안전벨트입니다.
r_t(\theta)=\frac{\pi_\theta(a_t\mid s_t)}{\pi_{\theta_{old}}(a_t\mid s_t)}, \qquad L^{CLIP} = \mathbb{E}\Big[\min\big(r_t A_t,\ \text{clip}(r_t, 1-\epsilon, 1+\epsilon)\,A_t\big)\Big]
기호 풀이 — r_t: 새/옛 정책의 확률비(1이면 그대로, 1.2면 20% 더 하려 함), \mathbb{E}[\cdot]: 모은 경험들의 평균, \text{clip}(\cdot): 값을 범위 안으로 가두는 함수, \epsilon=0.2: 허용 폭.
아래 그래프로 직접 확인해 보세요. 확률비 r_t가 clip 구간을 벗어나면 목적함수가 평평해져 (기울기 0 → 더 못 바뀜) 정책이 한 번에 크게 변하지 못합니다. 어드밴티지 부호와 \epsilon을 바꿔가며 회색 구간 밖에서 곡선이 꺾이는 지점을 보세요.
실선 = clip 목적함수 LCLIP, 점선 = clip 없는 r·A, 회색 띠 = clip 구간
어드밴티지는 어떻게 구하나 — GAE
앞서 어드밴티지가 방향키라고 했는데, “이 행동 덕분에 미래 보상이 평균보다 나았나”는 미래가 불확실해 추정하기 까다롭습니다. GAE는 한 스텝만 내다보는 추정(편향 적음·노이즈 큼)과 끝까지 보는 추정(노이즈 적음·편향 큼) 사이를 \lambda로 절충합니다.
먼저 한 스텝의 “예상보다 좋았던 정도”인 TD 잔차 \delta_t를 정의하고, 이를 미래로 갈수록 점점 작게 가중해 더합니다.
\delta_t = r_t + \gamma V(s_{t+1}) - V(s_t), \qquad \hat A_t = \sum_{l\ge 0}(\gamma\lambda)^l\,\delta_{t+l}
기호 풀이 — \delta_t: 받은 보상 + 다음 상황 가치가 현재 가치보다 얼마나 컸나(=예상 대비 깜짝 정도), \gamma=0.99: 할인율(먼 미래 보상일수록 덜 중요하게), \lambda=0.95: 편향-노이즈 절충 손잡이.
최종 손실 — 세 가지를 함께
PPO가 실제로 최소화하는 손실은 세 조각의 합입니다.
L = \underbrace{L^{CLIP}}_{\text{① 정책 개선}}\;-\;c_1\underbrace{L^{VF}}_{\text{② 가치 정확도}}\;+\;c_2\underbrace{S[\pi_\theta]}_{\text{③ 탐험 유지}}, \qquad c_1=1.0,\ c_2=0.01
- ① L^{CLIP} — 위에서 본 안전한 정책 개선.
- ② L^{VF} — critic이 가치 V(s)를 정확히 맞히게(가치가 정확해야 ①의 어드밴티지도 정확).
- ③ S[\pi_\theta] — 정책의 엔트로피(무작위성) 보너스. 너무 일찍 한 행동만 고집하지 않도록 약간의 탐험을 남겨둠.
이 상수 \epsilon, c_1, c_2, \gamma, \lambda가 코드 설정에 그대로 들어갑니다 — 아래에서 직접 확인합니다.
2. 네트워크 설정 — 코드로 읽기
DreamWaQ는 actor와 critic이 다른 입력을 받는 비대칭 구조이고(1차시), 둘 다 [512,256,128] ELU MLP입니다.
# dreamwaq_manager/.../config/go2/agents/rsl_rl_ppo_cfg.py (Go2BasePPORunnerCfg)
actor = RslRlMLPModelCfg(
hidden_dims=[512, 256, 128],
activation="elu",
obs_normalization=True,
distribution_cfg=RslRlMLPModelCfg.GaussianDistributionCfg(
init_std=1.0,
std_type="log",
),
)
critic = RslRlMLPModelCfg(
hidden_dims=[512, 256, 128],
activation="elu",
obs_normalization=False,
)- 1
-
은닉층 3개
512 → 256 → 128. actor 출력은 12(행동 평균), critic 출력은 1(상태가치). - 2
- actor 입력 정규화 ON — 관측 분포를 표준화해 학습 안정화 (단, Waq는 3차시에서 Identity로 교체).
- 3
- 가우시안 정책의 초기 표준편차 \sigma=1.0 — 초기 탐험 폭.
- 4
- \sigma를 log 스케일로 파라미터화 → 항상 양수 보장, 수치 안정.
- 5
- critic은 정규화 OFF (Base). 입력이 특권 관측이라 분포가 안정적.
| Actor | Critic | |
|---|---|---|
| 입력 (Base / Oracle / Waq) | 45 / 48 / 64 | — / 238 / 235 |
| 출력 | 12 (행동 평균) | 1 (가치) |
flowchart LR O1["Actor 관측<br/>45 / 48 / 64"] --> AM["MLP 512·256·128 ELU"] --> MU["평균 μ (12)"] --> DI["𝒩(μ, σ²)"] --> ACT(["행동 (12)"]) O2["Critic 관측<br/>238 / 235 (특권)"] --> CM["MLP 512·256·128 ELU"] --> V(["가치 V (1)"]) V -. "GAE 어드밴티지" .-> AM classDef a fill:#e8f5e9,stroke:#2e7d32; classDef c fill:#fce4ec,stroke:#c2185b; class O1,AM,MU,DI,ACT a; class O2,CM,V c;
왜 비대칭인가? critic은 학습 중에만 쓰이므로 지형·외란 같은 특권 정보로 정확한 가치를 추정 → 더 좋은 어드밴티지 → actor 학습 가속. actor는 배포 가능한 관측만 받습니다.
3. PPO 알고리즘 설정 — 코드로 읽기
§1의 수식 상수들이 그대로 설정에 들어갑니다.
# rsl_rl_ppo_cfg.py (Go2BasePPORunnerCfg.algorithm)
algorithm = RslRlPpoAlgorithmCfg(
clip_param=0.2,
value_loss_coef=1.0,
use_clipped_value_loss=True,
entropy_coef=0.01,
gamma=0.99,
lam=0.95,
num_learning_epochs=5,
num_mini_batches=4,
learning_rate=1.0e-3,
schedule="adaptive",
desired_kl=0.01,
max_grad_norm=1.0,
)- 1
- \epsilon=0.2 — L^{CLIP}의 clip 범위.
- 2
- c_1=1.0 — 가치손실 가중치. clipped value loss도 사용.
- 3
- c_2=0.01 — 엔트로피 보너스(탐험 유지).
- 4
- \gamma=0.99, \lambda=0.95 — GAE 상수.
- 5
- 한 롤아웃을 5 epoch × 4 mini-batch로 재사용해 갱신.
- 6
-
KL 기반 adaptive 학습률: 측정한 KL이
desired_kl=0.01보다 너무 크면 lr↓, 너무 작으면 lr↑. 안정적이면서 빠른 학습. - 7
- 그래디언트 노름을 1.0으로 클리핑 → 폭주 방지.
clip_actions = 1.0: std가 큰 정책은 ±10 이상 행동을 내 관절 한계를 벗어나고 극단적 PD 토크로 학습이 붕괴합니다. wrapper 레벨에서 ±1로 자릅니다. Direct는 1차시 _pre_physics_step의 clamp(-1.0, 1.0)으로 같은 일을 합니다.
4. 학습 루프 — 코드로 읽기
OnPolicyRunner.learn()은 롤아웃 수집 → 어드밴티지 계산 → PPO 갱신을 반복합니다. 한 반복의 골격은 다음과 같습니다.
- 1
- 롤아웃 수집: 24스텝 동안 4096개 환경에서 전이를 모음 (스텝당 4096개 샘플).
- 2
- actor가 현재 관측에서 행동을 샘플(가우시안에서 추출).
- 3
-
환경 한 스텝 진행 — 1차시의
_pre_physics_step→물리→_get_rewards→_get_observations흐름. - 4
- 전이를 storage에 기록하고 관측 정규화 통계를 갱신.
- 5
- 롤아웃 종료 후 GAE로 어드밴티지·리턴 계산(§1 수식).
- 6
- PPO 갱신: 5 epoch × 4 mini-batch로 L = L^{CLIP} - c_1 L^{VF} + c_2 S 최소화.
flowchart LR S(["관측"]) --> ACT["actor.act<br/>행동 샘플"] --> ENV["env.step<br/>(4096 병렬)"] --> ST["전이 저장"] ST -->|"24스텝 미만: 반복"| ACT ST -->|"24스텝 완료"| GAE["compute_returns<br/>(GAE)"] --> UPD["update<br/>5ep × 4mb"] --> S classDef hot fill:#fff3e0,stroke:#f57c00; class GAE,UPD hot;
Base/Oracle은 이 표준 runner를, Waq는 CENet을 통합한 커스텀 runner를 씁니다. 교체는 설정 한 줄로 끝납니다.
- 1
-
표준
OnPolicyRunner대신 CENet 통합 runner 사용 (3차시). - 2
- CENet까지 학습하므로 더 긴 5000 iters.
- 3
- CENet에 넘길 설정 — 관측 히스토리 5스텝, AdaBoot 사용.
- 4
- VAE 하이퍼파라미터 — 3차시에서 자세히.
5. 실행 — 학습과 평가
태스크 ID만 바꾸면 Manager/Direct, Base/Oracle/Waq 모두 같은 스크립트로 학습합니다.
# 학습 (헤드리스, 기본 4096 envs)
python train.py --task=DreamWaQ-Manager-Go2-Base-v0 --headless
# 빠른 스모크 테스트
python train.py --task=DreamWaQ-Manager-Go2-Base-v0 --headless --num_envs=64 --max_iterations=100
# wandb 로깅 / 이어서 학습
python train.py --task=DreamWaQ-Manager-Go2-Base-v0 --headless --logger=wandb
python train.py --task=DreamWaQ-Manager-Go2-Base-v0 --headless \
--resume --load_run=FOLDER_NAME --checkpoint=NUMBER
# 평가 (GUI로 50개 환경)
python play.py --task=DreamWaQ-Manager-Go2-Base-Play-v0 \
--load_run=FOLDER_NAME --checkpoint=model_500.ptDirect는 ID만 DreamWaQ-Direct-Go2-Base-v0로 — PPO 설정·학습 스크립트는 동일합니다.
- 환경 수: 기본 4096 (RTX 4080 16GB 안정), 8192는 OOM 위험.
- log_std 클램프
[-5, 2]→ std[0.007, 7.4]: 긴 학습에서 std 폭주 방지(Waq runner가 강제). - 학습 시간: Base/Oracle 1500 iters ≈ 수 시간, Waq 5000 iters ≈ 10시간+.
6. 핵심 정리
- PPO-Clip(\epsilon=0.2)이 확률비를 잘라 안정적으로 갱신하고, GAE(\gamma=0.99,\lambda=0.95)가 어드밴티지를 추정한다.
- 손실 상수 c_1=1.0, c_2=0.01이
algorithm설정에 그대로 들어간다. - 비대칭 actor-critic
[512,256,128]ELU — log-std, adaptive LR, 행동 클램프가 안정성의 핵심. - 학습 루프는 롤아웃(24스텝) → GAE → 5ep×4mb 갱신의 반복. Waq만 runner를 교체한다.
actor는 아직 선속도도 지형도 모릅니다. 고유수용성 히스토리만으로 이를 추정하는 CENet(VAE) 의 forward/update와, 관측을 45→64로 증강하는 runner 루프를 코드로 따라갑니다.