659.53 3D 회전 표현: 회전 행렬 (Rotation Matrix) 기초

1. 개요

회전 행렬(rotation matrix)은 3차원 공간에서의 회전을 3 \times 3 직교 행렬로 표현하는 방법이다. 회전 행렬은 선형대수학의 기본 도구인 행렬-벡터 곱을 통해 벡터 변환을 수행하므로, 좌표 변환의 수학적 체계에 자연스럽게 통합된다. 특이점이 존재하지 않고, 회전 합성이 행렬 곱셈으로 직관적으로 이루어지며, 벡터 변환이 단일 행렬-벡터 곱으로 수행된다는 장점이 있다. 반면 9개의 파라미터와 6개의 구속 조건으로 3자유도를 표현하는 과잉 매개변수화(over-parameterization)의 특성을 가진다. 본 절에서는 회전 행렬의 수학적 정의, 대수적 성질, 기본 회전 행렬, 그리고 ROS2 및 TF2 환경에서의 활용을 체계적으로 다룬다.

2. 회전 행렬의 수학적 정의

2.1 정의

회전 행렬 R은 다음 두 조건을 동시에 만족하는 3 \times 3 실수 행렬이다:

R^T R = R R^T = I_3 \quad \text{(직교 조건)}

\det(R) = +1 \quad \text{(고유 회전 조건)}

첫 번째 조건은 R이 **직교 행렬(orthogonal matrix)**임을 의미한다. 직교 행렬은 내적과 노름을 보존하는 선형 변환에 대응한다. 두 번째 조건은 반사(reflection)를 배제하고 순수한 회전만을 나타내기 위한 것이다. 행렬식이 -1인 직교 행렬은 회전이 아닌 부적절한 회전(improper rotation, 즉 반사를 포함하는 변환)에 해당한다.

이 두 조건을 만족하는 행렬의 집합은 특수 직교군(special orthogonal group) SO(3)을 형성한다:

SO(3) = \{R \in \mathbb{R}^{3 \times 3} \mid R^T R = I_3, \; \det(R) = +1\}

2.2 구속 조건의 분석

3 \times 3 행렬은 9개의 독립 원소를 가진다. 직교 조건 R^T R = I_3은 대칭 행렬 R^T R에 대한 조건이므로, 6개의 독립적인 스칼라 방정식을 제공한다:

  • 3개의 단위 벡터 조건: 각 열벡터의 노름이 1이어야 한다.

\|\mathbf{r}_1\| = 1, \quad \|\mathbf{r}_2\| = 1, \quad \|\mathbf{r}_3\| = 1

  • 3개의 직교성 조건: 서로 다른 열벡터 쌍이 직교해야 한다.

\mathbf{r}_1 \cdot \mathbf{r}_2 = 0, \quad \mathbf{r}_2 \cdot \mathbf{r}_3 = 0, \quad \mathbf{r}_1 \cdot \mathbf{r}_3 = 0

여기서 \mathbf{r}_1, \mathbf{r}_2, \mathbf{r}_3R의 열벡터이다. 9개의 파라미터에서 6개의 구속 조건을 빼면 9 - 6 = 3자유도가 남으며, 이는 3D 회전의 자유도와 일치한다.

행렬식 조건 \det(R) = +1은 직교 조건으로부터 \det(R) = \pm 1이 보장되므로, 추가적인 자유도를 제거하지 않고 부호만 선택하는 역할을 한다.

3. 회전 행렬의 기하학적 해석

3.1 열벡터의 의미

회전 행렬 R의 열벡터는 회전된 좌표계의 기저 벡터(basis vector)를 전역 좌표계에서 표현한 것이다:

R = \begin{pmatrix} | & | & | \\ \mathbf{r}_1 & \mathbf{r}_2 & \mathbf{r}_3 \\ | & | & | \end{pmatrix}

  • \mathbf{r}_1: 회전된 좌표계의 x축 단위 벡터 (전역 좌표계 기준)
  • \mathbf{r}_2: 회전된 좌표계의 y축 단위 벡터 (전역 좌표계 기준)
  • \mathbf{r}_3: 회전된 좌표계의 z축 단위 벡터 (전역 좌표계 기준)

