6.120 로드리게스 공식과 회전의 지수 표현
1. 개요
3차원 공간에서의 회전은 로봇공학의 가장 기본적인 연산이다. 오일러의 회전 정리(Euler’s rotation theorem)에 의하면, 임의의 회전은 고정된 축을 중심으로 한 단일 회전으로 표현할 수 있다. 로드리게스(Rodrigues) 공식은 회전축과 회전각으로부터 회전 행렬을 직접 계산하는 닫힌 형태(closed-form)의 공식이며, 이는 반대칭 행렬의 행렬 지수와 정확히 일치한다. 본 절에서는 로드리게스 공식의 유도, 수학적 성질, 그리고 로봇공학에서의 다양한 응용을 다룬다.
2. 회전의 축-각 표현
2.1 기본 정의
임의의 회전은 단위 벡터 \hat{\boldsymbol{\omega}} \in \mathbb{R}^3 (\|\hat{\boldsymbol{\omega}}\| = 1)로 표현되는 회전축과 회전각 \theta \in [0, \pi]로 완전히 기술할 수 있다. 이 두 정보를 결합한 회전 벡터(rotation vector)는 다음과 같다.
\boldsymbol{\omega} = \theta\,\hat{\boldsymbol{\omega}}
회전 벡터의 방향은 회전축이고, 크기는 회전각이다. 회전의 양의 방향은 오른손 법칙(right-hand rule)을 따른다.
2.2 반대칭 행렬과 외적 연산자
벡터 \boldsymbol{\omega} = (\omega_1, \omega_2, \omega_3)^T에 대응하는 반대칭 행렬(skew-symmetric matrix)은 다음과 같이 정의한다.
[\boldsymbol{\omega}]_\times = \begin{bmatrix} 0 & -\omega_3 & \omega_2 \\ \omega_3 & 0 & -\omega_1 \\ -\omega_2 & \omega_1 & 0 \end{bmatrix}
이 행렬은 외적 연산을 행렬-벡터 곱으로 표현하는 역할을 한다. 즉, 임의의 벡터 \mathbf{p}에 대해 다음이 성립한다.
[\boldsymbol{\omega}]_\times \mathbf{p} = \boldsymbol{\omega} \times \mathbf{p}
반대칭 행렬의 집합 \mathfrak{so}(3) = \{\mathbf{S} \in \mathbb{R}^{3 \times 3} : \mathbf{S}^T = -\mathbf{S}\}는 회전 군 SO(3)의 리 대수(Lie algebra)를 구성한다.
3. 로드리게스 공식의 유도
3.1 행렬 지수로부터의 유도
단위 회전축 \hat{\boldsymbol{\omega}}에 대해 [\hat{\boldsymbol{\omega}}]_\times의 거듭제곱은 다음과 같은 주기적 성질을 갖는다.
[\hat{\boldsymbol{\omega}}]_\times^2 = \hat{\boldsymbol{\omega}}\hat{\boldsymbol{\omega}}^T - \mathbf{I}
[\hat{\boldsymbol{\omega}}]_\times^3 = -[\hat{\boldsymbol{\omega}}]_\times
[\hat{\boldsymbol{\omega}}]_\times^4 = -[\hat{\boldsymbol{\omega}}]_\times^2
[\hat{\boldsymbol{\omega}}]_\times^5 = [\hat{\boldsymbol{\omega}}]_\times
이 주기성을 이용하여 행렬 지수의 급수를 정리한다.
e^{\theta[\hat{\boldsymbol{\omega}}]_\times} = \sum_{k=0}^{\infty} \frac{\theta^k [\hat{\boldsymbol{\omega}}]_\times^k}{k!}
짝수 거듭제곱과 홀수 거듭제곱을 분리하면 다음과 같다.
e^{\theta[\hat{\boldsymbol{\omega}}]_\times} = \mathbf{I} + \left(\theta - \frac{\theta^3}{3!} + \frac{\theta^5}{5!} - \cdots\right)[\hat{\boldsymbol{\omega}}]_\times + \left(\frac{\theta^2}{2!} - \frac{\theta^4}{4!} + \frac{\theta^6}{6!} - \cdots\right)[\hat{\boldsymbol{\omega}}]_\times^2
괄호 안의 급수는 각각 \sin\theta와 1 - \cos\theta이므로 다음을 얻는다.
\boxed{e^{\theta[\hat{\boldsymbol{\omega}}]_\times} = \mathbf{I} + \sin\theta\,[\hat{\boldsymbol{\omega}}]_\times + (1 - \cos\theta)\,[\hat{\boldsymbol{\omega}}]_\times^2}
이것이 로드리게스 공식(Rodrigues’ rotation formula)이다.
3.2 벡터 형태의 로드리게스 공식
회전 행렬 \mathbf{R} = e^{\theta[\hat{\boldsymbol{\omega}}]_\times}을 벡터 \mathbf{p}에 적용하면 다음과 같다.
\mathbf{R}\mathbf{p} = \mathbf{p}\cos\theta + (\hat{\boldsymbol{\omega}} \times \mathbf{p})\sin\theta + \hat{\boldsymbol{\omega}}(\hat{\boldsymbol{\omega}} \cdot \mathbf{p})(1 - \cos\theta)
이 형태는 기하학적 해석이 명확하다.
- \mathbf{p}\cos\theta: 원래 벡터의 축소된 성분
- (\hat{\boldsymbol{\omega}} \times \mathbf{p})\sin\theta: 회전축에 수직인 평면 내의 회전 성분
- \hat{\boldsymbol{\omega}}(\hat{\boldsymbol{\omega}} \cdot \mathbf{p})(1 - \cos\theta): 회전축 방향 사영의 보정 성분
3.3 기하학적 유도
벡터 \mathbf{p}를 회전축 \hat{\boldsymbol{\omega}} 방향 성분과 수직 성분으로 분해한다.
\mathbf{p}_\parallel = (\hat{\boldsymbol{\omega}} \cdot \mathbf{p})\hat{\boldsymbol{\omega}}, \quad \mathbf{p}_\perp = \mathbf{p} - \mathbf{p}_\parallel
회전축 방향 성분 \mathbf{p}_\parallel은 회전에 의해 변하지 않는다. 수직 성분 \mathbf{p}_\perp는 \hat{\boldsymbol{\omega}}에 수직인 평면 내에서 \theta만큼 회전한다. 이 평면의 직교 기저를 \mathbf{p}_\perp와 \hat{\boldsymbol{\omega}} \times \mathbf{p}_\perp = \hat{\boldsymbol{\omega}} \times \mathbf{p}로 잡으면 다음과 같다.
\mathbf{R}\mathbf{p} = \mathbf{p}_\parallel + \mathbf{p}_\perp \cos\theta + (\hat{\boldsymbol{\omega}} \times \mathbf{p})\sin\theta
이를 전개하면 위의 벡터 형태와 동일한 결과를 얻는다.
4. 로드리게스 공식의 성질
4.1 직교성 보존
로드리게스 공식으로 계산한 \mathbf{R}이 직교 행렬임을 확인한다.
\mathbf{R}^T = \mathbf{I} - \sin\theta\,[\hat{\boldsymbol{\omega}}]_\times + (1 - \cos\theta)\,[\hat{\boldsymbol{\omega}}]_\times^2 = e^{-\theta[\hat{\boldsymbol{\omega}}]_\times}
따라서 \mathbf{R}^T\mathbf{R} = e^{-\theta[\hat{\boldsymbol{\omega}}]_\times} e^{\theta[\hat{\boldsymbol{\omega}}]_\times} = \mathbf{I}이다. 또한 \det(\mathbf{R}) = e^{\text{tr}(\theta[\hat{\boldsymbol{\omega}}]_\times)} = e^0 = 1이므로 \mathbf{R} \in SO(3)이다.
4.2 역회전
역회전은 부호를 바꾸어 얻는다.
\mathbf{R}^{-1} = \mathbf{R}^T = e^{-\theta[\hat{\boldsymbol{\omega}}]_\times} = \mathbf{I} - \sin\theta\,[\hat{\boldsymbol{\omega}}]_\times + (1 - \cos\theta)\,[\hat{\boldsymbol{\omega}}]_\times^2
4.3 특수한 경우
\theta = 0일 때: \mathbf{R} = \mathbf{I} (항등 회전)
\theta = \pi일 때: \sin\pi = 0이므로 다음과 같다.
\mathbf{R} = \mathbf{I} + 2[\hat{\boldsymbol{\omega}}]_\times^2 = 2\hat{\boldsymbol{\omega}}\hat{\boldsymbol{\omega}}^T - \mathbf{I}
이는 \hat{\boldsymbol{\omega}}축에 대한 180° 회전이다.
\theta = \pi/2일 때: \sin(\pi/2) = 1, \cos(\pi/2) = 0이므로 다음과 같다.
\mathbf{R} = \mathbf{I} + [\hat{\boldsymbol{\omega}}]_\times + [\hat{\boldsymbol{\omega}}]_\times^2 = \hat{\boldsymbol{\omega}}\hat{\boldsymbol{\omega}}^T + [\hat{\boldsymbol{\omega}}]_\times
5. 회전 행렬에서 축-각 추출
5.1 회전각의 추출
회전 행렬 \mathbf{R}로부터 회전각 \theta를 추출하려면 대각합(trace)을 이용한다. 로드리게스 공식에서 대각합을 취하면 다음과 같다.
\text{tr}(\mathbf{R}) = 3 - 2(1 - \cos\theta) = 1 + 2\cos\theta
따라서 회전각은 다음과 같다.
\theta = \arccos\left(\frac{\text{tr}(\mathbf{R}) - 1}{2}\right)
5.2 회전축의 추출
\theta \neq 0이고 \theta \neq \pi인 일반적인 경우, 회전축은 \mathbf{R}의 반대칭 부분으로부터 추출한다.
\mathbf{R} - \mathbf{R}^T = 2\sin\theta\,[\hat{\boldsymbol{\omega}}]_\times
따라서 다음과 같다.
[\hat{\boldsymbol{\omega}}]_\times = \frac{\mathbf{R} - \mathbf{R}^T}{2\sin\theta}
구체적으로 각 성분은 다음과 같다.
\hat{\boldsymbol{\omega}} = \frac{1}{2\sin\theta}\begin{bmatrix} R_{32} - R_{23} \\ R_{13} - R_{31} \\ R_{21} - R_{12} \end{bmatrix}
5.3 특이한 경우의 처리
\theta = 0인 경우: 회전축이 정의되지 않는다(항등 회전). 임의의 단위 벡터를 회전축으로 설정한다.
\theta = \pi인 경우: \sin\theta = 0이므로 반대칭 부분에서 축을 추출할 수 없다. 이 경우 \mathbf{R} + \mathbf{I} = 2\hat{\boldsymbol{\omega}}\hat{\boldsymbol{\omega}}^T를 이용한다. \mathbf{R} + \mathbf{I}의 영이 아닌 열벡터를 정규화하여 \hat{\boldsymbol{\omega}}를 얻는다.
\hat{\boldsymbol{\omega}} = \frac{(\mathbf{R} + \mathbf{I})\mathbf{e}_j}{\|(\mathbf{R} + \mathbf{I})\mathbf{e}_j\|}
여기서 \mathbf{e}_j는 (\mathbf{R} + \mathbf{I})의 열 중 가장 큰 노름을 갖는 열에 대응하는 단위 벡터이다.
5.4 수치적으로 안정한 구현
\theta가 0이나 \pi에 가까울 때 수치적 안정성을 위해 다음과 같은 전략을 사용한다.
\cos\theta와 \sin\theta를 동시에 사용하여 atan2 함수를 이용한다.
\theta = \text{atan2}\left(\|(\mathbf{R} - \mathbf{R}^T)^{\vee}\| / 2,\, (\text{tr}(\mathbf{R}) - 1)/2\right)
여기서 (\cdot)^{\vee}는 반대칭 행렬에서 벡터를 추출하는 연산자이다. 이 방법은 \arccos의 \theta \approx 0, \pi 근방에서의 민감도 문제를 회피한다.
6. SE(3)로의 확장
6.1 트위스트와 강체 운동의 지수 표현
강체 운동은 회전과 병진의 결합이다. 트위스트(twist) \boldsymbol{\xi} = (\boldsymbol{v}, \boldsymbol{\omega})^T \in \mathbb{R}^6에 대응하는 4 \times 4 행렬은 다음과 같다.
[\boldsymbol{\xi}] = \begin{bmatrix} [\boldsymbol{\omega}]_\times & \mathbf{v} \\ \mathbf{0}^T & 0 \end{bmatrix} \in \mathfrak{se}(3)
이 행렬의 지수는 동차 변환 행렬을 생성한다.
e^{\theta[\boldsymbol{\xi}]} = \begin{bmatrix} e^{\theta[\hat{\boldsymbol{\omega}}]_\times} & \mathbf{G}(\theta)\mathbf{v} \\ \mathbf{0}^T & 1 \end{bmatrix} \in SE(3)
여기서 \boldsymbol{\omega} \neq \mathbf{0}일 때, \hat{\boldsymbol{\omega}} = \boldsymbol{\omega}/\|\boldsymbol{\omega}\|이고 \mathbf{G}(\theta)는 다음과 같다.
\mathbf{G}(\theta) = \mathbf{I}\theta + (1 - \cos\theta)[\hat{\boldsymbol{\omega}}]_\times + (\theta - \sin\theta)[\hat{\boldsymbol{\omega}}]_\times^2
\|\boldsymbol{\omega}\| = 1로 정규화한 경우이며, 일반적인 \boldsymbol{\omega}에 대해서는 \theta = \|\boldsymbol{\omega}\|로 대체한다.
6.2 곱의 지수 공식(Product of Exponentials)
로봇 매니퓰레이터의 순기구학은 각 관절의 트위스트에 대한 지수의 곱으로 표현할 수 있다. n자유도 매니퓰레이터의 순기구학은 다음과 같다.
\mathbf{T}(\mathbf{q}) = e^{[\boldsymbol{\xi}_1]q_1}\, e^{[\boldsymbol{\xi}_2]q_2} \cdots e^{[\boldsymbol{\xi}_n]q_n}\, \mathbf{T}(0)
여기서 \boldsymbol{\xi}_i는 i번째 관절의 트위스트이고, q_i는 관절 변수이며, \mathbf{T}(0)은 기준 배치(reference configuration)에서의 말단 장치 변환이다.
이 표현은 DH 파라미터 방법과 동등한 정보를 담고 있으면서도, 좌표계를 각 관절에 부착할 필요가 없어 기하학적 직관이 명확하다는 장점이 있다.
7. 수치적 구현 시 주의사항
7.1 소각 근사
\theta가 매우 작을 때(\theta < 10^{-8} 정도), \sin\theta/\theta와 (1 - \cos\theta)/\theta^2의 직접 계산은 0/0 형태의 부정형이 될 수 있다. 이 경우 테일러 전개를 사용한다.
\frac{\sin\theta}{\theta} = 1 - \frac{\theta^2}{6} + \frac{\theta^4}{120} - \cdots
\frac{1 - \cos\theta}{\theta^2} = \frac{1}{2} - \frac{\theta^2}{24} + \frac{\theta^4}{720} - \cdots
배정밀도에서 \theta < 10^{-4} 정도면 첫 두 항만으로 기계 정밀도를 달성할 수 있다.
7.2 \theta \approx \pi 근방
\theta가 \pi에 가까울 때 \sin\theta \approx 0이므로, 회전축 추출에서 \sin\theta로 나누는 연산이 불안정해진다. 이 경우 \mathbf{R} + \mathbf{I} = 2\hat{\boldsymbol{\omega}}\hat{\boldsymbol{\omega}}^T를 이용하는 것이 수치적으로 안정적이다.
7.3 계산 효율
로드리게스 공식의 행렬 형태는 삼각함수 2회, 행렬 곱 1회([\hat{\boldsymbol{\omega}}]_\times^2), 스칼라-행렬 곱 2회, 행렬 합 2회로 계산할 수 있다. 이는 3 \times 3 행렬 곱의 일반적인 비용(O(27) 곱셈)보다 효율적이며, 반대칭 행렬의 구조를 이용하면 더욱 최적화할 수 있다.
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.
- Siciliano, B., Sciavicco, L., Villani, L., & Oriolo, G. (2009). Robotics: Modelling, Planning and Control. Springer.
- Selig, J. M. (2005). Geometric Fundamentals of Robotics (2nd ed.). Springer.
- Craig, J. J. (2005). Introduction to Robotics: Mechanics and Control (3rd ed.). Pearson Prentice Hall.
- Rodrigues, O. (1840). “Des lois géométriques qui régissent les déplacements d’un système solide dans l’espace.” Journal de Mathématiques Pures et Appliquées, 5, 380–440.
v 0.1