659.50 3D 회전 표현: 오일러 각 (Euler Angles) 기초

1. 개요

오일러 각(Euler angles)은 3차원 공간에서의 강체 회전을 세 개의 연속적인 기본 회전(elementary rotation)의 합성으로 표현하는 방법이다. 1775년 레온하르트 오일러(Leonhard Euler)에 의해 제안된 이 표현 방식은, 세 개의 스칼라 각도만으로 회전을 기술하므로 인간의 직관에 부합하며, 이로 인해 로봇공학, 항공우주 공학, 컴퓨터 그래픽스 등 다양한 공학 분야에서 사용자 인터페이스와 설정 파라미터에 널리 활용된다. 그러나 짐벌 락(gimbal lock) 현상과 보간의 비균일성이라는 고유한 한계를 가지므로, 내부 연산에서는 쿼터니언이나 회전 행렬이 선호된다. 본 절에서는 오일러 각의 기본 개념, 회전 순서 규약, 수학적 정의, 그리고 로봇공학에서의 활용과 한계를 체계적으로 다룬다.

2. 기본 회전 (Elementary Rotation)

2.1 좌표축 기준 회전

3차원 공간에서 좌표축 중 하나를 중심으로 수행하는 회전을 기본 회전이라 한다. 오른손 좌표계에서 각 축 기준의 기본 회전 행렬은 다음과 같다.

x축 기준 회전 (Roll, \phi):

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

y축 기준 회전 (Pitch, \theta):

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

z축 기준 회전 (Yaw, \psi):

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

각 기본 회전 행렬은 직교 행렬(orthogonal matrix)이며, 행렬식이 +1인 특수 직교 행렬(SO(3)의 원소)이다.

2.2 기본 회전의 양의 방향

오른손 좌표계에서 양의 회전 방향은 **오른손 법칙(right-hand rule)**에 의해 정의된다. 회전축의 양의 방향을 오른손 엄지손가락으로 가리킬 때, 나머지 손가락이 감기는 방향이 양의 회전 방향이다. 이는 좌표축의 양의 끝에서 원점을 바라볼 때 반시계 방향(counter-clockwise)에 해당한다.

3. 오일러 각의 정의

3.1 오일러 정리

오일러 회전 정리(Euler’s rotation theorem)에 의하면, 3차원 공간에서 고정점을 가지는 임의의 강체 운동은 해당 고정점을 지나는 하나의 축에 대한 단일 회전으로 나타낼 수 있다. 이를 확장하면, 임의의 3D 회전은 세 개의 좌표축 기준 기본 회전의 합성으로도 표현할 수 있다.

3.2 오일러 각의 구성

오일러 각은 세 개의 각도 (\alpha, \beta, \gamma)로 구성되며, 이 세 각도는 각각 특정 좌표축에 대한 기본 회전에 대응한다. 최종 회전 행렬은 세 기본 회전 행렬의 곱으로 표현된다:

R = R_{\text{axis}_3}(\gamma) R_{\text{axis}_2}(\beta) R_{\text{axis}_1}(\alpha)

여기서 \text{axis}_1, \text{axis}_2, \text{axis}_3\{x, y, z\} 중에서 선택되며, 이 축의 선택과 순서가 **회전 순서 규약(rotation sequence convention)**을 결정한다.

3.3 고유 오일러 각과 타이트-브라이언 각

회전 순서 규약은 크게 두 부류로 분류된다:

고유 오일러 각 (Proper Euler Angles):

첫 번째와 세 번째 축이 동일한 경우이다. 6가지 경우가 존재한다:

XYX, \quad XZX, \quad YXY, \quad YZY, \quad ZXZ, \quad ZYZ

고유 오일러 각은 천체역학, 결정학 등에서 전통적으로 사용되어 왔다. ZYZ 순서는 양자역학과 핵물리학에서, ZXZ 순서는 고전역학에서 널리 사용된다.

타이트-브라이언 각 (Tait-Bryan Angles):

세 축이 모두 다른 경우이다. 6가지 경우가 존재한다:

XYZ, \quad XZY, \quad YXZ, \quad YZX, \quad ZXY, \quad ZYX

타이트-브라이언 각은 항공우주 공학과 로봇공학에서 주로 사용되며, Roll-Pitch-Yaw (RPY) 표현이 이에 해당한다. 총 12가지 회전 순서 규약 중, 로봇공학에서 가장 빈번하게 사용되는 것은 ZYX 순서(Yaw-Pitch-Roll 또는 3-2-1 순서)와 XYZ 순서이다.

