659.49 쿼터니언 연산 (곱셈, 역, 켤레)

1. 개요

쿼터니언을 이용한 3차원 회전 표현의 실용적 가치는 쿼터니언 연산의 효율성에 기반한다. 쿼터니언의 세 가지 핵심 연산인 곱셈(multiplication), 역(inverse), 켤레(conjugate)는 회전의 합성, 역회전, 그리고 벡터의 좌표 변환을 수행하는 데 사용된다. 본 절에서는 각 연산의 수학적 정의, 기하학적 의미, 계산 절차, 그리고 ROS2 및 TF2 환경에서의 구현 방법을 체계적으로 다룬다.

2. 쿼터니언 켤레 (Conjugate)

2.1 정의

쿼터니언 \mathbf{q} = q_0 + q_1 i + q_2 j + q_3 k = (s, \mathbf{v})의 켤레(conjugate)는 벡터부의 부호를 반전한 쿼터니언이다:

\mathbf{q}^{*} = q_0 - q_1 i - q_2 j - q_3 k = (s, -\mathbf{v})

스칼라부는 유지되고 벡터부만 부호가 반전된다. 이는 복소수의 켤레 \bar{z} = a - bi를 4차원으로 확장한 것이다.

2.2 켤레의 대수적 성질

켤레 연산은 다음의 성질을 만족한다:

  1. 이중 켤레 (Involutory): (\mathbf{q}^{*})^{*} = \mathbf{q}
  2. 덧셈 보존: (\mathbf{p} + \mathbf{q})^{*} = \mathbf{p}^{*} + \mathbf{q}^{*}
  3. 곱셈 역순: (\mathbf{p}\mathbf{q})^{*} = \mathbf{q}^{*}\mathbf{p}^{*}
  4. 스칼라 곱 보존: (\alpha\mathbf{q})^{*} = \alpha\mathbf{q}^{*}, \alpha \in \mathbb{R}
  5. 노름과의 관계: \mathbf{q}\mathbf{q}^{*} = \mathbf{q}^{*}\mathbf{q} = \|\mathbf{q}\|^2

특히 성질 3은 행렬의 전치에 대한 (AB)^T = B^T A^T과 유사하며, 켤레가 곱셈의 순서를 뒤집는 반자기동형사상(anti-automorphism)임을 보여준다.

성질 5를 증명하면 다음과 같다:

\mathbf{q}\mathbf{q}^{*} = (s, \mathbf{v})(s, -\mathbf{v}) = (s^2 + \mathbf{v} \cdot \mathbf{v}, \; s(-\mathbf{v}) + s\mathbf{v} + \mathbf{v} \times (-\mathbf{v})) = (s^2 + \|\mathbf{v}\|^2, \; \mathbf{0})

외적 \mathbf{v} \times (-\mathbf{v}) = -\mathbf{v} \times \mathbf{v} = \mathbf{0}이고, 나머지 벡터 항은 상쇄되어 순수 스칼라 결과가 된다.

2.3 기하학적 의미

단위 쿼터니언 \mathbf{q}가 축 \hat{\mathbf{n}}에 대한 각도 \theta의 회전을 나타낼 때, 켤레 \mathbf{q}^{*}동일한 축에 대한 각도 -\theta의 회전, 즉 역회전(inverse rotation)을 나타낸다:

\mathbf{q} = \cos\frac{\theta}{2} + \sin\frac{\theta}{2}\hat{\mathbf{n}} \implies \mathbf{q}^{*} = \cos\frac{\theta}{2} - \sin\frac{\theta}{2}\hat{\mathbf{n}} = \cos\frac{-\theta}{2} + \sin\frac{-\theta}{2}\hat{\mathbf{n}}

이 관계가 성립하는 이유는 \cos(-\theta/2) = \cos(\theta/2)이고 \sin(-\theta/2) = -\sin(\theta/2)이기 때문이다.

2.4 구현

