659.51 오일러 각의 회전 순서 규약 (RPY, YPR)

1. 개요

오일러 각을 사용하여 3차원 회전을 표현할 때, 세 개의 기본 회전이 어떤 축 순서로 적용되는지에 따라 동일한 각도 값이 전혀 다른 회전을 나타낸다. 이 축의 적용 순서를 **회전 순서 규약(rotation sequence convention)**이라 하며, 수학적으로 12가지 고유한 규약이 존재한다. 로봇공학에서는 이 중 Roll-Pitch-Yaw(RPY)와 Yaw-Pitch-Roll(YPR) 규약이 가장 빈번하게 사용되며, 두 규약의 관계와 차이를 정확히 이해하는 것은 시스템 간 데이터 교환과 좌표 변환의 정확성을 보장하기 위해 필수적이다. 본 절에서는 다양한 회전 순서 규약의 정의, 분류 체계, 주요 규약의 수학적 관계, 그리고 ROS2 생태계에서의 표준 규약을 체계적으로 기술한다.

2. 회전 순서 규약의 분류

2.1 가지 회전 순서

3차원 회전을 세 개의 축 기준 기본 회전으로 분해할 때, 연속하는 두 회전의 축이 동일하지 않아야 한다는 제약 하에 12가지 고유한 순서가 가능하다. 이를 두 부류로 분류한다:

고유 오일러 각 (Proper Euler Angles) — 6가지:

첫 번째와 세 번째 축이 동일한 경우이다:

순서표기주요 사용 분야
x \to y \to xXYX일부 결정학
x \to z \to xXZX일부 결정학
y \to x \to yYXY특수 응용
y \to z \to yYZY특수 응용
z \to x \to zZXZ고전역학, 천체역학
z \to y \to zZYZ양자역학, 핵물리학

타이트-브라이언 각 (Tait-Bryan Angles) — 6가지:

세 축이 모두 다른 경우이다:

순서표기주요 사용 분야
x \to y \to zXYZ로봇공학 (RPY), 기계공학
x \to z \to yXZY특수 응용
y \to x \to zYXZ게임 엔진, 컴퓨터 그래픽스
y \to z \to xYZX특수 응용
z \to x \to yZXY일부 로봇 프레임워크
z \to y \to xZYX항공우주 (YPR), 내비게이션

2.2 내재적/외재적에 따른 규약 확장

각 12가지 축 순서에 대해 내재적(intrinsic) 또는 외재적(extrinsic) 해석이 적용되므로, 이론적으로 24가지 규약이 존재한다. 그러나 외재적 XYZ와 내재적 ZYX가 동일한 결과를 산출하는 동치 관계가 있으므로, 수학적으로 독립적인 규약은 12가지이다.

R_{\text{extrinsic}}^{A_1 A_2 A_3}(\alpha, \beta, \gamma) = R_{\text{intrinsic}}^{A_3 A_2 A_1}(\gamma, \beta, \alpha)

여기서 A_1, A_2, A_3는 축 이름이다.

3. Roll-Pitch-Yaw (RPY) 규약

3.1 정의와 축 대응

RPY 규약은 타이트-브라이언 각의 한 형태로, 세 각도를 다음과 같이 정의한다:

이름기호회전축물리적 의미
Roll (롤)\phix축세로축 기준 기울임 (좌우 경사)
Pitch (피치)\thetay축가로축 기준 기울임 (앞뒤 고개)
Yaw (요)\psiz축수직축 기준 회전 (방향 전환)

3.2 수학적 표현

RPY 규약은 외재적 XYZ 순서(또는 동등하게 내재적 ZYX 순서)로 정의된다. 합성 회전 행렬은:

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

행렬의 적용 순서를 명확히 하면, 벡터 \mathbf{v}에 대한 변환은:

\mathbf{v}' = R_z(\psi) R_y(\theta) R_x(\phi) \mathbf{v}

즉, 먼저 Roll(x축 회전)이 적용되고, 그 다음 Pitch(y축 회전), 마지막으로 Yaw(z축 회전)가 적용된다. 행렬 곱에서 가장 오른쪽의 행렬이 먼저 적용된다는 점에 주의해야 한다.

3.3 전개된 합성 회전 행렬