4. 내재적 회전과 외재적 회전

4.1 외재적 회전 (Extrinsic Rotation)

외재적 회전은 고정된 전역 좌표계의 축을 기준으로 순차적 회전을 수행하는 방식이다. 각 회전은 전역 좌표축에 대해 이루어지며, 이전 회전의 영향을 받지 않는다.

외재적 XYZ 회전의 합성 행렬은:

R_{\text{extrinsic}}^{XYZ} = R_z(\gamma) R_y(\beta) R_x(\alpha)

마지막에 적용되는 회전이 행렬 곱에서 가장 왼쪽에 위치한다.

4.2 내재적 회전 (Intrinsic Rotation)

내재적 회전은 회전하는 물체에 부착된 좌표계의 축을 기준으로 순차적 회전을 수행하는 방식이다. 각 회전이 수행된 후 물체의 좌표축이 함께 회전하므로, 다음 회전의 기준축이 이전 회전에 의해 변경된 축이 된다.

내재적 ZYX 회전(Yaw → Pitch → Roll)의 합성 행렬은:

R_{\text{intrinsic}}^{ZYX} = R_z(\psi) R_y(\theta) R_x(\phi)

4.3 외재적-내재적 동치 관계

중요한 수학적 사실로, 외재적 XYZ 회전과 내재적 ZYX 회전은 동일한 결과를 산출한다:

R_{\text{extrinsic}}^{XYZ}(\alpha, \beta, \gamma) = R_{\text{intrinsic}}^{ZYX}(\gamma, \beta, \alpha)

더 일반적으로, 임의의 회전 순서에 대해 축 순서를 뒤집고 각도 순서를 뒤집으면 외재적 회전과 내재적 회전이 동치가 된다. 이 동치 관계는 회전 순서 규약 간의 변환에서 혼동을 방지하기 위해 반드시 이해해야 한다.

5. Roll-Pitch-Yaw (RPY) 표현

5.1 정의

로봇공학에서 가장 널리 사용되는 오일러 각 표현은 Roll-Pitch-Yaw (RPY) 규약이다. 이 규약에서 세 각도의 의미는:

  • Roll (\phi, 롤): x축을 중심으로 한 회전. 로봇의 좌우 기울임에 해당한다.
  • Pitch (\theta, 피치): y축을 중심으로 한 회전. 로봇의 앞뒤 기울임(고개 숙임/젖힘)에 해당한다.
  • Yaw (\psi, 요): z축을 중심으로 한 회전. 로봇의 수평면 내 방향 전환에 해당한다.

RPY 규약은 외재적 XYZ 순서 또는 동등하게 내재적 ZYX 순서를 사용한다. 합성 회전 행렬은:

R_{RPY} = R_z(\psi) R_y(\theta) R_x(\phi)

이를 전개하면:

R_{RPY} = \begin{pmatrix} \cos\psi\cos\theta & \cos\psi\sin\theta\sin\phi - \sin\psi\cos\phi & \cos\psi\sin\theta\cos\phi + \sin\psi\sin\phi \\ \sin\psi\cos\theta & \sin\psi\sin\theta\sin\phi + \cos\psi\cos\phi & \sin\psi\sin\theta\cos\phi - \cos\psi\sin\phi \\ -\sin\theta & \cos\theta\sin\phi & \cos\theta\cos\phi \end{pmatrix}

5.2 각도 범위

RPY 각도의 관례적 범위는:

각도범위비고
Roll (\phi)[-\pi, \pi] 또는 (-\pi, \pi]전 범위
Pitch (\theta)[-\pi/2, \pi/2]제한 범위 (짐벌 락 회피)
Yaw (\psi)[-\pi, \pi] 또는 [0, 2\pi)전 범위

Pitch의 범위가 [-\pi/2, \pi/2]로 제한되는 이유는, \theta = \pm\pi/2에서 짐벌 락이 발생하기 때문이다. 이 제한을 두면 회전 행렬에서 RPY 각도를 유일하게 추출할 수 있다.

5.3 ROS2에서의 RPY 사용

ROS2와 TF2에서는 RPY 규약을 표준으로 사용한다. tf2::Quaternion 클래스의 setRPY() 메서드와 tf2::Matrix3x3getRPY() 메서드가 이 규약을 따른다:

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

// RPY에서 쿼터니언으로 변환
tf2::Quaternion q;
q.setRPY(roll, pitch, yaw);  // 외재적 XYZ = 내재적 ZYX

