7.128 비선형 최소 제곱 문제의 정식화
1. 문제의 정의
비선형 최소 제곱(nonlinear least squares) 문제는 잔차 함수(residual function)의 제곱합을 최소화하는 문제이다.
\min_{\mathbf{x} \in \mathbb{R}^n} \quad f(\mathbf{x}) = \frac{1}{2}\sum_{i=1}^{m} r_i(\mathbf{x})^2 = \frac{1}{2}\lVert \mathbf{r}(\mathbf{x}) \rVert^2 = \frac{1}{2}\mathbf{r}(\mathbf{x})^T\mathbf{r}(\mathbf{x})
여기서 \mathbf{r}(\mathbf{x}) = [r_1(\mathbf{x}), \ldots, r_m(\mathbf{x})]^T: \mathbb{R}^n \to \mathbb{R}^m은 잔차 벡터이다. 통상 m \geq n (관측 수가 파라미터 수 이상)인 과결정(overdetermined) 시스템이다.
2. 일반 최적화와의 차이
비선형 최소 제곱 문제는 일반 비선형 최적화의 특수한 경우이지만, 목적 함수의 제곱합 구조를 활용하여 더 효율적인 전용 알고리즘을 설계할 수 있다.
목적 함수의 그래디언트와 헤시안은 야코비안 \mathbf{J}(\mathbf{x}) = \frac{\partial \mathbf{r}}{\partial \mathbf{x}} \in \mathbb{R}^{m \times n}으로 표현된다.
\nabla f(\mathbf{x}) = \mathbf{J}(\mathbf{x})^T\mathbf{r}(\mathbf{x})
\nabla^2 f(\mathbf{x}) = \mathbf{J}(\mathbf{x})^T\mathbf{J}(\mathbf{x}) + \sum_{i=1}^{m} r_i(\mathbf{x})\nabla^2 r_i(\mathbf{x})
헤시안의 첫째 항 \mathbf{J}^T\mathbf{J}는 항상 양의 반정치이며, 야코비안만으로 계산 가능하다. 둘째 항 \sum r_i \nabla^2 r_i는 잔차의 2차 미분을 요구하며, 잔차가 작을 때(즉, 모델이 데이터를 잘 적합할 때) 무시할 수 있다.
3. 가우스-뉴턴 근사
잔차가 충분히 작거나 거의 선형인 경우, 헤시안의 2차 항을 무시한 가우스-뉴턴 근사가 유효하다.
\nabla^2 f(\mathbf{x}) \approx \mathbf{J}(\mathbf{x})^T\mathbf{J}(\mathbf{x})
이 근사의 이점은 다음과 같다.
- 잔차의 2차 미분 \nabla^2 r_i를 계산할 필요가 없다.
- 근사 헤시안 \mathbf{J}^T\mathbf{J}가 항상 양의 반정치이므로 별도의 정규화가 불필요하다.
- 야코비안 \mathbf{J}만으로 그래디언트와 근사 헤시안이 모두 계산된다.
4. 로봇 공학에서의 비선형 최소 제곱 문제
4.1 파라미터 추정
로봇 동역학 모델의 파라미터(질량, 관성, 마찰 계수 등)를 실험 데이터로부터 추정하는 문제이다.
r_i(\boldsymbol{\theta}) = \tau_i^{meas} - \tau_i^{model}(\mathbf{q}_i, \dot{\mathbf{q}}_i, \ddot{\mathbf{q}}_i; \boldsymbol{\theta})
여기서 \boldsymbol{\theta}는 추정할 동역학 파라미터 벡터, \tau_i^{meas}는 측정된 토크, \tau_i^{model}은 모델 예측 토크이다.
4.2 센서 캘리브레이션
카메라의 내부/외부 파라미터를 영상의 특징점 대응으로부터 추정하는 문제이다.
r_{ij}(\boldsymbol{\theta}) = \mathbf{p}_{ij}^{obs} - \pi(\mathbf{P}_j; \boldsymbol{\theta}_i)
여기서 \mathbf{p}_{ij}^{obs}는 관측된 영상 좌표, \pi는 투영 함수이다.
4.3 SLAM 백엔드 최적화
그래프 기반 SLAM에서 포즈 그래프의 최적화는 대규모 비선형 최소 제곱 문제이다.
\min_{\mathbf{x}} \sum_{(i,j) \in \mathcal{E}} \lVert \mathbf{z}_{ij} - h_{ij}(\mathbf{x}_i, \mathbf{x}_j) \rVert^2_{\boldsymbol{\Omega}_{ij}}
여기서 \mathbf{x}_i는 i번째 포즈, \mathbf{z}_{ij}는 포즈 i와 j 사이의 상대 측정, \boldsymbol{\Omega}_{ij}는 정보 행렬이다. 이 문제는 수만 개의 포즈 변수를 갖지만, 야코비안이 매우 희소하여 효율적 해법이 가능하다.
4.4 번들 조정(Bundle Adjustment)
시각 SLAM과 구조로부터의 모션(Structure from Motion)에서 카메라 포즈와 3차원 점의 위치를 동시에 최적화하는 문제이다. 야코비안이 블록 희소(block-sparse) 구조를 가지며, 슈어 보수를 이용한 효율적 분해가 가능하다.
5. 가중 최소 제곱
관측의 정밀도가 서로 다른 경우, 가중 행렬 \mathbf{W}를 도입한 가중 최소 제곱이 사용된다.
\min_{\mathbf{x}} \quad \frac{1}{2}\mathbf{r}(\mathbf{x})^T\mathbf{W}\mathbf{r}(\mathbf{x})
\mathbf{W} = \boldsymbol{\Sigma}^{-1}으로 설정하면(\boldsymbol{\Sigma}는 관측 잡음의 공분산 행렬), 이는 최대 우도 추정(maximum likelihood estimation)에 해당한다.
6. 강건 비용 함수
이상치(outlier)에 민감한 제곱 비용 대신, 강건 비용 함수(robust cost function)를 사용하여 이상치의 영향을 억제한다.
\min_{\mathbf{x}} \quad \sum_{i=1}^{m} \rho(r_i(\mathbf{x}))
대표적 강건 비용:
- 후버(Huber) 비용: \rho(r) = \begin{cases} \frac{1}{2}r^2 & \lvert r \rvert \leq \delta \\ \delta(\lvert r \rvert - \frac{1}{2}\delta) & \lvert r \rvert > \delta \end{cases}
- 코시(Cauchy) 비용: \rho(r) = \frac{c^2}{2}\ln(1 + (r/c)^2)
강건 비용 함수는 반복적 재가중 최소 제곱(Iteratively Reweighted Least Squares, IRLS)으로 풀 수 있다.
7. 참고 문헌
- Nocedal, J., & Wright, S. J. (2006). Numerical Optimization (2nd ed.). Springer.
- Björck, Å. (1996). Numerical Methods for Least Squares Problems. SIAM.
- Grisetti, G., Kümmerle, R., Stachniss, C., & Burgard, W. (2010). “A Tutorial on Graph-Based SLAM.” IEEE Intelligent Transportation Systems Magazine, 2(4), 31–43.
- Triggs, B., McLauchlan, P. F., Hartley, R. I., & Fitzgibbon, A. W. (2000). “Bundle Adjustment — A Modern Synthesis.” Vision Algorithms: Theory and Practice, Lecture Notes in Computer Science, 298–372.
version: 1.0