11.8 지수 사상(Exponential Map)

1. 지수 사상의 개요

지수 사상(exponential map)은 리 대수에서 리 군으로의 사상이며, 리 군과 리 대수를 연결하는 핵심 도구이다. 이 사상은 리 대수의 원소(무한소 운동)를 리 군의 원소(유한 변환)로 변환한다. 행렬 리 군에서는 행렬 지수 함수와 일치하며, 이는 리 군 이론의 가장 중요한 사상 중 하나이다. 지수 사상은 자세 추정, 매니퓰레이터 운동학, 운동 계획 등 로봇공학의 다양한 영역에서 핵심적인 역할을 한다.

2. 일반 리 군에서의 지수 사상

2.1 정의

리 군 G의 항등원에서의 1매개 변수 부분 군을 통해 지수 사상이 정의된다. 리 대수 \mathfrak{g}의 원소 X에 대응하는 1매개 변수 부분 군 \gamma_X : \mathbb{R} \to G가 존재하며, 다음을 만족한다.

\gamma_X(0) = e, \quad \dot\gamma_X(0) = X

지수 사상은 다음과 같이 정의된다.

\exp : \mathfrak{g} \to G, \quad \exp(X) = \gamma_X(1)

즉, X 방향으로 단위 시간 동안 리 군 위를 운동했을 때 도달하는 점이 \exp(X)이다.

2.2 성질

지수 사상은 다음의 성질을 가진다.

  • \exp(0) = e (영원이 항등원으로 사상된다)
  • \exp(tX)X에 의해 생성되는 1매개 변수 부분 군이다.
  • 항등원 근방에서 \exp는 미분 동형사상이다(즉, 일대일이고 매끄러우며 역도 매끄럽다).
  • 가환 리 군에서는 \exp(X + Y) = \exp(X)\exp(Y)이지만, 비가환 리 군에서는 일반적으로 그렇지 않다.

3. 행렬 지수

3.1 정의

행렬 리 군에서 지수 사상은 행렬 지수와 일치한다. 정사각 행렬 X의 행렬 지수는 다음과 같이 정의된다.

e^X = \exp(X) = \sum_{k=0}^{\infty}\frac{X^k}{k!} = \mathbf{I} + X + \frac{X^2}{2!} + \frac{X^3}{3!} + \ldots

이 무한 급수는 모든 정사각 행렬 X에 대해 절대 수렴하며, 행렬 노름의 의미에서 잘 정의된다.

3.2 수렴성

행렬 지수의 무한 급수는 다음과 같이 수렴한다.

\left\lVert\sum_{k=0}^{N}\frac{X^k}{k!} - e^X\right\rVert \to 0 \quad \text{as } N \to \infty

이 수렴은 임의의 행렬 노름에 대해 성립한다.

3.3 기본 성질

행렬 지수는 다음의 성질을 가진다.

  • e^0 = \mathbf{I}
  • e^{X+Y} = e^Xe^Y if XY = YX (가환적인 경우)
  • e^Xe^Y \neq e^{X+Y} in general (비가환적인 경우)
  • (e^X)^{-1} = e^{-X}
  • \det(e^X) = e^{\mathrm{tr}(X)}
  • e^X는 항상 가역이다.

3.4 가환과 비가환의 차이

두 행렬이 가환이면(즉, XY = YX), 지수의 곱이 합의 지수가 된다. 비가환이면 BCH 공식의 더 높은 차수 항들이 필요하다.

4. \mathfrak{so}(3)의 지수 사상

4.1 닫힌 형태

\mathfrak{so}(3)의 원소 [\boldsymbol{\omega}]_\times의 지수 사상은 로드리게스 공식에 의해 닫힌 형태로 표현된다.

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

여기서 \theta = \lVert\boldsymbol{\omega}\rVert이다. 이는 무한 급수가 닫힌 형태로 합산 가능함을 보여주는 우아한 결과이다.

4.2 유도

[\boldsymbol{\omega}]_\times의 거듭제곱이 다음의 패턴을 따른다.

[\boldsymbol{\omega}]_\times^3 = -\theta^2[\boldsymbol{\omega}]_\times

[\boldsymbol{\omega}]_\times^4 = -\theta^2[\boldsymbol{\omega}]_\times^2

[\boldsymbol{\omega}]_\times^5 = \theta^4[\boldsymbol{\omega}]_\times

이러한 순환 패턴을 이용하여 무한 급수를 합산하면 위의 닫힌 형태가 얻어진다. 사인과 코사인 함수의 테일러 급수가 자연스럽게 등장한다.

4.3 단위 축으로의 표현

\boldsymbol{\omega} = \theta\hat{\mathbf{u}}로 표현하면

\exp([\theta\hat{\mathbf{u}}]_\times) = \mathbf{I} + \sin\theta[\hat{\mathbf{u}}]_\times + (1 - \cos\theta)[\hat{\mathbf{u}}]_\times^2

이는 단위 축 \hat{\mathbf{u}} 주위의 \theta 회전을 나타내는 회전 행렬이다.

