11.9 로그 사상(Logarithmic Map)

1. 로그 사상의 개요

로그 사상(logarithmic map)은 지수 사상의 역이며, 리 군에서 리 대수로의 사상이다. 리 군의 원소(유한 변환)를 리 대수의 원소(무한소 운동)로 변환하는 이 사상은 자세 추정, 비선형 최적화, 자세 비교, 운동 계획 등 다양한 영역에서 핵심적인 역할을 한다. 행렬 리 군에서 로그 사상은 행렬 로그와 일치하며, 항등원 근방에서 잘 정의된다. 본 절에서는 로그 사상의 정의, 성질, 그리고 SO(3)SE(3)에서의 닫힌 형태를 체계적으로 다룬다.

2. 일반 리 군에서의 로그 사상

2.1 정의

리 군 G의 항등원 근방에서 지수 사상 \exp : \mathfrak{g} \to G는 일대일이며 미분 동형사상이다. 이 영역에서의 역 사상이 로그 사상이다.

\log : G \to \mathfrak{g}

즉, \log(\exp(X)) = X이고 \exp(\log(g)) = g가 항등원 근방에서 성립한다.

2.2 정의 영역

로그 사상은 일반적으로 항등원 근방에서만 정의된다. 멀리 떨어진 점에서는 다중값을 가질 수 있다. 정의 영역의 정확한 범위는 리 군의 구조에 의존한다.

2.3 다중값 문제

지수 사상이 일대일이 아니므로 로그 사상은 본질적으로 다중값일 수 있다. 예를 들어 \exp([\boldsymbol{\omega}]_\times) = \exp([(\boldsymbol{\omega} + 2\pi\hat{\mathbf{u}})]_\times)이 같은 회전을 나타낸다. 표준적인 로그는 가장 짧은 회전 벡터를 선택한다.

3. 행렬 로그

3.1 정의

가역 행렬 \mathbf{M}의 행렬 로그는 e^X = \mathbf{M}을 만족하는 행렬 X이다. 일반적으로 다중값을 가지지만, 항등 행렬 근방에서는 다음의 무한 급수로 정의된다.

\log(\mathbf{M}) = \sum_{k=1}^{\infty}\frac{(-1)^{k+1}}{k}(\mathbf{M} - \mathbf{I})^k

이 급수는 \lVert\mathbf{M} - \mathbf{I}\rVert < 1일 때 수렴한다.

3.2 수렴 영역

행렬 로그의 무한 급수는 항등 행렬 근방에서만 수렴한다. 더 멀리 떨어진 행렬에 대해서는 다른 방법(예: Schur 분해)을 사용해야 한다.

3.3 성질

행렬 로그는 다음의 성질을 가진다.

  • \log(\mathbf{I}) = \mathbf{0}
  • \exp(\log(\mathbf{M})) = \mathbf{M} (정의 영역에서)
  • \log(\exp(X)) = X (정의 영역에서)
  • 가환 행렬에 대해 \log(\mathbf{M}_1\mathbf{M}_2) = \log(\mathbf{M}_1) + \log(\mathbf{M}_2)
  • 일반적으로 \log(\mathbf{M}_1\mathbf{M}_2) \neq \log(\mathbf{M}_1) + \log(\mathbf{M}_2)

4. SO(3)의 로그 사상

4.1 정의

회전 행렬 \mathbf{R}에 대한 로그는 다음을 만족하는 반대칭 행렬 [\boldsymbol{\omega}]_\times이다.

\exp([\boldsymbol{\omega}]_\times) = \mathbf{R}

이는 회전 행렬을 회전 벡터로 변환하는 것과 동치이다.

4.2 회전 각의 추출

회전 행렬의 트레이스로부터 회전 각이 결정된다.

\theta = \arccos\!\left(\frac{\mathrm{tr}(\mathbf{R}) - 1}{2}\right)

회전 각의 범위는 [0, \pi]이다.

4.3 회전 축의 추출

회전 축은 회전 행렬의 반대칭 부분으로부터 결정된다.

[\hat{\mathbf{u}}]_\times = \frac{1}{2\sin\theta}(\mathbf{R} - \mathbf{R}^T)

또는 동등하게 벡터 형태로

\hat{\mathbf{u}} = \frac{1}{2\sin\theta}\begin{bmatrix}r_{32} - r_{23} \\ r_{13} - r_{31} \\ r_{21} - r_{12}\end{bmatrix}

4.4 회전 벡터