// C++ (tf2 라이브러리)
#include <tf2/LinearMath/Quaternion.h>

tf2::Quaternion q(0.0, 0.0, 0.7071, 0.7071);  // z축 90° 회전
tf2::Quaternion q_conj = q.inverse();  // tf2에서 단위 쿼터니언의 inverse()는 켤레와 동일

// 수동 켤레 계산
tf2::Quaternion q_conjugate(-q.x(), -q.y(), -q.z(), q.w());
# Python (NumPy)
import numpy as np

def quaternion_conjugate(q):
    """q = [x, y, z, w] 형식"""
    return np.array([-q[0], -q[1], -q[2], q[3]])

q = np.array([0.0, 0.0, 0.7071, 0.7071])
q_conj = quaternion_conjugate(q)
# 결과: [0.0, 0.0, -0.7071, 0.7071]

3. 쿼터니언 곱셈 (Multiplication)

3.1 정의

두 쿼터니언 \mathbf{p} = p_0 + p_1 i + p_2 j + p_3 k\mathbf{q} = q_0 + q_1 i + q_2 j + q_3 k의 곱은 분배법칙과 허수 단위의 곱셈 규칙을 적용하여 전개한다. 결과 쿼터니언 \mathbf{r} = \mathbf{p}\mathbf{q}의 각 성분은:

r_0 = p_0 q_0 - p_1 q_1 - p_2 q_2 - p_3 q_3

r_1 = p_0 q_1 + p_1 q_0 + p_2 q_3 - p_3 q_2

r_2 = p_0 q_2 - p_1 q_3 + p_2 q_0 + p_3 q_1

r_3 = p_0 q_3 + p_1 q_2 - p_2 q_1 + p_3 q_0

3.2 순서쌍 형식의 곱셈

순서쌍 표현 \mathbf{p} = (s_p, \mathbf{v}_p), \mathbf{q} = (s_q, \mathbf{v}_q)에서 곱셈은 다음과 같이 표현된다:

\mathbf{p}\mathbf{q} = (s_p s_q - \mathbf{v}_p \cdot \mathbf{v}_q, \; s_p \mathbf{v}_q + s_q \mathbf{v}_p + \mathbf{v}_p \times \mathbf{v}_q)

이 공식에서 각 항의 의미는 다음과 같다:

  • 스칼라부: s_p s_q - \mathbf{v}_p \cdot \mathbf{v}_q — 두 스칼라의 곱에서 벡터 내적을 뺀 값
  • 벡터부: s_p \mathbf{v}_q + s_q \mathbf{v}_p + \mathbf{v}_p \times \mathbf{v}_q — 스칼라-벡터 곱의 합에 벡터 외적을 더한 값

외적 항 \mathbf{v}_p \times \mathbf{v}_q는 반대칭(anti-symmetric)이므로, 이 항이 곱셈의 비가환성을 야기한다. 두 벡터부가 평행한 경우에만(\mathbf{v}_p \times \mathbf{v}_q = \mathbf{0}) 곱셈이 가환적이 된다.

3.3 행렬 형식의 곱셈

쿼터니언 곱셈을 행렬-벡터 곱으로 표현하면 구현이 용이하다. \mathbf{r} = \mathbf{p}\mathbf{q}에서 왼쪽 곱셈 행렬 L(\mathbf{p})는:

\mathbf{r} = L(\mathbf{p})\mathbf{q} = \begin{pmatrix} p_0 & -p_1 & -p_2 & -p_3 \\ p_1 & p_0 & -p_3 & p_2 \\ p_2 & p_3 & p_0 & -p_1 \\ p_3 & -p_2 & p_1 & p_0 \end{pmatrix} \begin{pmatrix} q_0 \\ q_1 \\ q_2 \\ q_3 \end{pmatrix}

오른쪽 곱셈 행렬 R(\mathbf{q})는:

\mathbf{r} = R(\mathbf{q})\mathbf{p} = \begin{pmatrix} q_0 & -q_1 & -q_2 & -q_3 \\ q_1 & q_0 & q_3 & -q_2 \\ q_2 & -q_3 & q_0 & q_1 \\ q_3 & q_2 & -q_1 & q_0 \end{pmatrix} \begin{pmatrix} p_0 \\ p_1 \\ p_2 \\ p_3 \end{pmatrix}

L(\mathbf{p}) \neq R(\mathbf{p})인 사실은 곱셈의 비가환성을 행렬 수준에서 확인해준다.

3.4 계산 복잡도

쿼터니언 곱셈의 계산 복잡도는 다음과 같다:

연산곱셈 횟수덧셈/뺄셈 횟수총 부동소수점 연산
직접 전개161228
행렬-벡터 곱161228

비교를 위해, 3 \times 3 회전 행렬의 곱셈은 27회의 곱셈과 18회의 덧셈(총 45회)을 필요로 한다. 따라서 쿼터니언 곱셈은 회전 행렬 곱셈보다 약 38% 적은 연산량으로 동일한 회전 합성을 수행한다.

3.5 기하학적 의미: 회전의 합성

단위 쿼터니언 \mathbf{q}_1\mathbf{q}_2의 곱 \mathbf{q}_2 \mathbf{q}_1은 먼저 \mathbf{q}_1에 의한 회전을 적용한 후 \mathbf{q}_2에 의한 회전을 적용하는 합성 회전(composite rotation)을 나타낸다:

L_{\mathbf{q}_2 \mathbf{q}_1}(\mathbf{p}) = \mathbf{q}_2 \mathbf{q}_1 \hat{\mathbf{p}} (\mathbf{q}_2 \mathbf{q}_1)^{*} = \mathbf{q}_2 (\mathbf{q}_1 \hat{\mathbf{p}} \mathbf{q}_1^{*}) \mathbf{q}_2^{*}

마지막 등호는 켤레의 역순 성질 (\mathbf{q}_2 \mathbf{q}_1)^{*} = \mathbf{q}_1^{*} \mathbf{q}_2^{*}과 결합법칙에 의해 성립한다.

곱셈 순서의 중요성: ROS2와 TF2에서 좌표 변환을 합성할 때, 곱셈의 순서에 주의해야 한다. 프레임 A에서 B로의 변환 \mathbf{q}_{AB}와 프레임 B에서 C로의 변환 \mathbf{q}_{BC}가 주어졌을 때, 프레임 A에서 C로의 합성 변환은:

\mathbf{q}_{AC} = \mathbf{q}_{BC} \cdot \mathbf{q}_{AB}

이다. 즉, 먼저 적용되는 변환이 오른쪽에 위치한다.

3.6 구현

// C++ (tf2 라이브러리)
#include <tf2/LinearMath/Quaternion.h>

tf2::Quaternion q1, q2;
q1.setRPY(0, 0, M_PI/4);  // z축 45° 회전
q2.setRPY(0, 0, M_PI/4);  // z축 45° 회전

// 합성 회전: 두 번의 45° 회전 = 90° 회전
tf2::Quaternion q_combined = q2 * q1;
q_combined.normalize();
# Python (tf_transformations)
from tf_transformations import quaternion_multiply, quaternion_from_euler

q1 = quaternion_from_euler(0, 0, 3.14159/4)  # z축 45° 회전
q2 = quaternion_from_euler(0, 0, 3.14159/4)  # z축 45° 회전

# 합성 회전: quaternion_multiply(q2, q1)
q_combined = quaternion_multiply(q2, q1)
# 결과: z축 90° 회전에 해당하는 쿼터니언
# Python (SciPy)
from scipy.spatial.transform import Rotation

r1 = Rotation.from_euler('z', 45, degrees=True)
r2 = Rotation.from_euler('z', 45, degrees=True)

r_combined = r2 * r1  # 합성 회전
q_combined = r_combined.as_quat()  # [x, y, z, w] 형식

4. 쿼터니언 역 (Inverse)