따라서 회전 행렬은 하나의 좌표계에서 다른 좌표계로의 **기저 변환(change of basis)**을 행렬로 표현한 것이다.

3.2 행벡터의 의미

회전 행렬의 행벡터는 전역 좌표계의 기저 벡터를 회전된 좌표계에서 표현한 것이다. 이는 R^T = R^{-1} 관계로부터 도출되며, 역변환(회전된 좌표계에서 전역 좌표계로의 변환)에서의 기저 벡터에 해당한다.

3.3 벡터 변환

회전 행렬 R에 의한 벡터 \mathbf{v}의 변환은 행렬-벡터 곱으로 수행된다:

\mathbf{v}' = R \mathbf{v}

이 변환은 다음의 성질을 보존한다:

  1. 길이 보존: \|\mathbf{v}'\| = \|R\mathbf{v}\| = \|\mathbf{v}\|
  2. 각도 보존: 두 벡터 사이의 각도가 변환 후에도 동일하다.
  3. 내적 보존: \mathbf{u}' \cdot \mathbf{v}' = (R\mathbf{u}) \cdot (R\mathbf{v}) = \mathbf{u} \cdot \mathbf{v}
  4. 외적 보존: \mathbf{u}' \times \mathbf{v}' = R(\mathbf{u} \times \mathbf{v})
  5. 방향 보존: \det(R) = +1이므로 좌표계의 손잡이성(handedness)이 보존된다.

4. 좌표축 기준 기본 회전 행렬

4.1 x축 기준 회전

x축을 중심으로 각도 \alpha만큼 회전하는 행렬:

R_x(\alpha) = \begin{pmatrix} 1 & 0 & 0 \\ 0 & \cos\alpha & -\sin\alpha \\ 0 & \sin\alpha & \cos\alpha \end{pmatrix}

x축은 고정되고, yz-평면 내에서 회전이 이루어진다.

4.2 y축 기준 회전

R_y(\beta) = \begin{pmatrix} \cos\beta & 0 & \sin\beta \\ 0 & 1 & 0 \\ -\sin\beta & 0 & \cos\beta \end{pmatrix}

y축 회전 행렬에서 \sin 항의 부호 패턴이 R_x, R_z와 다르다는 점에 주의해야 한다. 이는 R_y를 3차원 기본 회전 행렬의 일반 패턴에서 도출할 때, 순환 치환(cyclic permutation)에 의한 부호 변경에 기인한다.

4.3 z축 기준 회전

R_z(\gamma) = \begin{pmatrix} \cos\gamma & -\sin\gamma & 0 \\ \sin\gamma & \cos\gamma & 0 \\ 0 & 0 & 1 \end{pmatrix}

4.4 기본 회전 행렬의 공통 성질

모든 기본 회전 행렬은 다음의 성질을 만족한다:

  1. R_{\text{axis}}(0) = I_3 (영 회전은 항등 변환)
  2. R_{\text{axis}}(\alpha)^{-1} = R_{\text{axis}}(-\alpha) = R_{\text{axis}}(\alpha)^T (역회전은 전치)
  3. R_{\text{axis}}(\alpha) R_{\text{axis}}(\beta) = R_{\text{axis}}(\alpha + \beta) (동축 회전의 가환성)
  4. \det(R_{\text{axis}}(\alpha)) = \cos^2\alpha + \sin^2\alpha = 1

성질 3은 동일한 축에 대한 회전에서만 성립한다. 서로 다른 축에 대한 회전 행렬의 곱은 교환법칙이 성립하지 않는다:

R_x(\alpha) R_y(\beta) \neq R_y(\beta) R_x(\alpha) \quad \text{(일반적으로)}

5. 회전 행렬의 대수적 성질

5.1 군 구조

SO(3)은 행렬 곱셈에 대해 **군(group)**을 형성한다:

