659.59 동차 변환 행렬 (Homogeneous Transformation Matrix)

1. 개요

동차 변환 행렬(homogeneous transformation matrix)은 3차원 공간에서의 회전과 병진을 하나의 4 \times 4 행렬로 통합하여 표현하는 방법이다. 회전 행렬과 병진 벡터를 별도로 다루면 변환의 합성 시 \mathbf{p}' = R\mathbf{p} + \mathbf{t}와 같은 비선형(아핀) 연산이 필요하지만, 동차 좌표(homogeneous coordinates)를 도입하면 이를 단일 행렬 곱셈으로 통일할 수 있다. 이러한 수학적 편의성으로 인해 동차 변환 행렬은 로봇 운동학, 컴퓨터 비전, 컴퓨터 그래픽스에서 좌표 변환의 표준 도구로 사용된다. 본 절에서는 동차 좌표의 개념, 동차 변환 행렬의 구조, 대수적 성질, 그리고 ROS2 환경에서의 표현과 활용을 체계적으로 다룬다.

2. 동차 좌표 (Homogeneous Coordinates)

2.1 정의

3차원 유클리드 좌표 \mathbf{p} = (p_x, p_y, p_z)^T \in \mathbb{R}^3에 대응하는 동차 좌표는 4차원 벡터로 다음과 같이 정의된다:

\tilde{\mathbf{p}} = \begin{pmatrix} p_x \\ p_y \\ p_z \\ 1 \end{pmatrix} \in \mathbb{R}^4

네 번째 성분(스케일 인자)을 1로 설정하여 점(point)을 표현한다. 일반적으로 동차 좌표 (x, y, z, w)^T (단, w \neq 0)에 대응하는 유클리드 좌표는 (x/w, y/w, z/w)^T이다.

2.2 점과 방향 벡터의 구분

동차 좌표에서 네 번째 성분의 값에 따라 점과 방향 벡터를 구분한다:

네 번째 성분기하학적 객체변환 시 적용되는 연산
w = 1점 (Point)회전 + 병진
w = 0방향 벡터 (Direction Vector)회전만 (병진 불적용)

\text{점:} \quad \tilde{\mathbf{p}} = \begin{pmatrix} p_x \\ p_y \\ p_z \\ 1 \end{pmatrix}, \quad \text{벡터:} \quad \tilde{\mathbf{v}} = \begin{pmatrix} v_x \\ v_y \\ v_z \\ 0 \end{pmatrix}

이 구분은 물리적으로 중요한 의미를 가진다. 위치를 나타내는 점은 좌표계가 이동하면 좌표값이 변하지만, 방향(예: 속도, 힘)을 나타내는 벡터는 좌표계의 위치에 무관하고 방향에만 의존한다.

3. 동차 변환 행렬의 구조

3.1 정의

동차 변환 행렬 T \in SE(3)4 \times 4 행렬로 다음과 같이 구성된다:

T = \begin{pmatrix} R & \mathbf{t} \\ \mathbf{0}^T & 1 \end{pmatrix} = \begin{pmatrix} r_{11} & r_{12} & r_{13} & t_x \\ r_{21} & r_{22} & r_{23} & t_y \\ r_{31} & r_{32} & r_{33} & t_z \\ 0 & 0 & 0 & 1 \end{pmatrix}

여기서:

  • R \in SO(3): 3 \times 3 회전 행렬
  • \mathbf{t} \in \mathbb{R}^3: 3 \times 1 병진 벡터
  • \mathbf{0}^T = (0, 0, 0): 마지막 행의 처음 세 원소
  • 1: 마지막 행의 마지막 원소

마지막 행 (0, 0, 0, 1)은 고정되어 있으며, 이 행이 동차 좌표의 스케일을 보존하는 역할을 한다.

3.2 특수 유클리드 군 SE(3)

동차 변환 행렬의 집합은 특수 유클리드 군(Special Euclidean group) SE(3)을 형성한다:

SE(3) = \left\{ T = \begin{pmatrix} R & \mathbf{t} \\ \mathbf{0}^T & 1 \end{pmatrix} \;\middle|\; R \in SO(3), \; \mathbf{t} \in \mathbb{R}^3 \right\}

SE(3)4 \times 4 행렬 곱셈에 대해 군을 형성하며, 3차원 공간에서의 모든 강체 변환(rigid body transformation)을 나타낸다. SE(3)의 차원은 6이며, 이는 3차원 회전(3자유도)과 3차원 병진(3자유도)의 합이다.

3.3 변환의 적용

동차 변환 행렬에 의한 점의 변환:

\tilde{\mathbf{p}}' = T \tilde{\mathbf{p}} = \begin{pmatrix} R & \mathbf{t} \\ \mathbf{0}^T & 1 \end{pmatrix} \begin{pmatrix} \mathbf{p} \\ 1 \end{pmatrix} = \begin{pmatrix} R\mathbf{p} + \mathbf{t} \\ 1 \end{pmatrix}