R_{RPY} = \begin{pmatrix} c_\psi c_\theta & c_\psi s_\theta s_\phi - s_\psi c_\phi & c_\psi s_\theta c_\phi + s_\psi s_\phi \\ s_\psi c_\theta & s_\psi s_\theta s_\phi + c_\psi c_\phi & s_\psi s_\theta c_\phi - c_\psi s_\phi \\ -s_\theta & c_\theta s_\phi & c_\theta c_\phi \end{pmatrix}

여기서 c_\alpha = \cos\alpha, s_\alpha = \sin\alpha의 약기법을 사용하였다.

3.4 ROS2에서의 RPY 표준

ROS2와 TF2에서는 RPY 규약을 표준으로 채택하고 있다. 다음의 API가 RPY 규약을 따른다:

// tf2::Quaternion의 setRPY 메서드
tf2::Quaternion q;
q.setRPY(roll, pitch, yaw);  // 외재적 XYZ 순서

// tf2::Matrix3x3의 getRPY 메서드
tf2::Matrix3x3 m(q);
double roll, pitch, yaw;
m.getRPY(roll, pitch, yaw);

// tf2::Matrix3x3의 setRPY 메서드
tf2::Matrix3x3 m2;
m2.setRPY(roll, pitch, yaw);
# tf_transformations의 기본 순서 규약
from tf_transformations import quaternion_from_euler, euler_from_quaternion

# 기본: 'sxyz' (static/extrinsic XYZ = RPY)
q = quaternion_from_euler(roll, pitch, yaw)
(roll, pitch, yaw) = euler_from_quaternion(q)

URDF(Unified Robot Description Format)에서도 RPY 규약을 사용한다:

<!-- URDF에서의 RPY 사용 -->
<origin xyz="0 0 0.5" rpy="0 0 1.5708"/>
<!-- rpy="roll pitch yaw" 순서, 라디안 단위 -->

4. Yaw-Pitch-Roll (YPR) 규약

4.1 정의와 축 대응

YPR 규약은 항공우주 공학에서 주로 사용되는 규약으로, 내재적 ZYX 순서를 기준으로 한다:

적용 순서이름기호회전축 (물체 기준)
1번째Yaw (요)\psiz축 (초기 수직축)
2번째Pitch (피치)\thetay’축 (yaw 후 갱신된 가로축)
3번째Roll (롤)\phix’’축 (pitch 후 갱신된 세로축)

4.2 수학적 표현

YPR 규약의 합성 회전 행렬은 내재적 ZYX 순서를 따르므로:

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

이 행렬은 RPY 규약의 R_{RPY}(\phi, \theta, \psi)수학적으로 동일한 최종 행렬을 생성한다. 두 규약의 차이는 각도가 적용되는 해석적 순서명명법에 있으며, 최종 수학적 결과는 같다.

4.3 RPY와 YPR의 관계

RPY와 YPR은 동일한 회전을 서로 다른 관점에서 기술한다:

항목RPYYPR
회전 기준고정 좌표계 (외재적)물체 좌표계 (내재적)
축 순서외재적 X → Y → Z내재적 Z → Y → X
각도 입력 순서(\phi, \theta, \psi) = (roll, pitch, yaw)(\psi, \theta, \phi) = (yaw, pitch, roll)
합성 행렬R_z(\psi)R_y(\theta)R_x(\phi)R_z(\psi)R_y(\theta)R_x(\phi)
동일한 최종 행렬

핵심 차이점은 각도의 나열 순서이다. RPY에서는 (\text{roll}, \text{pitch}, \text{yaw}) 순서로 각도를 나열하지만, YPR에서는 (\text{yaw}, \text{pitch}, \text{roll}) 순서로 나열한다. 동일한 회전을 표현하는 동일한 행렬을 생성하되, 입력 인자의 순서가 다르다.

5. 항공우주 규약과 로봇공학 규약의 차이

5.1 좌표계 차이

항공우주 공학과 로봇공학에서 사용하는 좌표계 규약이 근본적으로 다르며, 이 차이가 오일러 각의 해석에도 영향을 미친다:

항목로봇공학 (ROS2/REP 103)항공우주 (NED)
전방 (Forward)x축 양의 방향x축 양의 방향 (North)
좌측 (Left)y축 양의 방향
상방 (Up)z축 양의 방향
우측 (Right)y축 양의 방향 (East)
하방 (Down)z축 양의 방향 (Down)
좌표계 종류ENU (East-North-Up)NED (North-East-Down)
Yaw 양의 방향반시계 (위에서 볼 때)시계 (위에서 볼 때)