// 쿼터니언에서 RPY로 변환
tf2::Matrix3x3 m(q);
double roll, pitch, yaw;
m.getRPY(roll, pitch, yaw);
# Python (tf_transformations)
from tf_transformations import quaternion_from_euler, euler_from_quaternion

# RPY에서 쿼터니언으로
q = quaternion_from_euler(roll, pitch, yaw)  # 기본: 'sxyz' (외재적 XYZ)

# 쿼터니언에서 RPY로
(roll, pitch, yaw) = euler_from_quaternion(q)

6. 오일러 각에서 회전 행렬로의 변환

6.1 일반적 변환 절차

주어진 회전 순서에 대해, 세 기본 회전 행렬을 순서대로 곱하여 합성 회전 행렬을 생성한다. RPY(외재적 XYZ) 순서의 경우:

R = R_z(\psi) R_y(\theta) R_x(\phi)

전개된 행렬의 각 원소는 삼각함수의 곱과 합으로 표현되며, 총 9개의 원소가 3개의 각도에 대한 함수로 결정된다. 9개의 원소 중 독립적인 것은 3개(3자유도)이며, 나머지 6개는 직교성 구속 조건에 의해 결정된다.

6.2 계산 예시

x축 기준 30°, y축 기준 45°, z축 기준 60° 회전(RPY 순서)의 합성 행렬을 계산하면:

\phi = 30° = \frac{\pi}{6}, \quad \theta = 45° = \frac{\pi}{4}, \quad \psi = 60° = \frac{\pi}{3}

각 기본 회전 행렬을 계산하고 곱하면 합성 회전 행렬을 얻는다.

import numpy as np

phi = np.radians(30)    # roll
theta = np.radians(45)  # pitch
psi = np.radians(60)    # yaw

Rx = np.array([[1, 0, 0],
               [0, np.cos(phi), -np.sin(phi)],
               [0, np.sin(phi), np.cos(phi)]])

Ry = np.array([[np.cos(theta), 0, np.sin(theta)],
               [0, 1, 0],
               [-np.sin(theta), 0, np.cos(theta)]])

Rz = np.array([[np.cos(psi), -np.sin(psi), 0],
               [np.sin(psi), np.cos(psi), 0],
               [0, 0, 1]])

R = Rz @ Ry @ Rx  # RPY 순서: Rz * Ry * Rx

7. 회전 행렬에서 오일러 각 추출

7.1 RPY 각도 추출

합성 회전 행렬 R이 주어졌을 때, RPY 각도를 추출하는 역과정은 다음과 같다. R의 원소를 r_{ij}로 표기하면:

\theta = -\arcsin(r_{31})

\phi = \text{atan2}(r_{32}, r_{33})

\psi = \text{atan2}(r_{21}, r_{11})

여기서 \text{atan2}는 사분면을 구분하는 역탄젠트 함수이다. 이 공식은 \cos\theta \neq 0, 즉 \theta \neq \pm\pi/2인 경우에 유효하다.

7.2 짐벌 락 근방에서의 처리

\theta = \pm\pi/2일 때 \cos\theta = 0이 되어 \phi\psi를 개별적으로 결정할 수 없다. 이 경우 \phi\psi의 합 또는 차만 결정 가능하며, 하나의 각도를 임의로 고정(일반적으로 0으로 설정)하여 나머지를 계산한다:

void rotationMatrixToRPY(const double R[3][3], 
                         double& roll, double& pitch, double& yaw) {
    double sin_pitch = -R[2][0];
    
    if (std::abs(sin_pitch) >= 1.0 - 1e-6) {
        // 짐벌 락 근방
        pitch = std::copysign(M_PI / 2.0, sin_pitch);
        roll = 0.0;  // 관례적으로 0으로 설정
        yaw = std::atan2(-R[0][1], R[1][1]);
    } else {
        pitch = std::asin(sin_pitch);
        roll = std::atan2(R[2][1], R[2][2]);
        yaw = std::atan2(R[1][0], R[0][0]);
    }
}

8. 오일러 각의 장점과 한계

8.1 장점

  1. 직관성: 세 개의 각도가 각각 독립적인 물리적 의미(롤, 피치, 요)를 가지므로, 인간이 회전 상태를 직관적으로 이해할 수 있다.
  2. 최소 파라미터: 3자유도 회전을 정확히 3개의 파라미터로 표현하므로, 파라미터 효율성이 최대이다.
  3. 사용자 인터페이스 적합성: 조종기 입력, 설정 파라미터, 로그 출력 등에서 사람이 직접 읽고 설정하기 용이하다.
  4. 미분 가능성: 특이점을 제외한 영역에서 각속도와의 관계가 명시적으로 정의된다.