유클리드 좌표로 다시 추출하면:

\mathbf{p}' = R\mathbf{p} + \mathbf{t}

이는 회전 후 병진을 적용하는 공식 \mathbf{p}' = R\mathbf{p} + \mathbf{t}를 행렬 곱셈 하나로 표현한 것이다.

방향 벡터의 변환:

\tilde{\mathbf{v}}' = T \tilde{\mathbf{v}} = \begin{pmatrix} R & \mathbf{t} \\ \mathbf{0}^T & 1 \end{pmatrix} \begin{pmatrix} \mathbf{v} \\ 0 \end{pmatrix} = \begin{pmatrix} R\mathbf{v} \\ 0 \end{pmatrix}

네 번째 성분이 0인 벡터에는 병진이 적용되지 않으며, 회전만 적용된다.

4. 동차 변환 행렬의 대수적 성질

4.1 군 구조

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

공리조건비고
닫힘T_1, T_2 \in SE(3) \Rightarrow T_1 T_2 \in SE(3)두 강체 변환의 합성은 강체 변환
결합법칙(T_1 T_2) T_3 = T_1 (T_2 T_3)행렬 곱셈의 결합법칙
항등원I_4 T = T I_4 = T4 \times 4 단위 행렬
역원T T^{-1} = T^{-1} T = I_4역변환 존재

SE(3)비가환군이다. 즉, 일반적으로 T_1 T_2 \neq T_2 T_1이다.

4.2 역행렬

동차 변환 행렬의 역행렬은 일반적인 4 \times 4 역행렬 계산을 필요로 하지 않으며, 회전 행렬의 전치와 병진 벡터의 역변환으로 효율적으로 계산된다:

T^{-1} = \begin{pmatrix} R^T & -R^T\mathbf{t} \\ \mathbf{0}^T & 1 \end{pmatrix}

이 공식은 R^{-1} = R^T인 직교 행렬의 성질을 이용한 것이다. 계산 비용은 3 \times 3 행렬-벡터 곱 1회와 부호 반전으로, 일반 4 \times 4 역행렬(O(n^3))에 비해 현저히 효율적이다.

4.3 항등 변환

항등 변환은 4 \times 4 단위 행렬이다:

T_{\text{identity}} = I_4 = \begin{pmatrix} 1 & 0 & 0 & 0 \\ 0 & 1 & 0 & 0 \\ 0 & 0 & 1 & 0 \\ 0 & 0 & 0 & 1 \end{pmatrix}

이는 회전 없음(R = I_3)과 병진 없음(\mathbf{t} = \mathbf{0})을 나타낸다.

5. 특수 형태의 동차 변환

5.1 순수 병진

회전이 없는 순수 병진 변환:

T_{\text{trans}}(\mathbf{t}) = \begin{pmatrix} I_3 & \mathbf{t} \\ \mathbf{0}^T & 1 \end{pmatrix} = \begin{pmatrix} 1 & 0 & 0 & t_x \\ 0 & 1 & 0 & t_y \\ 0 & 0 & 1 & t_z \\ 0 & 0 & 0 & 1 \end{pmatrix}

순수 병진의 합성은 가환적이다: T_{\text{trans}}(\mathbf{t}_1) T_{\text{trans}}(\mathbf{t}_2) = T_{\text{trans}}(\mathbf{t}_1 + \mathbf{t}_2)

5.2 순수 회전

병진이 없는 순수 회전 변환:

T_{\text{rot}}(R) = \begin{pmatrix} R & \mathbf{0} \\ \mathbf{0}^T & 1 \end{pmatrix}

순수 회전의 합성은 비가환적이다: T_{\text{rot}}(R_1) T_{\text{rot}}(R_2) = T_{\text{rot}}(R_1 R_2)

5.3 기본 축 회전의 동차 행렬

x축 기준 \alpha 회전:

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

y축 기준 \beta 회전, z축 기준 \gamma 회전도 유사하게 구성된다.

6. ROS2에서의 동차 변환 행렬

6.1 TF2와 동차 변환 행렬의 관계

TF2 라이브러리는 내부적으로 쿼터니언과 병진 벡터를 사용하여 변환을 저장하지만, 이를 동차 변환 행렬로 전환할 수 있다:

#include <tf2/LinearMath/Transform.h>
#include <Eigen/Geometry>

// tf2::Transform에서 Eigen 동차 행렬로 변환
tf2::Transform tf_transform;
tf_transform.setOrigin(tf2::Vector3(1.0, 0.5, 0.0));
tf2::Quaternion q;
q.setRPY(0, 0, M_PI/4);
tf_transform.setRotation(q);