이 좌표계 차이로 인해, 동일한 물리적 자세에 대해 RPY 값이 달라진다. 두 시스템 간 데이터를 변환할 때는 좌표계 변환을 반드시 적용해야 한다:

\text{roll}_{NED} = \text{roll}_{ENU}

\text{pitch}_{NED} = -\text{pitch}_{ENU}

\text{yaw}_{NED} = \frac{\pi}{2} - \text{yaw}_{ENU}

5.2 변환 예시

// ENU (ROS2) → NED (항공우주) 변환
void enu_to_ned_rpy(double roll_enu, double pitch_enu, double yaw_enu,
                     double& roll_ned, double& pitch_ned, double& yaw_ned) {
    roll_ned = roll_enu;
    pitch_ned = -pitch_enu;
    yaw_ned = M_PI / 2.0 - yaw_enu;
    
    // yaw_ned를 [-π, π] 범위로 정규화
    while (yaw_ned > M_PI) yaw_ned -= 2.0 * M_PI;
    while (yaw_ned <= -M_PI) yaw_ned += 2.0 * M_PI;
}

6. 다양한 분야별 회전 순서 규약

6.1 분야별 주요 규약 요약

분야규약축 순서해석비고
ROS2 / TF2RPY외재적 XYZ고정 좌표계setRPY(), URDF rpy
항공우주 (AIAA)YPR (3-2-1)내재적 ZYX물체 좌표계NED 좌표계
항공우주 (ECEF)YPR내재적 ZYX물체 좌표계지구 고정계
고전역학ZXZ내재적 ZXZ물체 좌표계Goldstein 교재
양자역학ZYZ내재적 ZYZ물체 좌표계Wigner 관례
Unity 엔진YXZ내재적 YXZ물체 좌표계왼손 좌표계
Unreal 엔진ZYX내재적 ZYX물체 좌표계왼손 좌표계
MATLAB RoboticsZYX외재적 XYZ고정 좌표계eul2rotm
SciPy사용자 지정선택 가능선택 가능Rotation.from_euler('xyz', ...)

6.2 SciPy에서의 규약 지정

Python의 SciPy 라이브러리에서는 회전 순서를 문자열로 명시적으로 지정할 수 있어, 규약 혼동의 위험이 줄어든다:

from scipy.spatial.transform import Rotation

# 외재적(고정 좌표계) 규약: 소문자 사용
r_extrinsic_xyz = Rotation.from_euler('xyz', [roll, pitch, yaw])  # RPY
r_extrinsic_zyx = Rotation.from_euler('zyx', [yaw, pitch, roll])

# 내재적(물체 좌표계) 규약: 대문자 사용
r_intrinsic_ZYX = Rotation.from_euler('ZYX', [yaw, pitch, roll])  # YPR (내재적)
r_intrinsic_XYZ = Rotation.from_euler('XYZ', [roll, pitch, yaw])

# 외재적 'xyz'와 내재적 'ZYX'는 동일한 결과
# (단, 각도 순서가 역순)
r1 = Rotation.from_euler('xyz', [roll, pitch, yaw])
r2 = Rotation.from_euler('ZYX', [yaw, pitch, roll])
# r1과 r2는 동일한 회전

6.3 tf_transformations에서의 규약 지정

tf_transformations 라이브러리에서도 다양한 규약을 지원한다:

from tf_transformations import euler_from_quaternion, quaternion_from_euler

# 규약 문자열: 's' 또는 'r' + 축 순서
# 's' = static (외재적), 'r' = rotating (내재적)

# RPY (외재적 XYZ) — ROS2 기본
q = quaternion_from_euler(roll, pitch, yaw, axes='sxyz')

# YPR (내재적 ZYX)
q = quaternion_from_euler(yaw, pitch, roll, axes='rzyx')

# ZXZ (고전역학)
q = quaternion_from_euler(alpha, beta, gamma, axes='rzxz')

7. 규약 혼동의 위험과 방지 대책

7.1 규약 혼동에 의한 오류 사례