회전 벡터는 회전 축과 회전 각의 곱이다.

\boldsymbol{\omega} = \theta\hat{\mathbf{u}}

4.5 로그 사상의 닫힌 형태

전체적으로 SO(3)의 로그 사상은 다음과 같이 표현된다.

\log(\mathbf{R}) = \frac{\theta}{2\sin\theta}(\mathbf{R} - \mathbf{R}^T)

여기서 \theta = \arccos((\mathrm{tr}(\mathbf{R}) - 1)/2)이다.

4.6 특수 경우의 처리

4.6.1 항등 회전 (\theta = 0)

\mathrm{tr}(\mathbf{R}) = 3이면 \theta = 0이고, 회전 축이 정의되지 않는다. 이 경우 \boldsymbol{\omega} = \mathbf{0}이다.

4.6.2 \pi 회전 (\theta = \pi)

\mathrm{tr}(\mathbf{R}) = -1이면 \theta = \pi이고, \sin\theta = 0이므로 위의 공식이 직접 적용되지 않는다. 이 경우 회전 축은 다음과 같이 추출된다.

\hat{\mathbf{u}}_i = \pm\sqrt{\frac{r_{ii} + 1}{2}}

축의 부호는 비대각 원소들로부터 결정된다.

이러한 특수 경우의 처리가 수치적 안정성을 보장한다.

5. SE(3)의 로그 사상

5.1 정의

강체 변환 \mathbf{T} = (\mathbf{R}, \mathbf{t})에 대한 로그는 다음을 만족하는 트위스트 \hat{\boldsymbol{\xi}}이다.

\exp(\hat{\boldsymbol{\xi}}) = \mathbf{T}

이는 동차 변환 행렬을 트위스트로 변환하는 것이다.

5.2 회전 부분과 병진 부분의 분리

SE(3)의 로그는 회전 부분과 병진 부분을 별도로 다룬다.

5.2.1 단계: 회전 부분의 로그

먼저 SO(3)의 로그 사상을 사용하여 회전 부분을 추출한다.

\boldsymbol{\omega} = \log(\mathbf{R})

여기서 \boldsymbol{\omega}는 회전 벡터이다.

5.2.2 단계: 병진 부분의 추출

병진 벡터 \mathbf{t}로부터 트위스트의 병진 부분 \mathbf{v}를 다음과 같이 계산한다.

\mathbf{v} = \mathbf{V}^{-1}(\boldsymbol{\omega})\mathbf{t}

여기서 \mathbf{V}^{-1}은 좌측 야코비안의 역이다.

5.3 좌측 야코비안의 역

좌측 야코비안의 역은 다음과 같이 표현된다.

\mathbf{V}^{-1}(\boldsymbol{\omega}) = \mathbf{I} - \frac{1}{2}[\boldsymbol{\omega}]_\times + \left(\frac{1}{\theta^2} - \frac{1 + \cos\theta}{2\theta\sin\theta}\right)[\boldsymbol{\omega}]_\times^2

여기서 \theta = \lVert\boldsymbol{\omega}\rVert이다. 이 식은 \theta = 0일 때 \mathbf{I}로 간주되며, 작은 \theta에서는 테일러 급수 전개가 사용된다.

5.4 전체 로그 사상

종합하면 SE(3)의 로그 사상은 다음과 같다.

\log(\mathbf{T}) = \begin{bmatrix}\boldsymbol{\omega} \\ \mathbf{V}^{-1}(\boldsymbol{\omega})\mathbf{t}\end{bmatrix}

여기서 \boldsymbol{\omega} = \log(\mathbf{R})이다.

5.5 특수 경우

5.5.1 항등 변환

\mathbf{T} = \mathbf{I}이면 \boldsymbol{\omega} = \mathbf{0}이고 \mathbf{V}^{-1} = \mathbf{I}이므로 \mathbf{v} = \mathbf{t} = \mathbf{0}이다. 따라서 \log(\mathbf{I}) = \mathbf{0}이다.

5.5.2 순수 회전

\mathbf{t} = \mathbf{0}이면 병진 부분이 0이지만, \mathbf{V}^{-1}\mathbf{0} = \mathbf{0}이므로 \mathbf{v} = \mathbf{0}이다.

5.5.3 순수 병진

\mathbf{R} = \mathbf{I}이면 \boldsymbol{\omega} = \mathbf{0}이고 \mathbf{V} = \mathbf{I}이므로 \mathbf{v} = \mathbf{t}이다.

