9.35 로드리게스 회전 공식의 유도
1. 목표
로드리게스 회전 공식(Rodrigues’ rotation formula)은 회전 축 \hat{\mathbf{u}}(단위 벡터)와 회전 각 \phi가 주어졌을 때, 이 축 주위의 회전에 의해 임의의 벡터 \mathbf{v}가 어떻게 변환되는지를 닫힌 형태로 기술하는 공식이다. 유도의 목표는 다음의 공식을 기하학적 논증으로부터 도출하는 것이다.
\mathbf{v}' = \mathbf{v}\cos\phi + (\hat{\mathbf{u}} \times \mathbf{v})\sin\phi + \hat{\mathbf{u}}(\hat{\mathbf{u}}^T\mathbf{v})(1 - \cos\phi)
이 벡터 공식으로부터 회전 행렬 형태
\mathbf{R}(\hat{\mathbf{u}}, \phi) = \mathbf{I} + \sin\phi\,[\hat{\mathbf{u}}]_\times + (1 - \cos\phi)\,[\hat{\mathbf{u}}]_\times^2
을 얻을 수 있다.
2. 벡터 분해에 기초한 기하학적 유도
2.1 벡터의 축 평행 및 수직 성분 분해
임의의 벡터 \mathbf{v} \in \mathbb{R}^3를 회전 축 \hat{\mathbf{u}}에 평행한 성분과 수직한 성분으로 분해한다.
\mathbf{v} = \mathbf{v}_\parallel + \mathbf{v}_\perp
여기서
\mathbf{v}_\parallel = (\hat{\mathbf{u}}^T\mathbf{v})\hat{\mathbf{u}} = \hat{\mathbf{u}}\hat{\mathbf{u}}^T\mathbf{v}
\mathbf{v}_\perp = \mathbf{v} - \mathbf{v}_\parallel = \mathbf{v} - \hat{\mathbf{u}}\hat{\mathbf{u}}^T\mathbf{v}
2.2 축 평행 성분은 회전에 불변
회전 축 위의 점은 회전에 의해 고정되므로, \mathbf{v}_\parallel의 회전 결과는 그 자신이다.
\mathbf{R}\mathbf{v}_\parallel = \mathbf{v}_\parallel
2.3 축 수직 성분은 평면 내에서 2차원 회전
\mathbf{v}_\perp는 \hat{\mathbf{u}}에 수직한 평면 내에 있다. 이 평면 내에서 \mathbf{v}_\perp의 회전은 2차원 회전과 동일하다. 2차원 회전은 직교 좌표를 구성하는 두 기저 벡터가 필요하며, 자연스러운 선택은 다음과 같다.
- 첫 번째 기저: \mathbf{v}_\perp 자체 (회전 전 위치)
- 두 번째 기저: \hat{\mathbf{u}} \times \mathbf{v}_\perp = \hat{\mathbf{u}} \times \mathbf{v} (외적 공식에 의해 \mathbf{v}_\parallel \times \hat{\mathbf{u}} = 0이므로)
두 기저 벡터는 \hat{\mathbf{u}}에 수직한 평면에 놓여 있으며 서로 직교한다. 또한 크기도 같다.
\lVert \hat{\mathbf{u}} \times \mathbf{v} \rVert = \lVert \hat{\mathbf{u}} \rVert \lVert \mathbf{v}_\perp \rVert \sin(\pi/2) = \lVert \mathbf{v}_\perp \rVert
(여기서 \hat{\mathbf{u}}와 \mathbf{v}_\perp가 서로 수직이므로.)
따라서 \{\mathbf{v}_\perp, \hat{\mathbf{u}} \times \mathbf{v}\}는 \hat{\mathbf{u}}에 수직한 평면의 정규 직교 기저(크기는 같음)를 구성한다.
2.4 차원 회전 공식 적용
\mathbf{v}_\perp를 \hat{\mathbf{u}} 주위로 \phi만큼 회전한 결과는 다음과 같다.
\mathbf{R}\mathbf{v}_\perp = \mathbf{v}_\perp\cos\phi + (\hat{\mathbf{u}} \times \mathbf{v})\sin\phi
이는 평면 내의 표준 2차원 회전 공식이다.
2.5 전체 회전의 합성
\mathbf{v} 전체의 회전은 축 평행 성분과 축 수직 성분의 합이다.
\mathbf{R}\mathbf{v} = \mathbf{R}\mathbf{v}_\parallel + \mathbf{R}\mathbf{v}_\perp = \mathbf{v}_\parallel + \mathbf{v}_\perp\cos\phi + (\hat{\mathbf{u}} \times \mathbf{v})\sin\phi
\mathbf{v}_\perp = \mathbf{v} - \mathbf{v}_\parallel을 대입하면
\mathbf{R}\mathbf{v} = \mathbf{v}_\parallel + (\mathbf{v} - \mathbf{v}_\parallel)\cos\phi + (\hat{\mathbf{u}} \times \mathbf{v})\sin\phi
= \mathbf{v}\cos\phi + \mathbf{v}_\parallel(1 - \cos\phi) + (\hat{\mathbf{u}} \times \mathbf{v})\sin\phi
\mathbf{v}_\parallel = \hat{\mathbf{u}}(\hat{\mathbf{u}}^T\mathbf{v})를 대입하여 최종 공식을 얻는다.
\boxed{\mathbf{R}\mathbf{v} = \mathbf{v}\cos\phi + (\hat{\mathbf{u}} \times \mathbf{v})\sin\phi + \hat{\mathbf{u}}(\hat{\mathbf{u}}^T\mathbf{v})(1 - \cos\phi)}
3. 행렬 형태로의 변환
3.1 외적의 반대칭 행렬 표현
외적 \hat{\mathbf{u}} \times \mathbf{v}는 반대칭 행렬 [\hat{\mathbf{u}}]_\times를 이용하여 행렬 곱으로 표현된다.
\hat{\mathbf{u}} \times \mathbf{v} = [\hat{\mathbf{u}}]_\times \mathbf{v}
[\hat{\mathbf{u}}]_\times = \begin{bmatrix}0 & -u_z & u_y \\ u_z & 0 & -u_x \\ -u_y & u_x & 0\end{bmatrix}
3.2 외적의 스칼라 곱
\hat{\mathbf{u}}(\hat{\mathbf{u}}^T\mathbf{v})는 랭크 1의 투영 행렬을 이용해
\hat{\mathbf{u}}(\hat{\mathbf{u}}^T\mathbf{v}) = (\hat{\mathbf{u}}\hat{\mathbf{u}}^T)\mathbf{v}
로 표현된다.
3.3 벡터 공식을 행렬 공식으로 변환
로드리게스의 벡터 공식을 \mathbf{v}에 대해 묶으면
\mathbf{R}\mathbf{v} = [\cos\phi\,\mathbf{I} + \sin\phi\,[\hat{\mathbf{u}}]_\times + (1 - \cos\phi)\,\hat{\mathbf{u}}\hat{\mathbf{u}}^T]\mathbf{v}
이 되므로
\mathbf{R}(\hat{\mathbf{u}}, \phi) = \cos\phi\,\mathbf{I} + \sin\phi\,[\hat{\mathbf{u}}]_\times + (1 - \cos\phi)\,\hat{\mathbf{u}}\hat{\mathbf{u}}^T
이 성립한다.
3.4 대체 형태
[\hat{\mathbf{u}}]_\times^2 = \hat{\mathbf{u}}\hat{\mathbf{u}}^T - \mathbf{I}라는 항등식을 이용하면
\hat{\mathbf{u}}\hat{\mathbf{u}}^T = \mathbf{I} + [\hat{\mathbf{u}}]_\times^2
이고, 이를 대입하면
\mathbf{R} = \cos\phi\,\mathbf{I} + \sin\phi\,[\hat{\mathbf{u}}]_\times + (1 - \cos\phi)(\mathbf{I} + [\hat{\mathbf{u}}]_\times^2)
= \mathbf{I} + \sin\phi\,[\hat{\mathbf{u}}]_\times + (1 - \cos\phi)\,[\hat{\mathbf{u}}]_\times^2
이 된다. 이것이 로드리게스 공식의 표준적 행렬 형태이다.
4. 행렬 지수 관점에서의 유도
4.1 행렬 지수의 정의
\phi[\hat{\mathbf{u}}]_\times의 행렬 지수는 다음의 테일러 급수로 정의된다.
\exp(\phi[\hat{\mathbf{u}}]_\times) = \sum_{k=0}^\infty \frac{\phi^k}{k!}[\hat{\mathbf{u}}]_\times^k
4.2 반대칭 행렬의 거듭제곱 패턴
[\hat{\mathbf{u}}]_\times가 단위 벡터의 반대칭 행렬이면, 다음의 항등식이 성립한다.
[\hat{\mathbf{u}}]_\times^3 = -[\hat{\mathbf{u}}]_\times
이로부터 거듭제곱의 패턴을 얻는다.
- 홀수 거듭제곱: [\hat{\mathbf{u}}]_\times, -[\hat{\mathbf{u}}]_\times, [\hat{\mathbf{u}}]_\times, -[\hat{\mathbf{u}}]_\times, \ldots
- 짝수 거듭제곱 (2 이상): [\hat{\mathbf{u}}]_\times^2, -[\hat{\mathbf{u}}]_\times^2, [\hat{\mathbf{u}}]_\times^2, \ldots
4.3 급수의 재정렬
테일러 급수를 \mathbf{I}, [\hat{\mathbf{u}}]_\times, [\hat{\mathbf{u}}]_\times^2의 계수로 분리한다.
\exp(\phi[\hat{\mathbf{u}}]_\times) = \mathbf{I} + \left(\phi - \frac{\phi^3}{3!} + \frac{\phi^5}{5!} - \cdots\right)[\hat{\mathbf{u}}]_\times + \left(\frac{\phi^2}{2!} - \frac{\phi^4}{4!} + \cdots\right)[\hat{\mathbf{u}}]_\times^2
각 괄호의 급수는 각각 \sin\phi와 1 - \cos\phi의 테일러 급수이다.
\sin\phi = \phi - \frac{\phi^3}{3!} + \frac{\phi^5}{5!} - \cdots
1 - \cos\phi = \frac{\phi^2}{2!} - \frac{\phi^4}{4!} + \cdots
4.4 닫힌 형태의 완성
대입하면
\exp(\phi[\hat{\mathbf{u}}]_\times) = \mathbf{I} + \sin\phi\,[\hat{\mathbf{u}}]_\times + (1 - \cos\phi)\,[\hat{\mathbf{u}}]_\times^2
이 되어 로드리게스 공식이 다시 확인된다. 이 유도는 로드리게스 공식이 \mathfrak{so}(3)에서 SO(3)으로의 지수 사상의 닫힌 형태임을 보여준다.
5. 유도의 의미와 일반화
5.1 기하학적 유도와 대수적 유도의 대응
기하학적 유도는 벡터 분해에 의한 직관을 제공하며, 대수적 유도는 행렬 지수의 닫힌 형태를 보여준다. 두 유도는 동일한 결과를 제공하나, 각각 서로 다른 관점을 제시한다.
- 기하학적 유도: 물리적 직관과 시각화에 적합
- 대수적 유도: 일반화와 고차원 확장에 적합
5.2 고차원 회전으로의 일반화
대수적 유도는 SO(n)의 반대칭 행렬로 일반화될 수 있으나, 닫힌 형태는 3차원에서만 로드리게스 공식과 같이 간결하게 나타난다. 이는 3차원에서 반대칭 행렬의 특이한 대수적 구조 때문이다.
6. 로봇 공학에서의 사용
로드리게스 공식은 로봇 공학의 다음 분야에서 핵심적으로 사용된다.
- 자세 갱신: 각속도 벡터로부터 회전 증분을 계산하여 자세를 갱신할 때
- 축-각도 입력 처리: 축과 각도로 지정된 회전 명령을 회전 행렬로 변환할 때
- 지수 사상 구현: 리 대수에서 리 군으로의 사상을 수치적으로 계산할 때
- 스크류 운동 분해: 강체 운동을 축-각도 성분으로 분해할 때
7. 참고 문헌
- 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.
- Murray, R. M., Li, Z., & Sastry, S. S. (1994). A Mathematical Introduction to Robotic Manipulation. CRC Press.
- Hall, B. C. (2015). Lie Groups, Lie Algebras, and Representations (2nd ed.). Springer.
- Barfoot, T. D. (2017). State Estimation for Robotics. Cambridge University Press.
- Shuster, M. D. (1993). “A Survey of Attitude Representations.” Journal of the Astronautical Sciences, 41(4), 439–517.
version: 1.0