Gazebo Sim2Sim — 배포 전 검증

DreamWaQ on IsaacLab — 4차시

Author

JungYeon Lee

Published

March 26, 2026

강의 로드맵

회차 주제
1차시 4족 보행 로봇 & IsaacLab 환경 구성
2차시 PPO & Actor-Critic — 보행 정책 학습
3차시 VAE & DreamWaQ — 지형 인식 없이 걷기 (CENet)
4차시 (오늘) Gazebo Sim2Sim — 배포 전 검증

IsaacLab에서 학습한 정책을 실로봇에 올리기 전, 다른 물리엔진(Gazebo)에서 검증합니다. 정책 추론 노드의 코드를 직접 짚으며 봅니다.

Tip오늘의 목표
  1. Sim2Sim 검증의 의미를 짧게 짚는다.
  2. 체크포인트 로딩과 추론 노드를 코드로 읽는다.
  3. 관절 순서 매핑(가장 흔한 버그)과 다중 주파수 제어를 따라간다.

1. Sim2Sim이란

시뮬레이터마다 물리엔진이 다릅니다 — IsaacLab은 PhysX(GPU), Gazebo는 ODE/CPU. 학습과 다른 엔진에서도 정책이 걷는다면, 특정 시뮬레이터에 과적합되지 않았다는 신호입니다.

\text{IsaacLab (PhysX)} \longrightarrow \text{Gazebo (ODE)} \longrightarrow \text{실로봇}

3차시까지의 도메인 randomization이 이 격차를 견디게 한 준비였습니다. 배포는 별도 저장소 quadruped_sim2sim의 ROS2 패키지로, 토픽 흐름은:

flowchart LR
  UI["robot_UI<br/>(PyQt5)"] -->|"/robot_velocity_command"| RC["robot_controller<br/>(정책 추론)"]
  RC -->|"/joint_effort_controller/commands"| GZ["Gazebo"]
  GZ -->|"/joint_states<br/>/imu_plugin/out"| RC
  classDef ui fill:#e8eaf6,stroke:#3949ab; classDef rc fill:#fff3e0,stroke:#f57c00; classDef gz fill:#e0f2f1,stroke:#00897b;
  class UI ui; class RC rc; class GZ gz;
Figure 1: ROS2 토픽 흐름 — UI 명령과 센서를 받아 정책이 토크를 발행한다
패키지 역할
robot_controller 정책 추론 노드
robot_description URDF/xacro, 메시
robot_gazebo Gazebo launch, ros2_control
robot_UI PyQt5 속도 명령 GUI

2. 정책 로더 — 학습 산출물을 배포 형식으로

3차시 체크포인트(model_*.pt)에는 actor와 CENet이 함께 저장돼 있습니다. 배포엔 인코더 + actor만 필요합니다(디코더 버림, 3차시 §6).

# robot_controller/.../load_dreamwaq_policy_go2.py
class CENet(nn.Module):
    def __init__(self, input_dim=225, latent_dim=19):
        self.encoder = nn.Sequential(
            nn.Linear(input_dim, 128), nn.ELU(),
            nn.Linear(128, 64),        nn.ELU(),
            nn.Linear(64, 3 + 32),                     # est_vel(3)+mu(16)+logvar(16)
        )
    def inference(self, obs_history_225):
        h = self.encoder(obs_history_225)
        est_vel = h[:, :3]
        mu = h[:, 3:3 + 16]
        return torch.cat([est_vel, mu], dim=-1)
1
학습(3차시)과 동일한 인코더 구조 — 가중치를 그대로 올리려면 구조가 일치해야 함.
2
추론 시엔 mu만 사용 — 재매개화 샘플링 없이 평균값(결정적).
3
[est_vel(3), mu(16)] = 19. logvar는 추론에 불필요해 버림.

체크포인트에서 필요한 가중치만 골라 로딩합니다. 학습 키 이름을 배포 모델 키로 변환하는 점이 핵심입니다.