4.4 의미

\mathfrak{so}(3)의 지수 사상은 회전 벡터(축-각도 벡터)에서 회전 행렬로의 사상이다. 이를 통해 회전 벡터가 회전을 매개변수화하는 자연스러운 방법임을 알 수 있다.

5. \mathfrak{se}(3)의 지수 사상

5.1 닫힌 형태

\mathfrak{se}(3)의 원소 \hat{\boldsymbol{\xi}}의 지수 사상도 닫힌 형태로 표현된다.

\exp(\hat{\boldsymbol{\xi}}) = \begin{bmatrix}\exp([\boldsymbol{\omega}]_\times) & \mathbf{V}(\boldsymbol{\omega})\mathbf{v} \\ \mathbf{0}^T & 1\end{bmatrix}

여기서

  • \exp([\boldsymbol{\omega}]_\times): 로드리게스 공식에 의한 회전 행렬
  • \mathbf{V}(\boldsymbol{\omega}): 좌측 야코비안

5.2 좌측 야코비안

좌측 야코비안의 닫힌 형태는 다음과 같다.

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

여기서 \theta = \lVert\boldsymbol{\omega}\rVert이다.

5.3 의미

\mathfrak{se}(3)의 지수 사상은 트위스트(6차원 운동 벡터)에서 강체 변환(동차 변환 행렬)으로의 사상이다. 회전 부분과 병진 부분이 결합된 형태로 표현된다.

5.4 순수 회전과 순수 병진의 특수 경우

5.4.1 순수 회전 (\mathbf{v} = \mathbf{0})

\exp(\hat{\boldsymbol{\xi}}) = \begin{bmatrix}\exp([\boldsymbol{\omega}]_\times) & \mathbf{0} \\ \mathbf{0}^T & 1\end{bmatrix}

5.4.2 순수 병진 (\boldsymbol{\omega} = \mathbf{0})

\boldsymbol{\omega} = \mathbf{0}이면 \mathbf{V} = \mathbf{I}이므로

\exp(\hat{\boldsymbol{\xi}}) = \begin{bmatrix}\mathbf{I} & \mathbf{v} \\ \mathbf{0}^T & 1\end{bmatrix}

이는 단순 병진 변환이다.

6. 지수 사상의 기하학적 해석

6.1 측지선

리 군 위의 측지선(geodesic)은 두 점 사이의 가장 짧은 곡선이다. 항등원에서 \exp(X)로의 측지선은 정확히 1매개 변수 부분 군 t \mapsto \exp(tX)이다.

이로 인해 지수 사상은 측지선과 자연스럽게 연결된다.

6.2 다양체의 곡률

리 군이 비가환이면 곡률을 가지며, 측지선이 직선이 아니다. 지수 사상은 이러한 곡률을 고려하여 리 대수(접선 공간)의 원소를 리 군의 원소로 변환한다.

7. 지수 사상의 영역과 치역

7.1 영역

지수 사상의 영역은 리 대수 전체이다. 행렬 지수는 모든 정사각 행렬에 대해 정의된다.

7.2 치역

지수 사상의 치역은 리 군의 항등 성분이다. 즉, 항등원과 연결된 부분 군이다. 연결 리 군에서는 이가 전체 리 군이지만, 비연결 리 군에서는 한 성분만 사상된다.

7.3 위로의 사상 여부

지수 사상이 위로의 사상(surjective)인지는 리 군의 성질에 의존한다.

  • 콤팩트 연결 리 군에서는 위로의 사상이다.
  • 일반 연결 리 군에서는 위로의 사상이 아닐 수 있다.
  • SO(3), SU(2), SE(3)의 항등 성분은 위로의 사상이다.

7.4 일대일 사상 여부

지수 사상은 일반적으로 일대일이 아니다. 예를 들어 \mathfrak{so}(3)에서 SO(3)로의 지수 사상에서 \boldsymbol{\omega}\boldsymbol{\omega} + 2\pi\hat{\mathbf{u}}가 같은 회전을 산출한다.

7.5 항등원 근방의 일대일성

지수 사상은 항등원 근방에서 일대일이다. 이 영역에서 지수 사상의 역인 로그 사상이 정의된다.

8. BCH 공식

8.1 Baker-Campbell-Hausdorff 공식

두 리 대수 원소의 지수의 곱은 BCH 공식으로 표현된다.

\exp(X)\exp(Y) = \exp(Z)

여기서

Z = X + Y + \frac{1}{2}[X, Y] + \frac{1}{12}[X, [X, Y]] - \frac{1}{12}[Y, [X, Y]] + \ldots

이는 무한 급수이며, 모든 항이 리 괄호의 중첩 형태이다.

8.2 차 근사

XY가 충분히 작으면 1차 근사가 사용된다.

\exp(X)\exp(Y) \approx \exp(X + Y + \frac{1}{2}[X, Y])

8.3 가환과의 비교

가환 리 군에서는 [X, Y] = 0이므로

\exp(X)\exp(Y) = \exp(X + Y)