6. 로그 사상의 미분

6.1 우측 야코비안

로그 사상의 미분은 우측 야코비안의 역으로 표현된다.

\frac{d}{dt}\log(\mathbf{R}(t)\exp([\delta\boldsymbol{\omega}]_\times))\bigg|_{t=0} = \mathbf{J}_r^{-1}(\log(\mathbf{R}))\delta\boldsymbol{\omega}

이러한 미분은 비선형 최적화의 야코비안 계산에 활용된다.

6.2 야코비안의 닫힌 형태

우측 야코비안의 역은 다음과 같다.

\mathbf{J}_r^{-1}(\boldsymbol{\omega}) = \mathbf{I} + \frac{1}{2}[\boldsymbol{\omega}]_\times + \left(\frac{1}{\theta^2} - \frac{1 + \cos\theta}{2\theta\sin\theta}\right)[\boldsymbol{\omega}]_\times^2

6.3 활용

야코비안과 그 역은 다음과 같은 응용에서 사용된다.

  • 자세 추정의 갱신
  • 비선형 최적화의 헤시안 계산
  • 매니퓰레이터의 미분 운동학
  • 시각적 SLAM의 번들 조정

7. 로그 사상의 수치적 계산

7.1 일반 행렬 로그

일반 행렬에 대한 로그 계산은 어렵다. Schur 분해, Padé 근사, 부분 분해 등의 기법이 사용된다.

7.2 닫힌 형태의 활용

SO(3)SE(3)의 경우 닫힌 형태가 존재하므로 직접 사용한다. 이는 효율적이고 정확하다.

7.3 작은 회전의 처리

회전 각이 작을 때는 \sin\theta \approx \theta 등의 근사가 사용된다. 정확도와 안정성을 위해 테일러 급수 전개가 권장된다.

\frac{\theta}{2\sin\theta} \approx \frac{1}{2}\!\left(1 + \frac{\theta^2}{6} + \frac{7\theta^4}{360} + \ldots\right)

7.4 \pi 회전 근처의 처리

회전 각이 \pi에 가까울 때는 \sin\theta가 0에 가까워지지만 회전 벡터의 노름이 일정하다. 이 영역에서는 별도의 처리가 필요하다.

7.5 수치적 안정성

다양한 영역에서의 수치적 안정성을 보장하기 위해 다음과 같은 처리가 이루어진다.

  • 트레이스가 정의역을 벗어나지 않도록 클램핑한다.
  • 작은 각도와 큰 각도 모두에서 정확한 공식을 사용한다.
  • \pi 근처에서 특수 경우 처리를 한다.

8. 자세 거리

8.1 측지 거리

두 자세 \mathbf{R}_1\mathbf{R}_2 사이의 측지 거리는 로그 사상을 사용하여 정의된다.

d(\mathbf{R}_1, \mathbf{R}_2) = \lVert\log(\mathbf{R}_1^T\mathbf{R}_2)\rVert

이는 두 자세 사이의 가장 짧은 회전 각이며, 자세 다양체 위의 자연스러운 거리이다.

8.2 SE(3)의 거리

SE(3) 위의 거리도 비슷하게 정의된다.

d(\mathbf{T}_1, \mathbf{T}_2) = \lVert\log(\mathbf{T}_1^{-1}\mathbf{T}_2)\rVert_W

여기서 \lVert\cdot\rVert_W는 가중치 노름이며, 회전과 병진의 단위 차이를 보정한다.

9. 측지선 보간

9.1 측지선

리 군 위의 두 점 사이의 측지선은 로그 사상과 지수 사상을 사용하여 표현된다.

\gamma(t) = \mathbf{T}_0\exp(t\log(\mathbf{T}_0^{-1}\mathbf{T}_1))

여기서 t \in [0, 1]이며, \gamma(0) = \mathbf{T}_0이고 \gamma(1) = \mathbf{T}_1이다.

9.2 SLERP

쿼터니언의 SLERP은 본질적으로 SO(3) 위의 측지선 보간이며, 로그 사상을 사용하여 유도될 수 있다.

9.3 운동 계획

매니퓰레이터의 자세 보간이나 카메라 경로 생성에서 측지선 보간이 사용된다.

10. 자세 오차

10.1 자세 오차의 정의

추정 자세와 참 자세 사이의 오차는 로그 사상으로 정의된다.

\boldsymbol{\delta\omega} = \log(\hat{\mathbf{R}}^T\mathbf{R})