공리조건설명
닫힘 (Closure)R_1, R_2 \in SO(3) \Rightarrow R_1 R_2 \in SO(3)두 회전의 합성은 회전
결합법칙(R_1 R_2) R_3 = R_1 (R_2 R_3)행렬 곱셈은 결합적
항등원I_3 R = R I_3 = R항등 행렬은 회전 없음
역원R R^{-1} = R^{-1} R = I_3R^{-1} = R^T

SO(3)은 교환법칙을 만족하지 않으므로 **비가환군(non-abelian group)**이다.

5.2 역행렬과 전치 행렬의 관계

직교 행렬의 핵심 성질로서, 역행렬이 전치 행렬과 동일하다:

R^{-1} = R^T

이 성질은 역회전 계산을 매우 효율적으로 만든다. 일반적인 3 \times 3 행렬의 역행렬 계산은 O(n^3)의 복잡도를 가지지만, 회전 행렬의 역은 원소 재배치만으로 O(n^2)에 완료된다. 실질적으로는 메모리 내 원소의 인덱스 교환만 필요하므로, 추가적인 산술 연산이 필요 없다.

5.3 고유값과 고유벡터

모든 회전 행렬은 다음의 고유값 구조를 갖는다:

\lambda_1 = 1, \quad \lambda_2 = e^{i\theta}, \quad \lambda_3 = e^{-i\theta}

여기서 \theta는 회전 각도이다. 고유값 \lambda_1 = 1에 대응하는 고유벡터는 회전축이다. 이 사실은 오일러 회전 정리의 한 형태이며, 임의의 회전을 축-각 표현으로 변환할 때 활용된다.

고유값의 합(대각합)은:

\text{tr}(R) = 1 + 2\cos\theta

따라서 회전 각도를 회전 행렬의 대각합으로부터 구할 수 있다:

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

6. ROS2/TF2에서의 회전 행렬

6.1 tf2에서의 행렬 표현

TF2 라이브러리에서 회전 행렬은 tf2::Matrix3x3 클래스로 표현된다:

#include <tf2/LinearMath/Matrix3x3.h>
#include <tf2/LinearMath/Quaternion.h>

// 쿼터니언에서 회전 행렬 생성
tf2::Quaternion q;
q.setRPY(0.1, 0.2, 0.3);
tf2::Matrix3x3 R(q);

// 행렬 원소 접근
double r00 = R[0][0];  // 첫 번째 행, 첫 번째 열
double r12 = R[1][2];  // 두 번째 행, 세 번째 열

// 회전 행렬에서 RPY 추출
double roll, pitch, yaw;
R.getRPY(roll, pitch, yaw);

// 회전 행렬에서 쿼터니언 추출
tf2::Quaternion q_from_matrix;
R.getRotation(q_from_matrix);

6.2 Eigen 라이브러리 연동

ROS2 생태계에서 Eigen 라이브러리는 선형대수 연산의 표준 도구이며, tf2_eigen 패키지를 통해 TF2와 연동된다:

#include <Eigen/Geometry>
#include <tf2_eigen/tf2_eigen.hpp>

// Eigen 회전 행렬 생성
Eigen::Matrix3d R = Eigen::AngleAxisd(0.3, Eigen::Vector3d::UnitZ())
                   * Eigen::AngleAxisd(0.2, Eigen::Vector3d::UnitY())
                   * Eigen::AngleAxisd(0.1, Eigen::Vector3d::UnitX());

// 쿼터니언으로 변환
Eigen::Quaterniond q(R);

// 벡터 회전
Eigen::Vector3d v(1.0, 0.0, 0.0);
Eigen::Vector3d v_rotated = R * v;
# Python (SciPy)
from scipy.spatial.transform import Rotation
import numpy as np

# 회전 행렬 생성
r = Rotation.from_euler('xyz', [0.1, 0.2, 0.3])
R = r.as_matrix()  # 3x3 NumPy 배열

# 벡터 회전
v = np.array([1.0, 0.0, 0.0])
v_rotated = R @ v

# 회전 행렬에서 쿼터니언으로 변환
q = r.as_quat()  # [x, y, z, w]