오일러 각 규약의 혼동은 로봇 시스템에서 심각한 오류를 초래할 수 있다. 대표적인 위험 상황은:

  1. ROS2 노드와 외부 IMU 간의 규약 불일치: IMU 제조사가 NED(YPR) 규약을 사용하고 ROS2 노드가 ENU(RPY) 규약을 사용하는 경우, 변환 없이 데이터를 사용하면 자세 추정이 왜곡된다.

  2. 게임 엔진과 로봇 시뮬레이터 간의 차이: Unity(왼손 좌표계, YXZ 순서)에서 생성된 자세 데이터를 Gazebo(오른손 좌표계, RPY 순서)에서 사용할 때 좌표계 변환이 필요하다.

  3. 라이브러리 간 인자 순서 차이: setRPY(roll, pitch, yaw) 형태의 API와 setEulerYPR(yaw, pitch, roll) 형태의 API를 혼용할 때, 인자 순서를 잘못 맞추는 오류가 발생한다.

7.2 방지 대책

  1. 프로젝트 내 단일 규약 확립: 프로젝트 문서에 사용하는 오일러 각 규약을 명시적으로 기록한다.

  2. 변수명에 규약 포함: 변수명에 규약 정보를 포함하여 혼동을 방지한다:

// 명확한 변수명 사용
double roll_enu, pitch_enu, yaw_enu;   // ENU 좌표계의 RPY
double roll_ned, pitch_ned, yaw_ned;   // NED 좌표계의 YPR
  1. 내부 표현을 쿼터니언으로 통일: 오일러 각은 입출력 인터페이스에서만 사용하고, 내부 데이터 전달은 항상 쿼터니언으로 수행한다.

  2. 변환 함수의 단위 테스트: 오일러 각 ↔ 쿼터니언 변환 함수에 대해 알려진 회전(예: 90° 단축 회전)의 변환 결과를 검증하는 단위 테스트를 작성한다:

import numpy as np
from tf_transformations import quaternion_from_euler

def test_rpy_convention():
    """z축 90° 회전의 RPY → 쿼터니언 변환 검증"""
    q = quaternion_from_euler(0, 0, np.pi/2)  # roll=0, pitch=0, yaw=90°
    # 기대값: [x, y, z, w] = [0, 0, sin(45°), cos(45°)]
    expected = np.array([0.0, 0.0, np.sin(np.pi/4), np.cos(np.pi/4)])
    np.testing.assert_allclose(q, expected, atol=1e-10)

8. 짐벌 락과 각도 범위

8.1 짐벌 락 발생 조건

각 회전 순서 규약에 따라 짐벌 락이 발생하는 각도가 다르다:

규약짐벌 락 조건잠기는 각도
타이트-브라이언 (RPY, YPR 등)두 번째 각도 = \pm\pi/2\theta = \pm 90°
고유 오일러 (ZXZ, ZYZ 등)두 번째 각도 = 0 또는 \pi\beta = 0° 또는 180°

타이트-브라이언 각에서는 피치가 \pm 90°일 때, 고유 오일러 각에서는 두 번째 각도(nutation angle)가 또는 180°일 때 짐벌 락이 발생한다.

8.2 규약별 표준 각도 범위

규약첫 번째 각도두 번째 각도세 번째 각도
RPY (타이트-브라이안)[-\pi, \pi][-\pi/2, \pi/2][-\pi, \pi]
ZXZ (고유 오일러)[-\pi, \pi][0, \pi][-\pi, \pi]
ZYZ (고유 오일러)[-\pi, \pi][0, \pi][-\pi, \pi]

9. 요약

오일러 각의 회전 순서 규약은 세 기본 회전의 축 순서와 내재적/외재적 해석 방식에 의해 결정되며, 이론적으로 12가지(해석 방식 포함 24가지, 동치 관계 고려 시 12가지) 고유 규약이 존재한다. 로봇공학(ROS2)에서는 외재적 XYZ 순서의 RPY 규약을 표준으로 사용하고, 항공우주 공학에서는 내재적 ZYX의 YPR 규약을 사용한다. 두 규약은 각도 나열 순서만 다를 뿐 동일한 합성 행렬을 산출한다. 규약 혼동은 심각한 시스템 오류를 초래하므로, 프로젝트 내 단일 규약 확립, 명시적 변수명 사용, 내부 표현의 쿼터니언 통일 등의 방지 대책을 체계적으로 적용해야 한다.

10. 참고 문헌

  • 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.
  • Goldstein, H. (1980). Classical Mechanics (2nd Edition). Addison-Wesley.
  • REP 103 — Standard Units of Measure and Coordinate Conventions. https://www.ros.org/reps/rep-0103.html
  • SciPy Documentation. “scipy.spatial.transform.Rotation.” https://docs.scipy.org/doc/scipy/reference/generated/scipy.spatial.transform.Rotation.html