4.1 정의

쿼터니언 \mathbf{q}의 역(inverse) \mathbf{q}^{-1}\mathbf{q}\mathbf{q}^{-1} = \mathbf{q}^{-1}\mathbf{q} = 1을 만족하는 쿼터니언이다. 일반적인 (비영) 쿼터니언의 역은 다음과 같이 정의된다:

\mathbf{q}^{-1} = \frac{\mathbf{q}^{*}}{\|\mathbf{q}\|^2} = \frac{q_0 - q_1 i - q_2 j - q_3 k}{q_0^2 + q_1^2 + q_2^2 + q_3^2}

4.2 단위 쿼터니언의 역

단위 쿼터니언(\|\mathbf{q}\| = 1)의 경우, 역은 켤레와 동일하다:

\|\mathbf{q}\| = 1 \implies \mathbf{q}^{-1} = \mathbf{q}^{*}

이 성질은 로봇공학에서 매우 중요하다. 3D 회전을 나타내는 쿼터니언은 항상 단위 쿼터니언이므로, 역회전을 구할 때 나눗셈 연산이 불필요하다. 벡터부의 부호를 반전하는 것만으로 역을 얻을 수 있다.

4.3 역 쿼터니언의 성질

  1. 이중 역: (\mathbf{q}^{-1})^{-1} = \mathbf{q}
  2. 곱셈 역순: (\mathbf{p}\mathbf{q})^{-1} = \mathbf{q}^{-1}\mathbf{p}^{-1}
  3. 항등 원소의 역: \mathbf{1}^{-1} = \mathbf{1}

성질 2는 합성 회전의 역을 구할 때 중요하다. 예를 들어, \mathbf{q}_{AC} = \mathbf{q}_{BC}\mathbf{q}_{AB}일 때:

\mathbf{q}_{CA} = \mathbf{q}_{AC}^{-1} = (\mathbf{q}_{BC}\mathbf{q}_{AB})^{-1} = \mathbf{q}_{AB}^{-1}\mathbf{q}_{BC}^{-1} = \mathbf{q}_{BA}\mathbf{q}_{CB}

4.4 기하학적 의미

단위 쿼터니언의 역은 원래 회전의 역회전을 나타낸다. 축 \hat{\mathbf{n}}에 대한 각도 \theta의 회전 \mathbf{q}의 역 \mathbf{q}^{-1} = \mathbf{q}^{*}는 동일한 축에 대한 각도 -\theta의 회전이다.

TF2에서 프레임 A에서 B로의 변환 T_{AB}가 주어졌을 때, 프레임 B에서 A로의 변환은 역변환 T_{BA} = T_{AB}^{-1}이며, 회전 성분은 쿼터니언의 켤레로 구해진다. TF2는 이 역변환을 내부적으로 자동 수행하므로, 사용자가 lookupTransform("A", "B")lookupTransform("B", "A") 중 어느 방향이든 요청할 수 있다.

4.5 구현

// C++ (tf2 라이브러리)
#include <tf2/LinearMath/Quaternion.h>

tf2::Quaternion q;
q.setRPY(0.1, 0.2, 0.3);
q.normalize();

// 역 쿼터니언 (단위 쿼터니언이므로 켤레와 동일)
tf2::Quaternion q_inv = q.inverse();

// 검증: q * q_inv ≈ 항등 쿼터니언
tf2::Quaternion identity = q * q_inv;
// identity ≈ (0, 0, 0, 1)
# Python (tf_transformations)
from tf_transformations import quaternion_inverse

q = [0.0, 0.0, 0.7071, 0.7071]  # [x, y, z, w]
q_inv = quaternion_inverse(q)
# 결과: [0.0, 0.0, -0.7071, 0.7071]
# Python (SciPy)
from scipy.spatial.transform import Rotation

r = Rotation.from_euler('z', 90, degrees=True)
r_inv = r.inv()
q_inv = r_inv.as_quat()

5. 복합 연산

