6.121 행렬 로그 함수와 역변환

1. 개요

행렬 로그 함수(matrix logarithm)는 행렬 지수 함수(matrix exponential)의 역연산이다. 로봇공학에서 행렬 로그는 회전 행렬이나 동차 변환 행렬로부터 대응하는 리 대수(Lie algebra) 원소를 추출하는 데 사용된다. 이는 회전 행렬에서 회전축과 회전각을 추출하거나, 강체 운동의 트위스트(twist) 표현을 얻는 과정에 해당한다. 본 절에서는 행렬 로그의 수학적 정의, 존재 조건, SO(3)SE(3)에서의 닫힌 형태 공식, 그리고 수치적 계산 방법을 다룬다.

2. 행렬 로그의 일반 이론

2.1 정의

정방 행렬 \mathbf{B} \in \mathbb{C}^{n \times n}에 대해, e^{\mathbf{X}} = \mathbf{B}를 만족하는 행렬 \mathbf{X}\mathbf{B}의 행렬 로그라 하고 \mathbf{X} = \log(\mathbf{B})로 표기한다.

스칼라 로그와 달리, 행렬 로그는 일반적으로 유일하지 않다. 예를 들어, 회전 행렬 \mathbf{R}에 대해 e^{\theta[\hat{\boldsymbol{\omega}}]_\times} = \mathbf{R}이면 e^{(\theta + 2k\pi)[\hat{\boldsymbol{\omega}}]_\times} = \mathbf{R}도 성립한다(k는 임의의 정수).

2.2 존재 조건

행렬 로그의 존재에 대한 기본 정리는 다음과 같다.

정리: 정방 행렬 \mathbf{B}가 가역(invertible)이면, \mathbf{B}의 행렬 로그가 존재한다. 즉, e^{\mathbf{X}} = \mathbf{B}를 만족하는 \mathbf{X}가 존재한다.

특히 \mathbf{B}의 모든 고유값이 양의 실수이면, 실수 행렬 로그가 존재한다.

2.3 급수 표현

\|\mathbf{B} - \mathbf{I}\| < 1인 경우, 행렬 로그는 다음과 같은 급수로 표현할 수 있다.

\log(\mathbf{B}) = \sum_{k=1}^{\infty} \frac{(-1)^{k+1}}{k}(\mathbf{B} - \mathbf{I})^k = (\mathbf{B} - \mathbf{I}) - \frac{(\mathbf{B} - \mathbf{I})^2}{2} + \frac{(\mathbf{B} - \mathbf{I})^3}{3} - \cdots

이 급수는 스칼라 로그 \ln(1+x) = x - x^2/2 + x^3/3 - \cdots의 자연스러운 확장이며, \|\mathbf{B} - \mathbf{I}\| < 1일 때 수렴한다. 그러나 수렴 반경이 제한적이므로 실용적인 계산에서는 다른 방법을 사용한다.

3. SO(3)에서의 행렬 로그

3.1 닫힌 형태 공식

회전 행렬 \mathbf{R} \in SO(3)에서 대응하는 반대칭 행렬 [\boldsymbol{\omega}]_\times \in \mathfrak{so}(3)를 구하는 것이 SO(3)에서의 행렬 로그이다. 로드리게스 공식의 역변환에 해당한다.

회전각 \theta는 다음과 같이 구한다.

\theta = \arccos\left(\frac{\text{tr}(\mathbf{R}) - 1}{2}\right), \quad \theta \in [0, \pi]

회전축의 반대칭 행렬 표현은 다음과 같다.

경우 1: \theta \neq 0이고 \theta \neq \pi인 일반적인 경우

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

따라서 행렬 로그는 다음과 같다.

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

경우 2: \theta = 0 (항등 회전)

\log(\mathbf{I}) = \mathbf{0}

경우 3: \theta = \pi

\sin\theta = 0이므로 경우 1의 공식을 직접 사용할 수 없다. 이 경우 \mathbf{R} + \mathbf{I} = 2\hat{\boldsymbol{\omega}}\hat{\boldsymbol{\omega}}^T를 이용하여 \hat{\boldsymbol{\omega}}를 먼저 구한 후 \log(\mathbf{R}) = \pi[\hat{\boldsymbol{\omega}}]_\times로 계산한다.

\mathbf{R} + \mathbf{I}의 열벡터 중 영이 아닌 것을 정규화하여 \hat{\boldsymbol{\omega}}를 얻는다. 수치적 안정성을 위해 가장 큰 노름의 열벡터를 선택한다.

3.2 유일성과 다가성

SO(3)에서의 행렬 로그는 \theta \in (0, \pi)일 때 유일하다(부호의 모호성을 제외하면). \theta = \pi일 때는 \hat{\boldsymbol{\omega}}-\hat{\boldsymbol{\omega}} 모두 유효하므로 두 개의 로그가 존재한다. \theta = 0일 때는 로그가 영행렬로 유일하다.

