659.18 TransformStamped의 변환 (Transform) 필드
1. 개요
geometry_msgs/msg/TransformStamped 메시지의 transform 필드는 geometry_msgs/msg/Transform 타입으로, 부모 프레임에서 자식 프레임으로의 강체 변환(rigid body transformation)을 구체적인 수치 데이터로 기술한다. 이 필드는 3차원 공간에서의 병진(translation)과 회전(rotation) 정보를 독립적으로 포함하며, 두 좌표 프레임 간의 공간적 관계를 완전하게 정의한다.
2. Transform 메시지의 정의
geometry_msgs/msg/Transform 메시지는 다음과 같이 정의된다.
# geometry_msgs/msg/Transform
geometry_msgs/Vector3 translation
geometry_msgs/Quaternion rotation
이 메시지는 두 개의 하위 필드로 구성된다. translation 필드는 3차원 병진 벡터를 나타내고, rotation 필드는 3차원 회전을 쿼터니언으로 표현한다. 이 두 필드의 조합은 3차원 유클리드 공간에서의 강체 변환을 완전히 기술하며, 6 자유도(6-DOF: 3 병진 + 3 회전)의 변환에 해당한다.
3. translation 필드
3.1 메시지 구조
translation 필드는 geometry_msgs/msg/Vector3 타입으로 정의된다.
# geometry_msgs/msg/Vector3
float64 x
float64 y
float64 z
3.2 물리적 의미
translation 필드는 부모 프레임(parent frame)의 원점에서 자식 프레임(child frame)의 원점까지의 위치 벡터(position vector)를 나타낸다. 이 벡터는 부모 프레임의 좌표축을 기준으로 표현된다.
부모 프레임을 A, 자식 프레임을 B라 하면, translation 필드는 다음과 같이 표현된다.
\mathbf{t}^{A}_{B} = \begin{pmatrix} t_x \\ t_y \\ t_z \end{pmatrix}
여기서 각 성분의 의미는 다음과 같다.
| 성분 | 설명 | 단위 |
|---|---|---|
| t_x | 부모 프레임 x축 방향의 변위 | m |
| t_y | 부모 프레임 y축 방향의 변위 | m |
| t_z | 부모 프레임 z축 방향의 변위 | m |
3.3 단위 규약
ROS2의 단위 규약(REP 103)에 따라, 병진 변환의 모든 성분은 미터(m) 단위를 사용한다. 이는 SI 단위계를 따르는 것이며, 밀리미터, 센티미터, 인치 등의 다른 단위를 사용하여서는 안 된다.
3.4 데이터 타입
각 성분은 IEEE 754 64비트 배정밀도 부동소수점(float64, double)으로 표현된다. 이를 통해 약 15–16자리의 유효 숫자를 보장하며, 나노미터 수준의 미세한 위치 차이도 표현할 수 있다. 이러한 정밀도는 정밀 로봇 매니퓰레이션, 측량, 그리고 항법 시스템에서 요구되는 수준을 충족한다.
3.5 사용 예시
다음은 부모 프레임 odom에서 자식 프레임 base_link까지 x축 방향으로 2.5m, y축 방향으로 1.0m 떨어진 위치를 설정하는 예시이다.
transform.translation.x = 2.5; // odom 프레임의 x축 방향 2.5m
transform.translation.y = 1.0; // odom 프레임의 y축 방향 1.0m
transform.translation.z = 0.0; // 지면 높이 동일
4. rotation 필드
4.1 메시지 구조
rotation 필드는 geometry_msgs/msg/Quaternion 타입으로 정의된다.
# geometry_msgs/msg/Quaternion
float64 x
float64 y
float64 z
float64 w
4.2 쿼터니언의 수학적 기초
쿼터니언(quaternion)은 3차원 회전을 4개의 실수로 표현하는 수학적 도구이다. 단위 쿼터니언 q는 다음과 같이 정의된다.
q = w + x\mathbf{i} + y\mathbf{j} + z\mathbf{k}
여기서 \mathbf{i}, \mathbf{j}, \mathbf{k}는 쿼터니언의 허수 기저이며, 다음 관계를 만족한다.
\mathbf{i}^2 = \mathbf{j}^2 = \mathbf{k}^2 = \mathbf{i}\mathbf{j}\mathbf{k} = -1
ROS2에서는 쿼터니언의 성분을 (x, y, z, w) 순서로 저장한다. 여기서 (x, y, z)는 벡터 부분(허수부)이고, w는 스칼라 부분(실수부)이다.
4.3 단위 쿼터니언 조건
회전을 나타내기 위해서는 쿼터니언이 단위 노름(unit norm) 조건을 만족하여야 한다.
\lVert q \rVert = \sqrt{x^2 + y^2 + z^2 + w^2} = 1
이 조건을 만족하지 않는 쿼터니언은 유효한 회전을 표현하지 않으며, 변환 연산의 결과가 부정확해질 수 있다.
4.4 축-각 표현과의 관계
단위 쿼터니언은 회전축 \hat{\mathbf{n}} = (n_x, n_y, n_z)과 회전각 \theta로부터 다음과 같이 구성된다.
q = \cos\frac{\theta}{2} + \sin\frac{\theta}{2}(n_x\mathbf{i} + n_y\mathbf{j} + n_z\mathbf{k})
따라서 각 성분은 다음과 같다.
\begin{aligned} w &= \cos\frac{\theta}{2} \\ x &= n_x \sin\frac{\theta}{2} \\ y &= n_y \sin\frac{\theta}{2} \\ z &= n_z \sin\frac{\theta}{2} \end{aligned}
4.5 특수 회전값
4.5.1 항등 회전 (Identity Rotation)
회전이 없는 상태, 즉 두 프레임의 축 방향이 완전히 동일한 경우의 쿼터니언은 다음과 같다.
q_{\text{identity}} = (x=0, y=0, z=0, w=1)
4.5.2 주요 축 회전
| 회전 | 쿼터니언 (x, y, z, w) |
|---|---|
| z축 기준 90° 회전 | (0, 0, 0.7071, 0.7071) |
| z축 기준 180° 회전 | (0, 0, 1, 0) |
| y축 기준 90° 회전 | (0, 0.7071, 0, 0.7071) |
| x축 기준 90° 회전 | (0.7071, 0, 0, 0.7071) |
4.6 쿼터니언의 장점
TF2에서 회전 표현으로 쿼터니언을 채택한 이유는 다음과 같다.
- 짐벌 락 회피: 오일러 각 표현에서 발생하는 짐벌 락(gimbal lock) 특이점이 없다.
- 보간 적합성: 구면 선형 보간(SLERP)을 통해 두 회전 사이의 부드러운 중간 회전을 계산할 수 있다.
- 연산 효율성: 쿼터니언 곱셈은 회전 행렬 곱셈(9개 요소)보다 적은 연산량(4개 요소)으로 회전 합성이 가능하다.
- 수치 안정성: 정규화 연산이 단순하여, 반복적인 회전 합성 시 발생하는 수치적 오차를 쉽게 보정할 수 있다.
5. 동차 변환 행렬과의 관계
Transform 필드가 표현하는 강체 변환은 4 \times 4 동차 변환 행렬(homogeneous transformation matrix)로 다음과 같이 표현된다.
T = \begin{bmatrix} R & \mathbf{t} \\ \mathbf{0}^T & 1 \end{bmatrix} = \begin{bmatrix} 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{bmatrix}
여기서 R은 쿼터니언 rotation으로부터 도출되는 3 \times 3 회전 행렬이고, \mathbf{t}는 translation에 해당하는 병진 벡터이다. 회전 행렬 R은 쿼터니언으로부터 다음과 같이 계산된다.
R = \begin{bmatrix} 1 - 2(y^2 + z^2) & 2(xy - wz) & 2(xz + wy) \\ 2(xy + wz) & 1 - 2(x^2 + z^2) & 2(yz - wx) \\ 2(xz - wy) & 2(yz + wx) & 1 - 2(x^2 + y^2) \end{bmatrix}
6. 변환 합성
두 개의 연속된 변환 T_1과 T_2를 합성(composition)하여 하나의 변환 T_{12}를 구할 수 있다.
T_{12} = T_1 \cdot T_2
합성된 변환의 병진과 회전 성분은 다음과 같다.
\begin{aligned} \mathbf{t}_{12} &= R_1 \cdot \mathbf{t}_2 + \mathbf{t}_1 \\ q_{12} &= q_1 \otimes q_2 \end{aligned}
여기서 \otimes는 쿼터니언 곱셈(Hamilton product)을 나타낸다. TF2는 변환 트리를 통해 임의의 두 프레임 사이의 변환을 이러한 합성 연산을 통해 자동으로 계산한다.
7. 역변환
변환 T의 역변환 T^{-1}은 다음과 같다.
T^{-1} = \begin{bmatrix} R^T & -R^T \mathbf{t} \\ \mathbf{0}^T & 1 \end{bmatrix}
쿼터니언과 병진 성분으로 표현하면 다음과 같다.
\begin{aligned} q^{-1} &= (−x, −y, −z, w) \quad (\text{단위 쿼터니언의 역 = 켤레}) \\ \mathbf{t}^{-1} &= −R^T \mathbf{t} \end{aligned}
TF2는 lookupTransform() 호출 시 변환 트리의 간선 방향과 반대 방향의 변환이 요청되면, 이 역변환을 자동으로 계산하여 반환한다.
8. 프로그래밍 예시
8.1 C++ (rclcpp) 예시
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <tf2/LinearMath/Quaternion.h>
geometry_msgs::msg::TransformStamped t;
// 병진 변환 설정
t.transform.translation.x = 1.0;
t.transform.translation.y = 0.0;
t.transform.translation.z = 0.5;
// 쿼터니언을 오일러 각(RPY)으로부터 생성
tf2::Quaternion q;
q.setRPY(0.0, 0.0, M_PI / 4.0); // roll=0, pitch=0, yaw=45°
t.transform.rotation.x = q.x();
t.transform.rotation.y = q.y();
t.transform.rotation.z = q.z();
t.transform.rotation.w = q.w();
8.2 Python (rclpy) 예시
from geometry_msgs.msg import TransformStamped
from tf_transformations import quaternion_from_euler
import math
t = TransformStamped()
# 병진 변환 설정
t.transform.translation.x = 1.0
t.transform.translation.y = 0.0
t.transform.translation.z = 0.5
# 쿼터니언을 오일러 각(RPY)으로부터 생성
q = quaternion_from_euler(0.0, 0.0, math.pi / 4.0)
t.transform.rotation.x = q[0]
t.transform.rotation.y = q[1]
t.transform.rotation.z = q[2]
t.transform.rotation.w = q[3]
9. Transform 필드 설정 시 주의 사항
9.1 쿼터니언 기본값 문제
geometry_msgs/msg/Quaternion 메시지의 기본 초기화 값은 (x=0, y=0, z=0, w=0)이다. 이는 노름이 0인 유효하지 않은 쿼터니언이다. 따라서 TransformStamped 메시지를 생성한 후에는 반드시 rotation.w를 명시적으로 설정하여야 한다. 항등 회전을 의도하는 경우 rotation.w = 1.0으로 설정한다.
9.2 쿼터니언 정규화
반복적인 변환 합성이나 부동소수점 연산의 누적 오차로 인해 쿼터니언의 노름이 1에서 미세하게 벗어날 수 있다. 이러한 경우 주기적으로 쿼터니언을 정규화하여 단위 노름 조건을 유지하여야 한다.
q_{\text{normalized}} = \frac{q}{\lVert q \rVert}
9.3 병진과 회전의 독립성
Transform 필드의 translation과 rotation은 물리적으로는 하나의 강체 변환을 구성하지만, 메시지 구조상으로는 독립적인 필드이다. 따라서 병진만 변경하고 회전을 변경하지 않거나, 그 반대의 경우에도 각 필드를 독립적으로 설정할 수 있다. 다만, 두 필드가 함께 하나의 유효한 강체 변환을 구성하는지 항상 확인하여야 한다.
9.4 좌표계 규약 준수
ROS2의 오른손 좌표계 규약(REP 103)에 따라, x축은 전방(forward), y축은 좌측(left), z축은 상방(up)을 나타낸다. translation의 각 성분은 이 규약에 따른 방향의 변위를 의미하며, rotation의 양의 회전 방향은 오른손 법칙(right-hand rule)을 따른다.
10. 참고 문헌
- ROS2 공식 문서, “geometry_msgs/msg/Transform,” https://docs.ros.org/en/humble/p/geometry_msgs/
- ROS2 공식 문서, “geometry_msgs/msg/Quaternion,” https://docs.ros.org/en/humble/p/geometry_msgs/
- ROS Enhancement Proposal (REP) 103, “Standard Units of Measure and Coordinate Conventions,” https://www.ros.org/reps/rep-0103.html
- Kuipers, J. B., Quaternions and Rotation Sequences, Princeton University Press, 2002.
- Diebel, J., “Representing Attitude: Euler Angles, Unit Quaternions, and Rotation Vectors,” Stanford University Technical Report, 2006.
- ROS2 Humble Hawksbill 기준 (2022)