5.1 벡터 회전

쿼터니언 \mathbf{q}에 의한 3D 벡터 \mathbf{p}의 회전은 쿼터니언 곱셈과 켤레를 조합하여 수행한다:

\mathbf{p}' = \mathbf{q}\hat{\mathbf{p}}\mathbf{q}^{*}

여기서 \hat{\mathbf{p}} = (0, \mathbf{p})는 순수 쿼터니언이다. 이 연산을 전개하면:

\mathbf{p}' = \mathbf{p} + 2s(\mathbf{v} \times \mathbf{p}) + 2\mathbf{v} \times (\mathbf{v} \times \mathbf{p})

여기서 s\mathbf{q}의 스칼라부, \mathbf{v}는 벡터부이다. 이 전개식은 두 번의 외적과 스칼라 곱셈으로 구성되며, 전체 쿼터니언 곱셈(28 FLOPs)보다 효율적인 21 FLOPs로 계산된다.

// C++ 구현: 최적화된 벡터 회전
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Vector3.h>

tf2::Vector3 rotate_vector(const tf2::Quaternion& q, const tf2::Vector3& v) {
    tf2::Vector3 u(q.x(), q.y(), q.z());  // 벡터부
    double s = q.w();                       // 스칼라부
    
    return v + 2.0 * s * u.cross(v) + 2.0 * u.cross(u.cross(v));
}
// tf2 라이브러리의 내장 연산
tf2::Quaternion q;
q.setRPY(0, 0, M_PI / 2);  // z축 90° 회전

tf2::Vector3 v(1.0, 0.0, 0.0);  // x축 단위 벡터
tf2::Vector3 v_rotated = tf2::quatRotate(q, v);
// 결과: (0, 1, 0) — x축이 y축으로 회전

5.2 쿼터니언 차이 (Difference)

두 회전 \mathbf{q}_1\mathbf{q}_2 사이의 상대 회전(relative rotation) 또는 회전 차이(rotation difference)는 다음과 같이 계산한다:

\mathbf{q}_{\text{diff}} = \mathbf{q}_2 \mathbf{q}_1^{-1} = \mathbf{q}_2 \mathbf{q}_1^{*}

\mathbf{q}_{\text{diff}}\mathbf{q}_1에서 \mathbf{q}_2로 변환하는 회전이다. 두 회전 사이의 최소 각도 차이는:

\theta_{\text{diff}} = 2\arccos(|\mathbf{q}_1 \cdot \mathbf{q}_2|)

여기서 \mathbf{q}_1 \cdot \mathbf{q}_2는 4차원 내적이며, 절댓값은 이중 피복 성질을 고려한 것이다.

// 두 쿼터니언 사이의 각도 차이 (라디안)
double quaternion_angle_diff(const tf2::Quaternion& q1, 
                              const tf2::Quaternion& q2) {
    double dot = q1.dot(q2);
    return 2.0 * std::acos(std::min(std::abs(dot), 1.0));
}

5.3 쿼터니언 거듭제곱 (Power)

단위 쿼터니언의 t제곱(t \in \mathbb{R})은 회전 각도를 t배로 스케일링하는 연산이다:

\mathbf{q}^t = \cos\left(\frac{t\theta}{2}\right) + \sin\left(\frac{t\theta}{2}\right)\hat{\mathbf{n}}

여기서 \theta = 2\arccos(w)이고 \hat{\mathbf{n}}은 정규화된 벡터부이다.

  • t = 0: 항등 회전
  • t = 1: 원래 회전
  • t = -1: 역회전 (\mathbf{q}^{-1}과 동일)
  • t = 0.5: 절반 회전 (절반 각도의 회전)
  • t = 2: 두 배 회전