# load_learned_models
checkpoint = torch.load(pt_file, map_location='cpu', weights_only=False)
filtered_enc = {k: v for k, v in checkpoint['cenet_state_dict'].items()
                if k.startswith('encoder.')}
cenet.load_state_dict(filtered_enc, strict=False)
actor_sd = {k.replace('actor.', 'mlp.'): v
            for k, v in checkpoint['model_state_dict'].items() if k.startswith('actor.')}
actor.load_state_dict(actor_sd, strict=False)
1
학습 체크포인트 로드 (actor + CENet + 옵티마이저 상태 등 포함).
2
CENet에서 인코더 가중치만 추출(디코더 제외).
3
actor 가중치 키 actor.* → 배포 모델 키 mlp.*이름 변환 후 로딩.
flowchart LR
  CKPT["model_5000.pt"] --> A["cenet_state_dict"] -->|"encoder.* 만"| CE(["배포 CENet 인코더"])
  CKPT --> B["model_state_dict"] -->|"actor.* → mlp.*"| AC(["배포 Actor"])
  CE --> INF["추론<br/>64 → 행동 12"]
  AC --> INF
  classDef out fill:#e8f5e9,stroke:#2e7d32; class CE,AC out;
Figure 2: 체크포인트에서 배포에 필요한 가중치만 골라 이름을 바꿔 올린다

3. 관절 순서 매핑 — 가장 흔한 버그

Important넘어짐의 1순위 원인

IsaacLab과 Gazebo는 관절을 다른 순서로 나열합니다. Gazebo는 보통 URDF 알파벳 순으로 /joint_states를 발행하지만, 정책은 학습 순서(FL→FR→RL→RR, 각 다리 hip→thigh→calf)를 기대합니다. 어긋나면 즉시 넘어집니다.

flowchart LR
  G["Gazebo /joint_states<br/>(URDF 알파벳 순)<br/>FL_calf, FL_hip, FL_thigh, …"] --> M{{"이름 기반 매핑<br/>name → index<br/>_joint_map"}}
  M --> P["정책 기대 순서<br/>(FL→FR→RL→RR, hip→thigh→calf)<br/>FL_hip, FL_thigh, FL_calf, …"]
  classDef bad fill:#ffebee,stroke:#c62828; classDef good fill:#e8f5e9,stroke:#2e7d32; classDef map fill:#fff3e0,stroke:#f57c00;
  class G bad; class P good; class M map;
Figure 3: 관절 순서 불일치 — 이름 기반 매핑으로 항상 정책 순서로 재배열

해결: 관절 이름으로 인덱스 매핑을 만들어 항상 정책 순서로 재배열합니다.

# joint_state_callback
expected_order = [
    'FL_hip_joint', 'FL_thigh_joint', 'FL_calf_joint',
    'FR_hip_joint', 'FR_thigh_joint', 'FR_calf_joint',
    'RL_hip_joint', 'RL_thigh_joint', 'RL_calf_joint',
    'RR_hip_joint', 'RR_thigh_joint', 'RR_calf_joint',
]
name_to_idx = {name: i for i, name in enumerate(msg.name)}
self._joint_map = [name_to_idx[name] for name in expected_order]
self.dof_pos = torch.tensor([[msg.position[i] for i in self._joint_map]])
1
정책이 기대하는 표준 순서(1차시 default_dof_pos와 동일).
2
Gazebo 메시지의 name → index 사전을 만듦 — 발행 순서가 무엇이든 안전.
3
정책 순서 → Gazebo 인덱스 매핑 배열 생성.
4
매핑으로 재배열해 항상 정책 순서로 정렬. 속도(dof_vel)도 동일하게 처리.

4. 관측 재구성 & 추론 — 코드로 읽기

배포 노드는 1차시의 45차원 관측을 똑같이 재조립해야 합니다. 차원·순서·스케일이 학습과 어긋나면 정책이 헛돕니다.