일반적으로, \theta + 2k\pi (k는 정수)에 대해서도 e^{(\theta+2k\pi)[\hat{\boldsymbol{\omega}}]_\times} = \mathbf{R}이 성립하므로, 행렬 로그는 무한히 많다. 주로그(principal logarithm)는 \theta \in [0, \pi]인 것으로 선택한다.

4. SE(3)에서의 행렬 로그

4.1 닫힌 형태 공식

동차 변환 행렬 \mathbf{T} \in SE(3)에 대해, 대응하는 트위스트의 행렬 표현 [\boldsymbol{\xi}] \in \mathfrak{se}(3)을 구한다.

\mathbf{T} = \begin{bmatrix} \mathbf{R} & \mathbf{p} \\ \mathbf{0}^T & 1 \end{bmatrix}, \quad [\boldsymbol{\xi}] = \begin{bmatrix} [\boldsymbol{\omega}]_\times & \mathbf{v} \\ \mathbf{0}^T & 0 \end{bmatrix}

먼저 \mathbf{R}로부터 \theta[\hat{\boldsymbol{\omega}}]_\times를 구한다(앞의 SO(3) 로그 공식 사용).

경우 1: \theta \neq 0인 경우

\mathbf{v} = \mathbf{G}^{-1}(\theta)\,\mathbf{p}

여기서 \mathbf{G}(\theta)의 역행렬은 다음과 같다.

\mathbf{G}^{-1}(\theta) = \frac{1}{\theta}\mathbf{I} - \frac{1}{2}[\hat{\boldsymbol{\omega}}]_\times + \left(\frac{1}{\theta} - \frac{1}{2}\cot\frac{\theta}{2}\right)[\hat{\boldsymbol{\omega}}]_\times^2

경우 2: \theta = 0 (\mathbf{R} = \mathbf{I}, 순수 병진)

[\boldsymbol{\xi}] = \begin{bmatrix} \mathbf{0} & \mathbf{p} \\ \mathbf{0}^T & 0 \end{bmatrix}

4.2 \mathbf{G}^{-1}의 유도

\mathbf{G}(\theta)는 다음과 같이 정의되었다.

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

[\hat{\boldsymbol{\omega}}]_\times^3 = -[\hat{\boldsymbol{\omega}}]_\times[\hat{\boldsymbol{\omega}}]_\times^2 = \hat{\boldsymbol{\omega}}\hat{\boldsymbol{\omega}}^T - \mathbf{I}를 이용하여, \mathbf{G}의 역행렬을 \mathbf{I}, [\hat{\boldsymbol{\omega}}]_\times, [\hat{\boldsymbol{\omega}}]_\times^2의 선형결합 형태로 구한다.

\mathbf{G}^{-1} = a\mathbf{I} + b[\hat{\boldsymbol{\omega}}]_\times + c[\hat{\boldsymbol{\omega}}]_\times^2로 놓고 \mathbf{G}\mathbf{G}^{-1} = \mathbf{I}를 전개하면, 계수를 결정할 수 있다.

a = \frac{1}{\theta}, \quad b = -\frac{1}{2}, \quad c = \frac{1}{\theta} - \frac{1}{2}\cot\frac{\theta}{2}

5. 일반 행렬의 로그 계산

5.1 역스케일링-제곱 방법

일반적인 가역 행렬 \mathbf{B}의 행렬 로그를 수치적으로 계산하는 가장 신뢰할 수 있는 방법은 역스케일링-제곱(inverse scaling and squaring) 방법이다. 이 방법은 다음 항등식에 기반한다.

\log(\mathbf{B}) = 2^s \log(\mathbf{B}^{1/2^s})

알고리즘은 다음과 같다.

  1. \mathbf{B}^{1/2^s}\mathbf{I}에 충분히 가까워질 때까지 반복적으로 행렬 제곱근을 계산한다
  2. \log(\mathbf{B}^{1/2^s})를 파데 근사로 계산한다
  3. 결과에 2^s를 곱한다

5.2 파데 근사에 의한 로그 계산

\|\mathbf{C}\| < 1\mathbf{C} = \mathbf{B} - \mathbf{I}에 대해, [m/m] 대각 파데 근사를 적용한다.

\log(\mathbf{I} + \mathbf{C}) \approx p_m(\mathbf{C})\,[q_m(\mathbf{C})]^{-1}

여기서 p_mq_m은 적절한 다항식이다.

5.3 슈어 분해 기반 방법

실수 행렬의 로그를 계산할 때, 실슈어 분해(real Schur decomposition)를 먼저 수행하면 수치적 안정성이 향상된다.

\mathbf{B} = \mathbf{Q}\mathbf{T}\mathbf{Q}^T