# 회전 행렬에서 오일러 각으로 변환
euler = r.as_euler('xyz')  # [roll, pitch, yaw]

7. 회전 행렬과 다른 표현 방법의 비교

특성회전 행렬쿼터니언오일러 각
파라미터 수943
구속 조건 수610
자유도333
특이점없음없음있음 (짐벌 락)
벡터 회전15 FLOPs21 FLOPsN/A (행렬로 변환 필요)
합성45 FLOPs28 FLOPs삼각함수 연산
역변환전치 (0 FLOPs)켤레 (3 FLOPs)별도 공식 필요
정규화/직교화SVD (~81 FLOPs)9 FLOPsN/A
메모리72 바이트32 바이트24 바이트
직관성중간낮음높음

단일 벡터 변환에서는 회전 행렬이 최소 연산량(15 FLOPs)을 제공한다. 그러나 다수의 회전 합성이 필요한 관절 체인이나 연속적 변환에서는 쿼터니언이 더 효율적이며, 정규화 비용도 현저히 낮다.

8. 로드리게스 회전 공식

임의의 단위 벡터 \hat{\mathbf{n}}을 축으로 각도 \theta만큼 회전하는 회전 행렬은 로드리게스 공식(Rodrigues’ rotation formula)으로 직접 구성할 수 있다:

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

여기서 [\hat{\mathbf{n}}]_\times는 벡터 \hat{\mathbf{n}} = (n_x, n_y, n_z)^T의 반대칭 행렬(skew-symmetric matrix)이다:

[\hat{\mathbf{n}}]_\times = \begin{pmatrix} 0 & -n_z & n_y \\ n_z & 0 & -n_x \\ -n_y & n_x & 0 \end{pmatrix}

이 공식은 축-각 표현에서 회전 행렬로의 직접 변환을 제공하며, 쿼터니언을 경유하지 않고도 회전 행렬을 구성할 수 있게 한다.

Eigen::Matrix3d rodrigues(const Eigen::Vector3d& axis, double angle) {
    Eigen::Matrix3d K;
    K << 0, -axis.z(), axis.y(),
         axis.z(), 0, -axis.x(),
         -axis.y(), axis.x(), 0;
    
    return Eigen::Matrix3d::Identity() 
         + std::sin(angle) * K 
         + (1.0 - std::cos(angle)) * K * K;
}

9. 요약

회전 행렬은 SO(3)의 원소로서, 직교 조건 R^T R = I와 행렬식 조건 \det(R) = +1을 만족하는 3 \times 3 실수 행렬이다. 9개의 파라미터와 6개의 구속 조건으로 3자유도 회전을 과잉 매개변수화하지만, 특이점이 없고, 벡터 변환이 행렬-벡터 곱으로 효율적으로 수행되며, 역변환이 전치로 완료된다는 장점이 있다. 기본 회전 행렬의 곱으로 임의의 회전을 합성할 수 있으며, 로드리게스 공식을 통해 축-각 표현으로부터 직접 구성할 수도 있다. ROS2에서는 tf2::Matrix3x3Eigen::Matrix3d를 통해 회전 행렬을 활용하며, 쿼터니언과의 상호 변환이 자유롭게 지원된다.

10. 참고 문헌

  • Craig, J. J. (2005). Introduction to Robotics: Mechanics and Control (3rd Edition). Pearson Prentice Hall.
  • Siciliano, B. et al. (2010). Robotics: Modelling, Planning and Control. Springer.
  • Murray, R. M., Li, Z., & Sastry, S. S. (1994). A Mathematical Introduction to Robotic Manipulation. CRC Press.
  • Rodrigues, O. (1840). “Des lois géométriques qui régissent les déplacements d’un système solide.” Journal de Mathématiques Pures et Appliquées, 5, 380-440.
  • Strang, G. (2016). Introduction to Linear Algebra (5th Edition). Wellesley-Cambridge Press.
  • Open Robotics. “tf2 — ROS 2 Documentation.” https://docs.ros.org/en/rolling/Concepts/Intermediate/About-Tf2.html