이는 표준 지수 함수의 성질과 일치한다. 비가환의 경우 리 괄호 항들이 보정으로 추가된다.

9. 지수 사상의 미분

9.1 좌측 야코비안

지수 사상의 미분은 좌측 야코비안 \mathbf{J}_l로 표현된다.

\frac{d}{dt}\exp(X(t))\bigg|_{t=0} = \exp(X(0))[\mathbf{J}_l(X(0))\dot{X}(0)]^\wedge

좌측 야코비안의 \mathfrak{so}(3)에서의 형태는 다음과 같다.

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

9.2 우측 야코비안

마찬가지로 우측 야코비안 \mathbf{J}_r이 정의되며, 좌측과 우측 곱의 차이로 인해 다르다.

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

좌측 야코비안과 우측 야코비안의 관계는 \mathbf{J}_l(\boldsymbol{\omega}) = \mathbf{J}_r(-\boldsymbol{\omega})^T = \mathbf{J}_r(\boldsymbol{\omega})^T이다.

9.3 야코비안의 활용

좌측과 우측 야코비안은 비선형 최적화, 자세 추정의 갱신, 매니퓰레이터의 미분 운동학 등에서 활용된다.

10. 수치적 계산

10.1 직접 급수 계산

행렬 지수를 직접 무한 급수로 계산하는 것은 비효율적이며 수치적으로 안정적이지 않다. 적은 항으로 절단하면 부정확하고, 많은 항을 사용하면 비용이 든다.

10.2 Padé 근사

Padé 근사는 행렬 지수를 유리 함수로 근사하며, 수치적으로 안정적이다. 이는 일반적인 행렬 지수 계산에 사용된다.

10.3 닫힌 형태

\mathfrak{so}(3)\mathfrak{se}(3)의 경우 닫힌 형태가 존재하므로 직접 사용한다. 이는 가장 효율적이고 정확한 방법이다.

10.4 작은 인수의 처리

\theta가 매우 작으면 닫힌 형태의 분모가 0에 가까워져 수치 오류가 발생한다. 이러한 경우 테일러 급수 전개를 사용한다.

\frac{\sin\theta}{\theta} \approx 1 - \frac{\theta^2}{6} + \frac{\theta^4}{120}

\frac{1 - \cos\theta}{\theta^2} \approx \frac{1}{2} - \frac{\theta^2}{24} + \frac{\theta^4}{720}

이러한 근사가 작은 \theta에서 수치적 안정성을 보장한다.

11. 응용

11.1 자세 추정

자세 추정 알고리즘의 갱신은 종종 다음의 형태로 이루어진다.

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

여기서 \delta\boldsymbol{\theta}는 작은 회전 벡터이다. 지수 사상이 회전을 다양체 위에 유지한다.

11.2 매니퓰레이터 운동학

매니퓰레이터의 곱지수 공식에서 각 관절의 운동이 지수로 표현된다.

\mathbf{T}(\boldsymbol{\theta}) = e^{[\boldsymbol{\xi}_1]\theta_1}e^{[\boldsymbol{\xi}_2]\theta_2}\cdots e^{[\boldsymbol{\xi}_n]\theta_n}\mathbf{M}

각 지수 항이 한 관절의 변환이다.

11.3 운동 계획

운동 계획에서 두 자세 사이의 측지선 보간이 지수 사상을 사용한다.

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

이는 두 자세 사이의 자연스러운 보간이다.

11.4 비선형 최적화

비선형 최적화에서 자세 변수의 갱신이 지수 사상을 통해 이루어진다. 이는 변수가 다양체 위에 머물도록 보장한다.

11.5 시각적 SLAM

시각적 SLAM에서 카메라 자세의 갱신과 미분에 지수 사상이 활용된다. 비선형 최적화의 표준 도구이다.

12. 지수 사상의 라이브러리 지원

12.1 Eigen

Eigen은 행렬 지수를 직접 지원하지 않지만, 회전 행렬과 회전 벡터의 변환을 통해 \mathfrak{so}(3)의 지수 사상을 효과적으로 다룰 수 있다.

12.2 Sophus

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

Sophus::SO3d R = Sophus::SO3d::exp(omega);
Sophus::SE3d T = Sophus::SE3d::exp(xi);

12.3 manif

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

12.4 MATLAB

MATLAB의 expm 함수는 일반 행렬 지수를 계산한다.

13. 학습의 가치

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

  • 리 군과 리 대수의 연결을 명확히 한다.
  • 회전 벡터, 트위스트 등의 자세 표현이 자연스럽게 등장하는 이유를 이해한다.
  • 자세 추정 알고리즘의 갱신 단계를 깊이 이해할 수 있다.
  • 매니퓰레이터의 곱지수 공식을 이해하고 활용할 수 있다.
  • 측지선 보간과 운동 계획의 기초를 형성한다.

14. 참고 문헌

  • 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.
  • Moler, C., & Van Loan, C. (2003). “Nineteen dubious ways to compute the exponential of a matrix, twenty-five years later.” SIAM Review, 45(1), 3–49.

version: 1.0