이는 추정 자세에서 참 자세로의 회전 벡터이다.

10.2 자세 추정의 갱신

자세 추정의 갱신은 종종 다음과 같이 이루어진다.

\hat{\mathbf{R}}_{k+1} = \hat{\mathbf{R}}_k\exp([\boldsymbol{\delta\omega}]_\times)

여기서 \boldsymbol{\delta\omega}는 측정값을 사용하여 계산된 보정 벡터이다.

11. 비선형 최적화에서의 활용

11.1 자세 변수의 매개변수화

비선형 최적화에서 자세 변수는 매개변수화가 필요하다. 일반적인 방법은 명목 자세를 유지하고, 작은 보정을 리 대수의 원소로 표현하는 것이다.

\mathbf{R}(\boldsymbol{\delta}) = \hat{\mathbf{R}}\exp([\boldsymbol{\delta}]_\times)

여기서 \boldsymbol{\delta}가 최적화 변수이며, \boldsymbol{\delta} = \mathbf{0} 근방에서 최적화를 수행한다.

11.2 야코비안

비용 함수의 자코비안은 \boldsymbol{\delta}에 대해 계산되며, 로그 사상의 미분이 등장한다.

11.3 갱신

최적화의 한 단계 후 명목 자세가 갱신된다.

\hat{\mathbf{R}} \leftarrow \hat{\mathbf{R}}\exp([\boldsymbol{\delta}^*]_\times)

여기서 \boldsymbol{\delta}^*는 최적 보정이다. 이는 자세를 다양체 위에 유지한다.

12. 시각적 SLAM에서의 활용

12.1 카메라 자세 최적화

번들 조정에서 카메라 자세가 SE(3)의 원소이며, 최적화 변수는 \mathfrak{se}(3)의 원소로 매개변수화된다. 로그 사상이 자세 차이의 측정과 갱신에 사용된다.

12.2 그래프 SLAM

그래프 SLAM에서 노드는 SE(3)의 원소이고 엣지는 두 노드 사이의 상대 자세이다. 잔차의 계산에 로그 사상이 사용된다.

13. 매니퓰레이터에서의 활용

13.1 역기구학

수치적 역기구학에서 자세 오차의 계산에 로그 사상이 사용된다. 목표 자세와 현재 자세의 차이가 트위스트로 표현된다.

13.2 운동 계획

작업 공간의 경로를 트위스트의 시간 함수로 표현할 수 있다. 시작 자세와 목표 자세의 로그가 보간의 매개변수가 된다.

14. 학습의 가치

로그 사상을 깊이 이해하는 것은 다음과 같은 이점을 제공한다.

  • 자세를 리 대수의 원소로 변환하는 방법을 이해한다.
  • 자세 오차와 거리를 자연스럽게 정의할 수 있다.
  • 자세 추정과 비선형 최적화의 핵심 도구이다.
  • 측지선 보간과 운동 계획의 기초를 형성한다.
  • 시각적 SLAM과 번들 조정의 알고리즘을 이해한다.

15. 라이브러리 지원

15.1 Eigen

Eigen은 회전 행렬과 축-각도 표현 사이의 변환을 통해 SO(3)의 로그 사상을 효과적으로 다룰 수 있다.

Eigen::AngleAxisd aa(R);
Eigen::Vector3d omega = aa.angle() * aa.axis();

15.2 Sophus

Sophus 라이브러리는 SO(3)SE(3)의 로그 사상을 직접 제공한다.

Eigen::Vector3d omega = R.log();
Sophus::SE3d::Tangent xi = T.log();

15.3 manif

manif 라이브러리도 다양한 리 군의 로그 사상을 제공한다.

16. 참고 문헌

  • Hall, B. C. (2015). Lie Groups, Lie Algebras, and Representations: An Elementary Introduction (2nd ed.). Springer.
  • Stillwell, J. (2008). Naive Lie Theory. Springer.
  • Murray, R. M., Li, Z., & Sastry, S. S. (1994). A Mathematical Introduction to Robotic Manipulation. CRC Press.
  • Lynch, K. M., & Park, F. C. (2017). Modern Robotics: Mechanics, Planning, and Control. Cambridge University Press.
  • Sola, J., Deray, J., & Atchuthan, D. (2018). “A Micro Lie Theory for State Estimation in Robotics.” arXiv:1812.01537.
  • Higham, N. J. (2008). Functions of Matrices: Theory and Computation. SIAM.

version: 1.0