8.2 한계

  1. 짐벌 락: 특정 자세에서 하나의 자유도를 상실하여 회전 표현의 특이점이 발생한다.
  2. 비균일 보간: 오일러 각의 선형 보간은 균일한 회전 보간을 보장하지 않으며, 경로가 왜곡될 수 있다.
  3. 규약 혼동: 12가지 회전 순서와 내재적/외재적 구분에 의해 24가지 규약이 존재하므로, 시스템 간 데이터 교환 시 규약 불일치가 빈번하다.
  4. 회전 합성의 비효율성: 오일러 각에서 직접 회전 합성을 수행하려면 삼각함수 연산이 필요하며, 쿼터니언이나 회전 행렬에 비해 비효율적이다.
  5. 비가환성의 비직관적 표현: 오일러 각 자체에서는 회전의 비가환성이 드러나지 않아, 순서가 바뀌면 결과가 달라진다는 사실을 간과하기 쉽다.

9. 로봇공학에서의 활용 지침

9.1 오일러 각 사용이 적합한 경우

  • 사용자 인터페이스: 조이스틱 입력, 웹 UI의 자세 설정 슬라이더, 디버깅 로그 출력
  • 설정 파라미터: URDF/Xacro의 rpy 속성, 런치 파일의 자세 초기값
  • 2D 내비게이션: 평면 이동 로봇의 헤딩(heading) 각도 표현 (yaw만 사용)
  • 소규모 각도 변화: 짐벌 락으로부터 충분히 떨어진 자세 범위 내에서의 작은 회전

9.2 오일러 각 사용을 피해야 하는 경우

  • 임의의 3D 회전 합성: 내부 연산에서는 쿼터니언 또는 회전 행렬을 사용
  • 보간이 필요한 경로 생성: SLERP이나 기타 구면 보간 방법을 사용
  • 항공기/드론의 급격한 기동: 피치각이 \pm 90°에 근접하는 경우
  • 칼만 필터 상태 벡터: 쿼터니언이나 회전 벡터 사용이 권장

9.3 ROS2 생태계에서의 표준

ROS2에서 오일러 각은 주로 입출력과 사용자 상호작용에 사용되며, 내부 데이터 표현은 항상 쿼터니언으로 이루어진다:

# URDF에서의 RPY 사용 예 (설정 파라미터로서의 오일러 각)
# <origin xyz="0 0 0" rpy="0 0 1.5708"/>  <!-- yaw = 90° -->

# 내부 처리는 쿼터니언으로 수행
from tf_transformations import quaternion_from_euler
q = quaternion_from_euler(0, 0, 1.5708)  # 내부적으로 쿼터니언으로 변환

이 패턴은 오일러 각의 직관성과 쿼터니언의 수학적 견고성을 동시에 활용하는 모범적인 설계 방침이다.

10. 요약

오일러 각은 3차원 회전을 세 개의 축 기준 기본 회전의 합성으로 표현하는 직관적인 방법이다. Roll-Pitch-Yaw(RPY) 규약은 로봇공학에서 가장 널리 채택된 오일러 각 표현으로, 외재적 XYZ(내재적 ZYX) 순서를 사용한다. 오일러 각은 사용자 인터페이스와 설정 파라미터에 적합하나, 짐벌 락, 비균일 보간, 규약 혼동 등의 한계로 인해 내부 연산에서는 쿼터니언이 선호된다. ROS2에서는 입출력에 오일러 각을, 내부 표현에 쿼터니언을 사용하는 이분 전략이 표준으로 확립되어 있다.

11. 참고 문헌

  • Euler, L. (1776). “Nova methodus motum corporum rigidorum determinandi.” Novi Commentarii Academiae Scientiarum Petropolitanae, 20, 208-238.
  • Diebel, J. (2006). “Representing Attitude: Euler Angles, Unit Quaternions, and Rotation Vectors.” Stanford University Technical Report.
  • Slabaugh, G. G. (1999). “Computing Euler Angles from a Rotation Matrix.” City University London.
  • 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.
  • REP 103 — Standard Units of Measure and Coordinate Conventions. https://www.ros.org/reps/rep-0103.html