659.55 3D 회전 표현: 축-각 (Axis-Angle) 표현
1. 개요
축-각(axis-angle) 표현은 3차원 회전을 하나의 회전축(rotation axis) 벡터와 그 축에 대한 **회전 각도(rotation angle)**로 기술하는 방법이다. 이 표현은 오일러 회전 정리(Euler’s rotation theorem)에 직접 기반하며, 임의의 3D 회전이 고정점을 지나는 하나의 축에 대한 단일 회전으로 유일하게 기술될 수 있다는 정리의 내용을 수학적으로 형식화한 것이다. 축-각 표현은 쿼터니언 및 회전 행렬과의 변환이 명시적이고 직관적이며, 회전의 물리적 의미를 가장 직접적으로 반영한다는 특성을 가진다. 본 절에서는 축-각 표현의 수학적 정의, 다른 회전 표현과의 관계, 장단점, 그리고 ROS2에서의 활용을 체계적으로 다룬다.
2. 오일러 회전 정리
2.1 정리의 내용
오일러 회전 정리(Euler’s rotation theorem, 1775)는 다음을 진술한다:
3차원 공간에서 고정점을 가지는 강체의 임의의 변위(displacement)는 해당 고정점을 지나는 어떤 축에 대한 단일 회전으로 나타낼 수 있다.
수학적으로 표현하면, 임의의 회전 행렬 R \in SO(3)에 대해, 단위 벡터 \hat{\mathbf{n}} \in \mathbb{R}^3과 각도 \theta \in [0, \pi]가 존재하여 R이 \hat{\mathbf{n}}을 축으로 한 각도 \theta의 회전에 해당한다.
2.2 증명의 핵심
증명의 핵심은 회전 행렬이 반드시 고유값 \lambda = 1을 가진다는 사실에 기반한다. R \in SO(3)의 특성 다항식은 3차 실수 계수 다항식이므로 적어도 하나의 실수 고유값을 가지며, \det(R) = +1과 직교 조건으로부터 이 실수 고유값이 +1임이 보장된다. 고유값 +1에 대응하는 고유벡터가 바로 회전축이다:
R \hat{\mathbf{n}} = \hat{\mathbf{n}}
3. 축-각 표현의 정의
3.1 기본 형식
축-각 표현은 다음 두 요소로 구성된다:
(\hat{\mathbf{n}}, \theta)
여기서:
- \hat{\mathbf{n}} = (n_x, n_y, n_z)^T: 회전축의 단위 벡터, \|\hat{\mathbf{n}}\| = 1
- \theta: 오른손 법칙에 따른 회전 각도
회전 방향은 오른손 법칙에 의해 결정된다. \hat{\mathbf{n}}의 방향을 오른손 엄지손가락으로 가리킬 때, 나머지 손가락이 감기는 방향이 양의 회전 방향이다.
3.2 회전 벡터 (Rotation Vector) 형식
축과 각도를 하나의 벡터로 통합하여 표현할 수 있다:
\boldsymbol{\theta} = \theta \hat{\mathbf{n}} \in \mathbb{R}^3
이 3차원 벡터를 **회전 벡터(rotation vector)**라 한다. 회전 벡터의 방향이 회전축, 크기(노름)가 회전 각도를 나타낸다:
\hat{\mathbf{n}} = \frac{\boldsymbol{\theta}}{\|\boldsymbol{\theta}\|}, \quad \theta = \|\boldsymbol{\theta}\|
회전 벡터는 3개의 파라미터만으로 회전을 표현하며, 구속 조건이 없다는 점에서 오일러 각과 동일한 파라미터 효율성을 가진다. 그러나 \theta = 0 (항등 회전) 근방과 \theta = \pi (180° 회전) 근방에서 특이성이 존재한다.
3.3 파라미터 범위와 유일성
축-각 표현의 유일성 조건은 다음과 같다:
| 각도 범위 | 축의 유일성 | 표현의 유일성 |
|---|---|---|
| \theta = 0 | \hat{\mathbf{n}} 부정 (어떤 축이든 가능) | 비유일 |
| 0 < \theta < \pi | \hat{\mathbf{n}} 유일 | 유일 |
| \theta = \pi | \hat{\mathbf{n}}과 -\hat{\mathbf{n}}이 동일한 회전 | 비유일 (부호 모호) |
| \theta > \pi | (\hat{\mathbf{n}}, \theta)와 (-\hat{\mathbf{n}}, 2\pi - \theta)이 동일 | 비유일 |
따라서 \theta \in (0, \pi) 범위에서만 표현이 유일하며, 경계값에서는 주의가 필요하다.
4. 로드리게스 회전 공식
4.1 벡터 회전 공식
단위 벡터 \hat{\mathbf{n}}을 축으로 각도 \theta만큼 벡터 \mathbf{v}를 회전시키는 공식:
\mathbf{v}' = \mathbf{v}\cos\theta + (\hat{\mathbf{n}} \times \mathbf{v})\sin\theta + \hat{\mathbf{n}}(\hat{\mathbf{n}} \cdot \mathbf{v})(1 - \cos\theta)
이 공식의 각 항의 기하학적 의미는:
- \mathbf{v}\cos\theta: 원래 벡터를 \cos\theta로 축소
- (\hat{\mathbf{n}} \times \mathbf{v})\sin\theta: 회전 평면 내의 수직 성분
- \hat{\mathbf{n}}(\hat{\mathbf{n}} \cdot \mathbf{v})(1 - \cos\theta): 축 방향 사영의 보정
4.2 회전 행렬 형식
로드리게스 공식의 행렬 형식:
R(\hat{\mathbf{n}}, \theta) = I + (\sin\theta)[\hat{\mathbf{n}}]_\times + (1 - \cos\theta)[\hat{\mathbf{n}}]_\times^2
여기서 [\hat{\mathbf{n}}]_\times는 반대칭 행렬(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}
이 반대칭 행렬에 대해 [\hat{\mathbf{n}}]_\times \mathbf{v} = \hat{\mathbf{n}} \times \mathbf{v}가 성립한다. 또한 [\hat{\mathbf{n}}]_\times^2 = \hat{\mathbf{n}}\hat{\mathbf{n}}^T - I (단위 벡터인 경우)이므로, 회전 행렬을 다음과 같이 전개할 수도 있다:
R = \cos\theta \cdot I + (1 - \cos\theta) \hat{\mathbf{n}}\hat{\mathbf{n}}^T + \sin\theta \cdot [\hat{\mathbf{n}}]_\times
#include <Eigen/Geometry>
Eigen::Matrix3d axis_angle_to_matrix(
const Eigen::Vector3d& axis, double angle)
{
return Eigen::AngleAxisd(angle, axis.normalized()).toRotationMatrix();
}
// 수동 구현 (로드리게스 공식)
Eigen::Matrix3d rodrigues_formula(
const Eigen::Vector3d& n, double theta)
{
Eigen::Matrix3d K;
K << 0, -n.z(), n.y(),
n.z(), 0, -n.x(),
-n.y(), n.x(), 0;
return Eigen::Matrix3d::Identity()
+ std::sin(theta) * K
+ (1.0 - std::cos(theta)) * K * K;
}
5. 다른 회전 표현과의 변환
5.1 축-각에서 쿼터니언으로
축 \hat{\mathbf{n}}과 각도 \theta에서 단위 쿼터니언으로의 변환:
\mathbf{q} = \left(\cos\frac{\theta}{2}, \; \sin\frac{\theta}{2} \hat{\mathbf{n}}\right)
(w, x, y, z) 순서로:
w = \cos\frac{\theta}{2}, \quad x = n_x \sin\frac{\theta}{2}, \quad y = n_y \sin\frac{\theta}{2}, \quad z = n_z \sin\frac{\theta}{2}
tf2::Quaternion axis_angle_to_quaternion(
const tf2::Vector3& axis, double angle)
{
double half_angle = angle / 2.0;
double s = std::sin(half_angle);
return tf2::Quaternion(
axis.x() * s, axis.y() * s, axis.z() * s,
std::cos(half_angle));
}
5.2 쿼터니언에서 축-각으로
단위 쿼터니언 \mathbf{q} = (w, x, y, z)에서 축-각으로의 변환:
\theta = 2\arccos(|w|)
\hat{\mathbf{n}} = \frac{(x, y, z)}{\sqrt{x^2 + y^2 + z^2}} = \frac{(x, y, z)}{\sin(\theta/2)}
\theta \approx 0일 때 벡터부의 노름이 0에 근접하므로, 이 경우 축이 정의되지 않으며 항등 회전으로 처리해야 한다. 수치적으로 안정한 구현:
void quaternion_to_axis_angle(
const tf2::Quaternion& q,
tf2::Vector3& axis, double& angle)
{
double norm_v = std::sqrt(q.x()*q.x() + q.y()*q.y() + q.z()*q.z());
if (norm_v < 1e-10) {
// 항등 회전에 근접
axis = tf2::Vector3(1, 0, 0); // 임의의 축
angle = 0.0;
} else {
angle = 2.0 * std::atan2(norm_v, std::abs(q.w()));
axis = tf2::Vector3(q.x()/norm_v, q.y()/norm_v, q.z()/norm_v);
// w < 0이면 최단 경로 보장
if (q.w() < 0) {
axis = -axis;
angle = 2.0 * M_PI - angle;
}
}
}
5.3 회전 행렬에서 축-각으로
회전 행렬 R에서 회전 각도와 축을 추출하는 방법:
회전 각도:
\theta = \arccos\left(\frac{\text{tr}(R) - 1}{2}\right)
회전축 (\theta \neq 0, \pi인 경우):
\hat{\mathbf{n}} = \frac{1}{2\sin\theta} \begin{pmatrix} r_{32} - r_{23} \\ r_{13} - r_{31} \\ r_{21} - r_{12} \end{pmatrix}
특수 경우 (\theta = \pi):
\sin\theta = 0이므로 위 공식을 사용할 수 없다. 이 경우 R + I의 열벡터로부터 축을 추출한다:
\hat{\mathbf{n}} = \frac{1}{\sqrt{2(1 + r_{ii})}} \begin{pmatrix} 1 + r_{11} \\ r_{21} \\ r_{31} \end{pmatrix}
여기서 r_{ii}는 R의 대각 원소 중 가장 큰 것이다.
import numpy as np
def rotation_matrix_to_axis_angle(R):
theta = np.arccos(np.clip((np.trace(R) - 1) / 2, -1, 1))
if theta < 1e-10:
return np.array([1, 0, 0]), 0.0 # 항등 회전
if np.abs(theta - np.pi) < 1e-10:
# 180° 회전: R + I의 비영 열벡터 사용
RpI = R + np.eye(3)
col_norms = np.linalg.norm(RpI, axis=0)
best_col = np.argmax(col_norms)
n = RpI[:, best_col] / col_norms[best_col]
return n, theta
n = np.array([
R[2,1] - R[1,2],
R[0,2] - R[2,0],
R[1,0] - R[0,1]
]) / (2 * np.sin(theta))
return n, theta
5.4 회전 벡터에서 회전 행렬로의 변환
회전 벡터 \boldsymbol{\theta} = \theta\hat{\mathbf{n}}에서 회전 행렬로의 변환에는 로드리게스 공식이 사용된다. OpenCV에서는 cv::Rodrigues() 함수가 이 변환을 지원한다. Eigen에서는:
Eigen::Vector3d rotation_vector(0.1, 0.2, 0.3);
double angle = rotation_vector.norm();
Eigen::Vector3d axis = rotation_vector.normalized();
Eigen::AngleAxisd aa(angle, axis);
Eigen::Matrix3d R = aa.toRotationMatrix();
6. Eigen의 AngleAxis 클래스
Eigen 라이브러리는 축-각 표현을 Eigen::AngleAxis 템플릿 클래스로 지원한다:
#include <Eigen/Geometry>
// 축-각 생성
Eigen::AngleAxisd aa(M_PI / 4, Eigen::Vector3d::UnitZ()); // z축 45°
// 회전 행렬로 변환
Eigen::Matrix3d R = aa.toRotationMatrix();
// 쿼터니언으로 변환
Eigen::Quaterniond q(aa);
// 벡터 회전
Eigen::Vector3d v(1, 0, 0);
Eigen::Vector3d v_rotated = aa * v;
// 역회전
Eigen::AngleAxisd aa_inv = aa.inverse();
// 축과 각도 접근
double angle = aa.angle();
Eigen::Vector3d axis = aa.axis();
// 회전 합성 (쿼터니언 경유)
Eigen::AngleAxisd aa1(M_PI/6, Eigen::Vector3d::UnitX());
Eigen::AngleAxisd aa2(M_PI/4, Eigen::Vector3d::UnitZ());
Eigen::AngleAxisd aa_combined(Eigen::Quaterniond(aa2) * Eigen::Quaterniond(aa1));
7. 축-각 표현의 장단점
7.1 장점
- 물리적 직관성: 회전축과 회전 각도라는 물리적으로 명확한 양으로 회전을 기술하므로, 회전의 기하학적 의미를 직관적으로 파악할 수 있다.
- 최소 파라미터: 회전 벡터 형식에서 3개의 파라미터만으로 회전을 표현하며, 추가 구속 조건이 없다.
- 소각도 근사의 용이성: \theta \approx 0일 때 회전 벡터는 각속도 벡터에 근사적으로 비례하므로, 미소 회전의 표현에 적합하다.
- 로드리게스 공식의 직접 적용: 축-각에서 회전 행렬로의 변환이 명시적 공식으로 제공된다.
7.2 단점
- \theta = 0 특이성: 항등 회전에서 축이 정의되지 않으므로, 미분이나 보간에서 불연속이 발생할 수 있다.
- \theta = \pi 모호성: (\hat{\mathbf{n}}, \pi)와 (-\hat{\mathbf{n}}, \pi)가 동일한 회전을 나타내어, 부호 모호성이 존재한다.
- 비효율적 합성: 두 축-각 표현의 회전을 직접 합성하는 간단한 공식이 없다. 쿼터니언이나 회전 행렬로 변환 후 합성해야 한다.
- 비균일 보간: 축-각 공간에서의 선형 보간은 일반적으로 균일 회전 보간을 보장하지 않는다.
7.3 다른 표현과의 비교
| 특성 | 축-각 | 쿼터니언 | 회전 행렬 | 오일러 각 |
|---|---|---|---|---|
| 파라미터 수 | 3 (또는 4) | 4 | 9 | 3 |
| 구속 조건 | 0 (회전 벡터) | 1 | 6 | 0 |
| 짐벌 락 | 없음 | 없음 | 없음 | 있음 |
| 특이점 | \theta = 0, \pi | 없음 | 없음 | \theta_2 = \pm\pi/2 |
| 합성 | 비직접적 | 곱셈 | 곱셈 | 비직접적 |
| 직관성 | 높음 | 낮음 | 중간 | 높음 |
8. 로봇공학에서의 활용
8.1 관절 회전 표현
회전 관절(revolute joint)의 운동은 축-각 표현에 자연스럽게 대응한다. 관절의 회전축이 고정되어 있고 관절 각도가 변하는 구조이므로, 축-각 표현은 관절 운동학의 기본 표현이 된다.
// 관절 회전 표현
Eigen::Vector3d joint_axis(0, 0, 1); // z축 회전 관절
double joint_angle = M_PI / 3; // 60° 회전
Eigen::AngleAxisd joint_rotation(joint_angle, joint_axis);
Eigen::Matrix3d R_joint = joint_rotation.toRotationMatrix();
8.2 각속도와의 관계
미소 시간 \Delta t 동안의 미소 회전은 각속도 벡터 \boldsymbol{\omega}와 다음의 관계를 가진다:
\boldsymbol{\theta}_{\Delta} \approx \boldsymbol{\omega} \Delta t
이 근사는 \|\boldsymbol{\omega}\| \Delta t \ll 1일 때 유효하며, 관성 항법이나 자세 적분에서 널리 사용된다.
8.3 오차 표현
두 회전 사이의 오차를 표현할 때 축-각 또는 회전 벡터가 자주 사용된다. 기준 회전 R_d와 실제 회전 R 사이의 오차는:
R_e = R_d^T R
이 오차 회전의 회전 벡터 \boldsymbol{\theta}_e가 자세 오차를 나타내며, 제어기의 피드백 신호로 사용된다.
9. 요약
축-각 표현은 오일러 회전 정리에 기반하여 3D 회전을 단위 벡터(회전축)와 스칼라 각도의 쌍으로 기술하는 방법이다. 회전 벡터 형식으로 통합하면 3개의 파라미터만으로 구속 조건 없이 회전을 표현할 수 있다. 로드리게스 공식을 통해 회전 행렬과 직접적으로 연결되며, 쿼터니언과의 변환도 명시적이다. \theta = 0과 \theta = \pi에서의 특이성이 존재하지만, 관절 회전, 각속도, 회전 오차 등 물리적으로 직관적인 표현이 필요한 경우에 효과적으로 활용된다.
10. 참고 문헌
- 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.
- Murray, R. M., Li, Z., & Sastry, S. S. (1994). A Mathematical Introduction to Robotic Manipulation. CRC Press.
- 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.
- Sola, J. (2017). “Quaternion kinematics for the error-state Kalman filter.” arXiv:1711.02508.