# build_obs_45 — 1차시 actor 관측과 동일 구성
return torch.cat([
    self.base_ang_vel,
    self.projected_gravity,
    self.commands,
    self.dof_pos - self.default_dof_pos,
    self.dof_vel,
    self.actions,
], dim=-1)
1
IMU 각속도(3).
2
IMU 자세에서 계산한 중력 방향(3).
3
UI 속도 명령(3).
4
관절각을 기본자세 상대값으로(1차시와 동일).
5
직전 행동(12). 합쳐서 45차원 — 학습과 한 치도 달라선 안 됨.

추론은 3차시 흐름 그대로입니다.

# control_loop — 정책 추론 (50Hz)
obs_45 = self.build_obs_45()
self.update_ring_buffer(obs_45)
obs_history_225 = self.obs_history_buf.reshape(1, -1)
latent_19   = self.cenet.inference(obs_history_225)
actor_obs   = torch.cat([obs_45, latent_19], dim=-1)
raw_actions = self.actor.act_inference(actor_obs)
self.q_des  = self.default_dof_pos + raw_actions * self.action_scale
1
5스텝 링 버퍼에 최신 관측 추가.
2
평탄화 → 225 (3차시 CENet 입력).
3
CENet 인코더 추론 → [est_vel, mu] = 19.
4
actor 입력 64 = 45 + 19 (3차시 증강과 동일).
5
목표각 = 기본자세 + scale·행동 (1차시 수식).

5. 다중 주파수 제어 — 200 Hz PD + 50 Hz 정책

1차시 decimation=4처럼, 배포도 정책 50 Hz · PD 200 Hz입니다(4스텝마다 정책 1회).

def control_loop(self):
    if self.counter % 4 == 0:
        ...  # §4 추론으로 self.q_des 갱신
        self.counter = 0
    self.torques = self.Kp * (self.q_des - self.dof_pos) - self.Kd * self.dof_vel
    self.publish_torques(self.torques[0])
    self.counter += 1
1
50 Hz: 4번에 1번만 정책 추론 → 목표각 갱신(무겁다).
2
200 Hz: 매 틱 PD 토크 계산 \tau = K_p(q_{des}-q) - K_d\dot q (1차시 수식). 게인은 학습과 동일하게 K_p=20, K_d=0.5.
self.Kp = 20.0; self.Kd = 0.5; self.action_scale = 0.25   # 학습 설정과 동일해야 함

6. 실행과 트러블슈팅

colcon build && source install/setup.bash
ros2 launch robot_gazebo go2_gazebo.launch.py                          # Gazebo + 컨트롤러
ros2 run robot_controller load_dreamwaq_policy_go2 --checkpoint model_5000.pt  # 정책 노드
증상 원인 해결
즉시 넘어짐 관절 순서 불일치 이름 기반 매핑 (§3)
미세 떨림 PD 게인 불일치 학습과 동일한 K_p, K_d
제자리 회전 중력 회전 함수 오류 quat_rotate vs quat_rotate_inverse
정책이 헛돔 관측 차원/스케일 불일치 build_obs_45를 1차시와 대조
Note

다른 정책으로 교체하면 관측 구성이 달라집니다 — Walk-These-Ways(gait clock, history 30), HIMLoco(대조학습 잠재) 등. 배포 노드의 build_obs_45와 네트워크 입력 차원을 맞춰야 합니다.


7. 시리즈 마무리

차시 한 줄 요약
1차시 관측(45)·행동(PD)·보상·randomization으로 환경을 만든다
2차시 PPO + 비대칭 actor-critic로 정책을 학습한다
3차시 CENet(VAE)으로 지형 인식 없이 험지를 걷는다 (45→64)
4차시 Gazebo에서 배포 전 검증한다

핵심 흐름이 하나로 이어집니다: 1차시 45차원 관측 → 3차시 CENet 64차원 → 2차시 PPO 학습 → 4차시 다른 엔진 검증.

Tip더 나아가기

VLA 상위 플래너 + DreamWaQ 하위 컨트롤러 같은 확장은 lec/ideas.md에서, 제어 stack의 가장 아래 단일 관절 PD 제어는 1차시 행동 → PD 섹션에서 인터랙티브로 다룹니다.