659.58 3D 병진 (Translation) 표현
1. 개요
3차원 좌표 변환은 **회전(rotation)**과 **병진(translation)**의 두 가지 기본 요소로 구성된다. 앞선 절들에서 회전을 표현하는 다양한 방법(쿼터니언, 오일러 각, 회전 행렬, 축-각)을 다루었으며, 본 절에서는 좌표 변환의 나머지 구성 요소인 3D 병진을 체계적으로 다룬다. 병진은 공간 내에서의 위치 이동을 나타내며, 3차원 벡터 \mathbf{t} = (t_x, t_y, t_z)^T로 표현된다. TF2 라이브러리에서 병진은 geometry_msgs::msg::Vector3 타입으로 표현되며, 좌표 변환의 회전 성분과 결합하여 완전한 강체 변환(rigid body transformation)을 구성한다.
2. 병진 벡터의 수학적 정의
2.1 기본 정의
3차원 병진은 공간 내의 한 점을 다른 점으로 이동시키는 선형 이동이다. 수학적으로 점 \mathbf{p} \in \mathbb{R}^3에 병진 벡터 \mathbf{t} \in \mathbb{R}^3를 적용하면:
\mathbf{p}' = \mathbf{p} + \mathbf{t}
여기서 \mathbf{t} = (t_x, t_y, t_z)^T의 각 성분은 좌표축 방향으로의 이동량을 나타낸다:
- t_x: x축 방향 이동 (전방/후방, 단위: 미터)
- t_y: y축 방향 이동 (좌측/우측, 단위: 미터)
- t_z: z축 방향 이동 (상방/하방, 단위: 미터)
ROS2에서는 REP 103 규약에 따라 모든 거리의 단위로 **미터(meter)**를 사용한다.
2.2 병진의 대수적 성질
병진 연산은 다음의 성질을 만족한다:
| 성질 | 수식 | 비고 |
|---|---|---|
| 가환법칙 | \mathbf{t}_1 + \mathbf{t}_2 = \mathbf{t}_2 + \mathbf{t}_1 | 병진의 합성 순서 무관 |
| 결합법칙 | (\mathbf{t}_1 + \mathbf{t}_2) + \mathbf{t}_3 = \mathbf{t}_1 + (\mathbf{t}_2 + \mathbf{t}_3) | 그룹화 무관 |
| 항등원 | \mathbf{p} + \mathbf{0} = \mathbf{p} | 영벡터 |
| 역원 | \mathbf{t} + (-\mathbf{t}) = \mathbf{0} | 부호 반전 |
순수 병진의 합성은 벡터 덧셈이므로 **가환적(commutative)**이다. 이는 회전의 비가환성과 대조적이다. 그러나 회전과 병진이 결합된 강체 변환의 합성에서는 비가환성이 나타난다.
2.3 병진과 회전의 결합
로봇공학에서 좌표 프레임 간의 변환은 일반적으로 회전과 병진이 동시에 포함된다. 프레임 A에서 프레임 B로의 변환에서:
- 회전 R_{AB}: 프레임 B의 자세(orientation)를 프레임 A에서 표현
- 병진 \mathbf{t}_{AB}: 프레임 B의 원점 위치를 프레임 A에서 표현
프레임 B에서 표현된 점 \mathbf{p}_B를 프레임 A에서 표현하면:
\mathbf{p}_A = R_{AB} \mathbf{p}_B + \mathbf{t}_{AB}
이 공식에서 회전이 먼저 적용된 후 병진이 더해지는 점에 주의해야 한다. 순서가 바뀌면 결과가 달라진다.
3. TF2에서의 병진 표현
3.1 TransformStamped 메시지에서의 병진
TF2의 geometry_msgs::msg::TransformStamped 메시지에서 병진은 transform.translation 필드로 표현된다:
geometry_msgs::msg::TransformStamped t;
t.header.stamp = this->get_clock()->now();
t.header.frame_id = "world"; // 부모 프레임
t.child_frame_id = "robot"; // 자식 프레임
// 병진: 자식 프레임의 원점 위치 (부모 프레임 기준)
t.transform.translation.x = 1.0; // 전방 1m
t.transform.translation.y = 0.5; // 좌측 0.5m
t.transform.translation.z = 0.0; // 동일 높이
// 회전: 자식 프레임의 자세 (부모 프레임 기준)
t.transform.rotation.x = 0.0;
t.transform.rotation.y = 0.0;
t.transform.rotation.z = 0.0;
t.transform.rotation.w = 1.0; // 회전 없음
import rclpy
from geometry_msgs.msg import TransformStamped
t = TransformStamped()
t.header.stamp = node.get_clock().now().to_msg()
t.header.frame_id = 'world'
t.child_frame_id = 'robot'
t.transform.translation.x = 1.0
t.transform.translation.y = 0.5
t.transform.translation.z = 0.0
t.transform.rotation.x = 0.0
t.transform.rotation.y = 0.0
t.transform.rotation.z = 0.0
t.transform.rotation.w = 1.0
3.2 병진의 물리적 의미
TransformStamped에서 병진 벡터 (t_x, t_y, t_z)는 부모 프레임(parent frame)의 좌표계에서 표현된 자식 프레임(child frame)의 원점 위치이다. 이 정의를 명확히 이해하는 것이 TF2를 올바르게 사용하기 위한 핵심이다.
예를 들어, 로봇의 기체 프레임(base_link) 위에 카메라가 장착되어 있고, 카메라의 위치가 로봇 전방 0.3m, 좌측 0.05m, 상방 0.2m인 경우:
t.header.frame_id = "base_link";
t.child_frame_id = "camera";
t.transform.translation.x = 0.3; // 전방 0.3m
t.transform.translation.y = 0.05; // 좌측 0.05m
t.transform.translation.z = 0.2; // 상방 0.2m
3.3 Vector3 메시지 타입
병진은 geometry_msgs::msg::Vector3 타입으로 표현된다:
# geometry_msgs/msg/Vector3
float64 x
float64 y
float64 z
이 메시지 타입은 64비트 배정밀도(double) 부동소수점을 사용하며, 밀리미터 이하의 정밀도를 제공한다. 각 축에 대해 약 \pm 9 \times 10^{15} 미터 범위를 표현할 수 있으므로, 지구 규모의 좌표 표현에도 충분하다.
4. 병진 벡터의 좌표계 종속성
4.1 프레임에 따른 병진의 해석
동일한 물리적 이동이라도 어떤 좌표계에서 표현하느냐에 따라 병진 벡터의 성분이 달라진다. 프레임 A에서의 병진 벡터 \mathbf{t}_A를 프레임 B에서 표현하려면, 두 프레임 간의 회전 R_{BA}를 적용해야 한다:
\mathbf{t}_B = R_{BA} \mathbf{t}_A
이 변환은 병진 벡터의 방향만 변경하고 크기는 보존한다. 회전 행렬이 등거리 변환이기 때문이다.
4.2 전역 좌표계와 로컬 좌표계
로봇 시스템에서 병진은 주로 두 가지 기준 프레임에서 해석된다:
| 기준 | 의미 | 사용 예 |
|---|---|---|
| 전역 좌표계 (map, world) | 고정된 환경 기준 위치 | 로봇의 절대 위치 |
| 로컬 좌표계 (base_link) | 로봇 기체 기준 상대 위치 | 센서 장착 위치, 장애물 상대 위치 |
// TF2를 이용한 프레임 간 병진 변환 예시
geometry_msgs::msg::PointStamped point_in_camera;
point_in_camera.header.frame_id = "camera";
point_in_camera.point.x = 2.0; // 카메라 전방 2m
point_in_camera.point.y = 0.5; // 카메라 좌측 0.5m
point_in_camera.point.z = 0.0;
// 카메라 프레임 → 로봇 base_link 프레임으로 변환
geometry_msgs::msg::PointStamped point_in_base;
tf_buffer.transform(point_in_camera, point_in_base, "base_link");
5. 병진의 합성과 역변환
5.1 순수 병진의 합성
두 연속 병진 \mathbf{t}_1과 \mathbf{t}_2의 합성은 벡터 덧셈이다:
\mathbf{t}_{\text{total}} = \mathbf{t}_1 + \mathbf{t}_2
이 합성은 순서에 무관하다(\mathbf{t}_1 + \mathbf{t}_2 = \mathbf{t}_2 + \mathbf{t}_1).
5.2 회전을 포함한 변환의 합성에서의 병진
프레임 A → B 변환 (R_{AB}, \mathbf{t}_{AB})와 프레임 B → C 변환 (R_{BC}, \mathbf{t}_{BC})를 합성하면:
R_{AC} = R_{AB} R_{BC}
\mathbf{t}_{AC} = R_{AB} \mathbf{t}_{BC} + \mathbf{t}_{AB}
병진 벡터의 합성에서 \mathbf{t}_{BC}에 R_{AB}가 곱해지는 이유는, B 프레임에서 표현된 병진을 A 프레임으로 변환해야 하기 때문이다. 이 점이 순수 병진의 단순 벡터 덧셈과 다른 핵심적 차이이다.
5.3 역변환에서의 병진
변환 (R, \mathbf{t})의 역변환은:
R_{\text{inv}} = R^T
\mathbf{t}_{\text{inv}} = -R^T \mathbf{t}
역변환의 병진 벡터가 단순히 -\mathbf{t}가 아니라 -R^T \mathbf{t}인 이유는 역회전도 함께 적용되기 때문이다.
// 역변환 병진 계산 예시
tf2::Transform transform;
transform.setOrigin(tf2::Vector3(1.0, 0.5, 0.0));
tf2::Quaternion q;
q.setRPY(0, 0, M_PI/4);
transform.setRotation(q);
tf2::Transform inverse = transform.inverse();
// inverse.getOrigin()은 -R^T * t에 해당
6. 병진 관련 메시지 타입
6.1 geometry_msgs의 위치 관련 메시지
ROS2에서 위치와 병진을 표현하는 메시지 타입은 다음과 같다:
| 메시지 타입 | 설명 | 주요 필드 |
|---|---|---|
Vector3 | 3D 벡터 (방향+크기) | x, y, z (float64) |
Point | 3D 좌표점 | x, y, z (float64) |
Point32 | 3D 좌표점 (단정밀도) | x, y, z (float32) |
Pose | 위치 + 자세 | position (Point) + orientation (Quaternion) |
PoseStamped | 타임스탬프 + 프레임 포함 Pose | header + pose |
Transform | 변환 (병진 + 회전) | translation (Vector3) + rotation (Quaternion) |
6.2 Vector3와 Point의 차이
Vector3와 Point는 동일한 구조(x, y, z float64)를 가지지만, 의미론적으로 다르다:
Vector3: 방향과 크기를 가지는 벡터. 좌표 변환 시 회전만 적용된다 (병진 불적용). 예: 속도, 가속도, 힘.Point: 공간 내의 위치를 나타내는 점. 좌표 변환 시 회전과 병진 모두 적용된다. 예: 좌표, 위치.
이 차이는 tf2::doTransform()에서 변환 동작의 차이로 나타난다:
// Point 변환: 회전 + 병진 적용
// p' = R * p + t
geometry_msgs::msg::PointStamped point;
tf2::doTransform(point_in, point_out, transform);
// Vector3 변환: 회전만 적용
// v' = R * v
geometry_msgs::msg::Vector3Stamped vector;
tf2::doTransform(vector_in, vector_out, transform);
7. 병진의 보간
7.1 선형 보간 (LERP)
두 시점 t_0과 t_1에서의 병진 벡터 \mathbf{t}_0와 \mathbf{t}_1 사이의 보간은 선형 보간(LERP)으로 수행한다:
\mathbf{t}(\alpha) = (1 - \alpha)\mathbf{t}_0 + \alpha\mathbf{t}_1, \quad \alpha \in [0, 1]
여기서 \alpha = (t - t_0)/(t_1 - t_0)이다. 병진의 보간은 단순 선형 보간이 적절하며, 회전의 보간(SLERP)과 달리 특별한 고려가 필요하지 않다. TF2의 BufferCore는 병진 성분에 대해 LERP를, 회전 성분에 대해 SLERP를 자동으로 적용한다.
7.2 높은 주파수 변환에서의 정밀도
고속으로 이동하는 로봇에서 두 시점 사이의 병진 보간은 직선 경로를 가정한다. 실제 경로가 곡선인 경우(예: 원호 운동), 보간 오차는 다음에 비례한다:
\epsilon \propto \frac{v^2 \Delta t^2}{r}
여기서 v는 속도, \Delta t는 시간 간격, r은 경로의 곡률 반경이다. 변환 발행 주파수를 높이면(\Delta t 감소) 보간 오차를 줄일 수 있다.
8. 단위와 규약
8.1 ROS2의 단위 규약 (REP 103)
ROS2에서 병진과 관련된 단위 규약:
| 물리량 | 단위 | 비고 |
|---|---|---|
| 거리/변위 | 미터 (m) | SI 기본 단위 |
| 선속도 | 미터/초 (m/s) | Twist.linear |
| 선가속도 | 미터/초² (m/s²) | Accel.linear |
| 힘 | 뉴턴 (N) | Wrench.force |
8.2 좌표축 방향 규약 (REP 103)
| 축 | 방향 | 관례 |
|---|---|---|
| x | 전방 (Forward) | 양의 방향 = 전방 |
| y | 좌측 (Left) | 양의 방향 = 좌측 |
| z | 상방 (Up) | 양의 방향 = 상방 |
이 규약은 ENU(East-North-Up) 좌표계의 변형으로, 로봇의 진행 방향을 x축으로 설정한 것이다. 항공우주 공학에서 사용하는 NED(North-East-Down) 좌표계와는 y축과 z축의 방향이 다르므로 주의해야 한다.
9. 요약
3D 병진은 3차원 벡터 \mathbf{t} = (t_x, t_y, t_z)^T로 표현되며, 좌표 변환에서 회전 성분과 함께 완전한 강체 변환을 구성한다. TF2에서 병진은 TransformStamped 메시지의 transform.translation 필드로 표현되며, 부모 프레임에서 본 자식 프레임의 원점 위치를 의미한다. 순수 병진의 합성은 가환적이지만, 회전과 결합된 변환의 합성에서는 병진 벡터에 회전이 적용되므로 비가환적이 된다. 병진의 보간은 선형 보간(LERP)으로 수행되며, Vector3와 Point의 의미론적 차이에 따라 좌표 변환 시 병진 적용 여부가 결정된다.
10. 참고 문헌
- 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.
- Murray, R. M., Li, Z., & Sastry, S. S. (1994). A Mathematical Introduction to Robotic Manipulation. CRC Press.
- REP 103 — Standard Units of Measure and Coordinate Conventions. https://www.ros.org/reps/rep-0103.html
- Open Robotics. “tf2 — ROS 2 Documentation.” https://docs.ros.org/en/rolling/Concepts/Intermediate/About-Tf2.html