// 4x4 동차 변환 행렬 구성
Eigen::Affine3d T;
tf2::transformTFToEigen(tf_transform, T);  // tf2_eigen 사용 시
// 또는 수동 구성
Eigen::Matrix4d T_mat = Eigen::Matrix4d::Identity();
T_mat.block<3,3>(0,0) = Eigen::Quaterniond(
    q.w(), q.x(), q.y(), q.z()).toRotationMatrix();
T_mat.block<3,1>(0,3) = Eigen::Vector3d(1.0, 0.5, 0.0);
import numpy as np
from scipy.spatial.transform import Rotation

def transform_to_matrix(translation, quaternion):
    """병진 + 쿼터니언을 4x4 동차 변환 행렬로 변환"""
    T = np.eye(4)
    r = Rotation.from_quat(quaternion)  # [x, y, z, w]
    T[:3, :3] = r.as_matrix()
    T[:3, 3] = translation
    return T

# 사용 예
translation = [1.0, 0.5, 0.0]
quaternion = [0, 0, 0.3827, 0.9239]  # z축 45° 회전
T = transform_to_matrix(translation, quaternion)

6.2 Eigen의 Affine3d와 Isometry3d

Eigen 라이브러리에서 동차 변환 행렬은 Eigen::Affine3d 또는 Eigen::Isometry3d로 표현된다:

#include <Eigen/Geometry>

// Isometry3d: 등거리 변환 (회전 + 병진)
Eigen::Isometry3d T = Eigen::Isometry3d::Identity();
T.rotate(Eigen::AngleAxisd(M_PI/4, Eigen::Vector3d::UnitZ()));
T.pretranslate(Eigen::Vector3d(1.0, 0.5, 0.0));

// 점 변환
Eigen::Vector3d p(2.0, 0.0, 0.0);
Eigen::Vector3d p_transformed = T * p;

// 4x4 행렬로 접근
Eigen::Matrix4d T_matrix = T.matrix();

// 회전과 병진 추출
Eigen::Matrix3d R = T.rotation();
Eigen::Vector3d t = T.translation();

Isometry3dAffine3d의 특수화로서, 스케일이 포함되지 않는 등거리 변환(강체 변환)만을 표현한다. 내부적으로는 동일한 4 \times 4 행렬을 사용하지만, 역행렬 계산에서 최적화된 방법(전치 기반)을 적용할 수 있다.

7. 동차 변환 행렬과 쿼터니언 표현의 비교

특성동차 변환 행렬쿼터니언 + 벡터
파라미터 수16 (12 유효)7
메모리128 바이트56 바이트
변환 합성4 \times 4 행렬 곱 (64 곱셈)쿼터니언 곱 + 회전 적용 (~49 연산)
점 변환행렬-벡터 곱 (16 곱셈)쿼터니언 회전 + 덧셈 (~24 연산)
역변환R^T-R^T\mathbf{t}켤레와 회전 적용
직관성높음 (기하학적 해석 용이)중간
수치 안정성직교화 필요정규화로 충분

TF2가 내부적으로 쿼터니언 + 벡터 표현을 사용하는 이유는 메모리 효율성과 수치적 보정의 용이성에 있다. 동차 변환 행렬은 주로 운동학 체인 계산, 시각화, 외부 라이브러리 연동 시 사용된다.

8. 요약

동차 변환 행렬은 4 \times 4 행렬로 3D 회전과 병진을 통합하여 표현하며, 동차 좌표를 이용하여 아핀 변환을 선형 행렬 곱셈으로 환원한다. 동차 좌표에서 네 번째 성분이 1이면 점, 0이면 방향 벡터를 나타내어 병진 적용 여부가 자동으로 결정된다. 동차 변환 행렬의 집합은 특수 유클리드 군 SE(3)을 형성하며, 6자유도의 강체 변환을 나타낸다. 역변환은 회전 행렬의 전치와 병진의 역변환으로 효율적으로 계산된다. ROS2에서는 Eigen의 Isometry3dAffine3d를 이용하여 동차 변환 행렬을 활용할 수 있다.

9. 참고 문헌

  • Craig, J. J. (2005). Introduction to Robotics: Mechanics and Control (3rd Edition). Pearson Prentice Hall.
  • Murray, R. M., Li, Z., & Sastry, S. S. (1994). A Mathematical Introduction to Robotic Manipulation. CRC Press.
  • Siciliano, B. et al. (2010). Robotics: Modelling, Planning and Control. Springer.
  • Hartley, R. & Zisserman, A. (2003). Multiple View Geometry in Computer Vision (2nd Edition). Cambridge University Press.
  • Open Robotics. “tf2 — ROS 2 Documentation.” https://docs.ros.org/en/rolling/Concepts/Intermediate/About-Tf2.html