tf2::Quaternion quaternion_power(const tf2::Quaternion& q, double t) {
    // 항등 쿼터니언에 가까운 경우 처리
    if (std::abs(q.w()) > 0.9999) {
        return q;
    }
    
    double half_theta = std::acos(q.w());
    double new_half_theta = t * half_theta;
    double sin_ratio = std::sin(new_half_theta) / std::sin(half_theta);
    
    return tf2::Quaternion(
        q.x() * sin_ratio,
        q.y() * sin_ratio,
        q.z() * sin_ratio,
        std::cos(new_half_theta)
    );
}

6. 연산의 계산 복잡도 비교

다음 표는 쿼터니언과 회전 행렬의 주요 연산별 계산 복잡도를 비교한 것이다:

연산쿼터니언 (FLOPs)회전 행렬 (FLOPs)비율
합성 (곱셈)28450.62
역 (단위)3 (부호 반전)0 (전치)
벡터 회전21 (최적화)151.40
메모리 저장4 doubles9 doubles0.44
정규화/직교화9~81 (SVD)0.11

단일 벡터 회전에서는 회전 행렬이 약간 효율적이나, 회전 합성과 메모리 사용에서는 쿼터니언이 현저히 우수하다. 다수의 회전 합성이 필요한 관절 체인 계산이나, 메모리가 제한된 임베디드 환경에서는 쿼터니언이 유리하다.

7. 연산 규칙 요약

연산공식비고
켤레\mathbf{q}^{*} = (w, -x, -y, -z)벡터부 부호 반전
노름\Vert\mathbf{q}\Vert = \sqrt{w^2 + x^2 + y^2 + z^2}4차원 유클리드 거리
곱셈\mathbf{pq} = (s_p s_q - \mathbf{v}_p \cdot \mathbf{v}_q, \; s_p\mathbf{v}_q + s_q\mathbf{v}_p + \mathbf{v}_p \times \mathbf{v}_q)비가환적
역 (일반)\mathbf{q}^{-1} = \mathbf{q}^{*} / \Vert\mathbf{q}\Vert^2단위 시: \mathbf{q}^{-1} = \mathbf{q}^{*}
벡터 회전\mathbf{p}' = \mathbf{q}\hat{\mathbf{p}}\mathbf{q}^{*}\hat{\mathbf{p}} = (0, \mathbf{p})
회전 합성\mathbf{q}_{AC} = \mathbf{q}_{BC}\mathbf{q}_{AB}오른쪽이 먼저 적용
차이\mathbf{q}_{\text{diff}} = \mathbf{q}_2\mathbf{q}_1^{*}\mathbf{q}_1에서 \mathbf{q}_2로의 회전

8. 요약

쿼터니언의 켤레, 곱셈, 역 연산은 3차원 회전의 역변환, 합성, 좌표 변환을 수행하기 위한 기본 도구이다. 켤레는 벡터부의 부호 반전으로 정의되며, 단위 쿼터니언의 경우 역과 동일하다. 곱셈은 비가환적 연산으로 회전의 합성에 대응하며, 회전 행렬 곱셈 대비 약 38% 적은 연산량을 필요로 한다. 이 세 가지 기본 연산의 조합을 통해 벡터 회전, 회전 차이, 거듭제곱 등의 복합 연산이 구성되며, TF2 라이브러리와 ROS2 생태계에서 좌표 변환의 핵심 메커니즘으로 활용된다.

9. 참고 문헌

  • Kuipers, J. B. (1999). Quaternions and Rotation Sequences: A Primer with Applications to Orbits, Aerospace, and Virtual Reality. Princeton University Press.
  • Diebel, J. (2006). “Representing Attitude: Euler Angles, Unit Quaternions, and Rotation Vectors.” Stanford University Technical Report.
  • Shoemake, K. (1985). “Animating Rotation with Quaternion Curves.” ACM SIGGRAPH Computer Graphics, 19(3), 245-254.
  • Eberly, D. (2010). “Rotation Representations and Performance Issues.” Geometric Tools Technical Report.
  • Open Robotics. “tf2 — ROS 2 Documentation.” https://docs.ros.org/en/rolling/Concepts/Intermediate/About-Tf2.html