7.153 STOMP와 확률적 경로 최적화
1. STOMP의 개요
STOMP(Stochastic Trajectory Optimization for Motion Planning)는 칼라카르(Kalakrishnan) 등이 2011년에 제안한 확률적 궤적 최적화 방법이다. CHOMP가 그래디언트를 사용하여 결정론적으로 궤적을 갱신하는 반면, STOMP는 확률적으로 노이즈가 추가된 궤적 샘플들을 생성하고, 각 샘플의 비용을 평가하여 가중 평균으로 궤적을 갱신한다. 이 접근법은 비용 함수의 미분 가능성을 요구하지 않는다.
2. 알고리즘
2.1 궤적의 이산 표현
궤적을 N개의 격자점에서의 관절 자세로 이산화한다.
\boldsymbol{\Theta} = [\boldsymbol{\theta}_1, \boldsymbol{\theta}_2, \ldots, \boldsymbol{\theta}_N] \in \mathbb{R}^{n \times N}
여기서 n은 관절 수이다.
2.2 잡음 궤적 생성
현재 궤적 \boldsymbol{\Theta}로부터 K개의 잡음 궤적을 생성한다.
\boldsymbol{\Theta}_k = \boldsymbol{\Theta} + \boldsymbol{\epsilon}_k, \quad k = 1, \ldots, K
잡음 \boldsymbol{\epsilon}_k는 매끄러운 궤적 변동을 생성하기 위해 공분산 행렬 \mathbf{R}^{-1}을 갖는 다변량 정규 분포에서 샘플링된다.
\boldsymbol{\epsilon}_k \sim \mathcal{N}(\mathbf{0}, \mathbf{R}^{-1})
\mathbf{R}은 유한 차분 가속도 행렬과 관련되며, \mathbf{R}^{-1}에서의 샘플링은 매끄러운 잡음을 생성한다.
2.3 비용 평가
각 잡음 궤적의 각 시각에서 비용을 평가한다.
S(\boldsymbol{\Theta}_k) = \sum_{i=1}^{N} q(\boldsymbol{\theta}_{k,i})
여기서 q(\boldsymbol{\theta})는 상태 비용으로, 장애물 비용, 제약 위반 벌점 등을 포함한다.
2.4 확률적 갱신
각 시각 i에서 잡음 샘플에 대한 가중 평균으로 궤적을 갱신한다.
\delta\boldsymbol{\theta}_i = \frac{\sum_{k=1}^{K} \exp\left(-\frac{1}{\lambda}S_i(\boldsymbol{\Theta}_k)\right)\boldsymbol{\epsilon}_{k,i}}{\sum_{k=1}^{K} \exp\left(-\frac{1}{\lambda}S_i(\boldsymbol{\Theta}_k)\right)}
여기서 \lambda > 0은 온도 매개변수이고, S_i(\boldsymbol{\Theta}_k) = \sum_{j=i}^{N} q(\boldsymbol{\theta}_{k,j})는 시각 i 이후의 누적 비용(cost-to-go)이다.
갱신된 궤적: \boldsymbol{\Theta} \leftarrow \boldsymbol{\Theta} + \delta\boldsymbol{\Theta}
갱신 후 매끄러움 필터를 적용하여 궤적의 연속성을 유지한다.
3. 확률적 최적 제어와의 연결
STOMP는 경로 적분 최적 제어(path integral optimal control, PI²) 프레임워크에 기반한다. 확률적 최적 제어 이론에서 최적 제어 입력은 잡음 궤적의 비용에 의한 지수 가중 평균으로 표현되며, STOMP의 갱신 규칙은 이 이론의 이산화에 해당한다.
비용의 지수 가중 \exp(-S/\lambda)은 비용이 낮은 궤적에 높은 가중치를 부여하여, 양호한 궤적 방향으로의 갱신을 유도한다. 온도 \lambda가 작으면 최선의 궤적에 가중이 집중되고, \lambda가 크면 가중이 균등해진다.
4. CHOMP와의 비교
| 특성 | CHOMP | STOMP |
|---|---|---|
| 갱신 방법 | 결정론적 그래디언트 | 확률적 샘플링 |
| 비용 함수 요구 | 미분 가능 필수 | 미분 가능성 불요 |
| 국소 최적 탈출 | 어려움 | 확률적 탐색에 의해 가능 |
| 수렴 속도 | 빠름 (그래디언트 정보 활용) | 상대적으로 느림 |
| 비용 종류 | 매끄러운 비용에 적합 | 이진 비용, 불연속 비용에도 적용 |
| 병렬화 | 제한적 | 샘플 평가의 자연스러운 병렬화 |
5. 장점과 한계
장점: 비용 함수의 미분 가능성을 요구하지 않으므로, 이진 충돌 검사(충돌/비충돌), 비매끄러운 벌점 함수, 시뮬레이션 기반 비용 등에 적용 가능하다. 확률적 탐색에 의해 CHOMP보다 국소 최적에서의 탈출 가능성이 높다. 궤적 샘플의 비용 평가가 독립적이므로 병렬 처리에 적합하다.
한계: 그래디언트 정보를 활용하지 않으므로 수렴이 느리며, 많은 수의 샘플(K = 10 \sim 100)이 필요하다. 고차원 관절 공간에서 효율이 저하될 수 있다. 잡음의 크기와 온도 매개변수의 조절이 성능에 영향을 미친다.
6. 로봇 공학에서의 응용
매니퓰레이터 모션 계획: MoveIt(ROS의 모션 계획 프레임워크)에서 STOMP 플래너가 제공되며, CHOMP와 함께 경사 기반 경로 최적화의 대안으로 사용된다.
접촉 풍부한 조작: 물체와의 접촉을 포함하는 조작 궤적에서 접촉 전환에 의한 비매끄러움이 존재하므로, 미분 불요인 STOMP가 CHOMP보다 유리하다.
강화 학습과의 결합: PI² 기반 정책 학습에서 STOMP의 궤적 샘플링과 가중 갱신이 정책 개선에 사용된다.
7. 참고 문헌
- Kalakrishnan, M., Chitta, S., Theodorou, E., Pastor, P., & Schaal, S. (2011). “STOMP: Stochastic Trajectory Optimization for Motion Planning.” Proceedings of ICRA, 4569–4574.
- Theodorou, E., Buchli, J., & Schaal, S. (2010). “A Generalized Path Integral Control Approach to Reinforcement Learning.” Journal of Machine Learning Research, 11, 3137–3181.
- Zucker, M., et al. (2013). “CHOMP: Covariant Hamiltonian Optimization for Motion Planning.” IJRR, 32(9-10), 1164–1193.
version: 1.0