여기서 \mathbf{T}는 실준상삼각 행렬(real quasi-upper triangular matrix)이다. 그러면 다음과 같다.

\log(\mathbf{B}) = \mathbf{Q}\,\log(\mathbf{T})\,\mathbf{Q}^T

\log(\mathbf{T})1 \times 1 또는 2 \times 2 대각 블록의 로그를 먼저 계산하고, 비대각 블록은 시레스터(Sylvester) 방정식을 풀어 구한다.

6. 로봇공학에서의 응용

6.1 회전 보간

두 회전 행렬 \mathbf{R}_0\mathbf{R}_1 사이의 보간(interpolation)에 행렬 로그를 사용한다.

\mathbf{R}(t) = \mathbf{R}_0 \exp\left(t \cdot \log(\mathbf{R}_0^T \mathbf{R}_1)\right), \quad t \in [0, 1]

이 보간은 SO(3)의 측지선(geodesic)을 따르는 것으로, 일정한 각속도의 회전에 해당한다.

6.2 강체 운동의 보간

유사하게, 두 동차 변환 \mathbf{T}_0\mathbf{T}_1 사이의 보간은 다음과 같다.

\mathbf{T}(t) = \mathbf{T}_0 \exp\left(t \cdot \log(\mathbf{T}_0^{-1}\mathbf{T}_1)\right), \quad t \in [0, 1]

이 보간은 SE(3)의 나선형(screw) 운동에 해당하며, 슈비츠(Chasles)의 정리와 일치한다.

6.3 오차 계산

제어에서 현재 자세 \mathbf{R}_{\text{current}}와 목표 자세 \mathbf{R}_{\text{desired}} 사이의 오차를 리 대수 원소로 표현하면 다음과 같다.

[\mathbf{e}_R]_\times = \log(\mathbf{R}_{\text{current}}^T \mathbf{R}_{\text{desired}})

이 오차 표현은 배향 오차를 3차원 벡터로 나타내어 PD 제어기 등에 직접 사용할 수 있다.

\boldsymbol{\tau}_R = K_p \mathbf{e}_R + K_d \boldsymbol{\omega}_e

여기서 \boldsymbol{\omega}_e는 각속도 오차이다.

6.4 공간 야코비와 몸체 야코비

곱의 지수 공식(Product of Exponentials)에서 야코비 행렬은 행렬 로그의 미분을 통해 유도된다. 공간 야코비(space Jacobian)와 몸체 야코비(body Jacobian)의 변환 관계에도 행렬 로그가 관여한다.

7. 수치적 구현 시 주의사항

7.1 \theta \approx 0 근방

\theta가 매우 작을 때, \theta/(2\sin\theta) \approx 1/2 + \theta^2/12로 근사한다. 이 테일러 전개는 0/0 부정형을 회피한다.

\frac{\theta}{2\sin\theta} = \frac{1}{2} + \frac{\theta^2}{12} + \frac{7\theta^4}{720} + O(\theta^6)

7.2 \theta \approx \pi 근방

\sin\theta \approx 0이므로 1/(2\sin\theta)가 발산한다. 이 경우 \mathbf{R} + \mathbf{I}를 사용하는 대안적 알고리즘을 적용해야 한다. 또한 \cot(\theta/2)가 0에 가까워지므로 \mathbf{G}^{-1}의 계수 c도 수치적으로 불안정해질 수 있다.

7.3 \theta = \pi에서의 \mathbf{G}^{-1} 처리

\theta = \pi일 때, \cot(\pi/2) = 0이므로 c = 1/\pi가 되어 \mathbf{G}^{-1}은 유한한 값을 갖는다. 그러나 수치적으로 \theta\pi에 매우 가까울 때는 \cot(\theta/2)의 계산이 불안정해지므로, 별도의 테일러 전개나 극한값 대입이 필요하다.

7.4 구현 검증

행렬 로그의 구현을 검증하려면 다음과 같은 왕복(round-trip) 시험을 수행한다.

\|\exp(\log(\mathbf{R})) - \mathbf{R}\| < \epsilon, \quad \|\log(\exp(\mathbf{X})) - \mathbf{X}\| < \epsilon

다양한 \theta 값(특히 0, \pi, 그 근방)에 대해 이 시험을 통과하는지 확인한다.

8. 참고 문헌

  • 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.
  • Higham, N. J. (2008). Functions of Matrices: Theory and Computation. SIAM.
  • Selig, J. M. (2005). Geometric Fundamentals of Robotics (2nd ed.). Springer.
  • Siciliano, B., Sciavicco, L., Villani, L., & Oriolo, G. (2009). Robotics: Modelling, Planning and Control. Springer.
  • Al-Mohy, A. H., & Higham, N. J. (2012). “Improved Inverse Scaling and Squaring Algorithms for the Matrix Logarithm.” SIAM Journal on Scientific Computing, 34(4), C153–C169.

v 0.1