659.16 TransformStamped의 헤더 (Header) 필드
1. 개요
geometry_msgs/msg/TransformStamped 메시지의 header 필드는 std_msgs/msg/Header 타입으로, 좌표 변환 정보의 시간적 맥락과 기준 프레임을 정의하는 메타데이터를 포함한다. Header 필드는 TF2 시스템이 시간 기반의 변환 관리를 수행하는 데 필수적인 정보를 제공하며, 변환의 시간적 유효성 판단, 변환 트리 내에서의 프레임 관계 설정, 그리고 시간 동기화된 변환 조회의 기반이 된다.
2. Header 메시지의 정의
ROS2의 std_msgs/msg/Header 메시지는 다음과 같이 정의된다.
# std_msgs/msg/Header
builtin_interfaces/Time stamp
string frame_id
Header 메시지는 두 개의 필드로 구성된다. stamp 필드는 시간 정보를 포함하고, frame_id 필드는 프레임 식별자를 포함한다. 이 두 필드의 조합을 통해 TransformStamped 메시지의 시공간적(spatiotemporal) 맥락이 완전히 기술된다.
3. stamp 필드
3.1 시간 표현 구조
stamp 필드는 builtin_interfaces/msg/Time 타입으로 정의되며, 다음과 같은 하위 필드를 갖는다.
# builtin_interfaces/msg/Time
int32 sec
uint32 nanosec
- sec: 유닉스 에포크(Unix epoch, 1970년 1월 1일 00:00:00 UTC)로부터의 경과 시간을 초(second) 단위로 표현하는 부호 있는 32비트 정수이다. 부호 있는 정수를 사용함으로써 에포크 이전의 시간도 표현할 수 있으나, 일반적인 로봇 시스템 운용에서는 양수 값만 사용된다.
- nanosec: 초 이하의 시간을 나노초(nanosecond) 단위로 표현하는 부호 없는 32비트 정수이다. 유효 범위는 0 \leq \text{nanosec} < 10^{9}이며, 이를 통해 나노초 수준의 시간 분해능(temporal resolution)을 제공한다.
따라서 전체 시간 T는 다음과 같이 계산된다.
T = \text{sec} + \text{nanosec} \times 10^{-9} \quad [\text{초}]
3.2 TF2에서의 시간 스탬프 역할
TF2 시스템에서 stamp 필드는 다음과 같은 핵심적 기능을 수행한다.
3.2.1 시간 기반 변환 저장
TF2의 Buffer는 수신된 TransformStamped 메시지를 stamp 값에 따라 시간순으로 정렬하여 저장한다. 각 프레임 쌍(parent-child pair)에 대해 시계열(time series) 형태의 변환 이력이 유지되며, 이 이력의 보관 기간은 Buffer의 캐시 기간(cache duration) 설정에 의해 결정된다. 기본 캐시 기간은 통상적으로 10초이다.
3.2.2 변환 조회의 시간 인덱싱
lookupTransform() 함수를 통해 특정 시점의 변환을 조회할 때, stamp 값이 조회 키(query key)로 사용된다. TF2 버퍼는 요청된 시간에 정확히 일치하는 변환이 존재하지 않을 경우, 해당 시간 전후의 변환 데이터를 기반으로 보간(interpolation)을 수행하여 추정 변환을 생성한다.
3.2.3 보간 및 외삽 기준
시간 스탬프를 기반으로 두 가지 핵심 연산이 수행된다.
- 보간(interpolation): 요청 시간이 두 개의 저장된 변환 시간 사이에 존재할 때, 병진(translation) 성분에 대해서는 선형 보간(LERP)을, 회전(rotation) 성분에 대해서는 구면 선형 보간(SLERP)을 적용하여 중간 변환을 생성한다.
- 외삽(extrapolation): 요청 시간이 저장된 변환 시간의 범위를 벗어날 때, 허용 오차(tolerance) 이내인 경우에만 가장 가까운 변환을 반환한다. 허용 오차를 초과하면
ExtrapolationException이 발생한다.
3.3 시간 스탬프 설정 방법
3.3.1 현재 시간 사용
가장 일반적인 방법은 노드의 현재 시계에서 시간을 가져오는 것이다.
C++ (rclcpp):
geometry_msgs::msg::TransformStamped t;
t.header.stamp = this->get_clock()->now();
Python (rclpy):
t = TransformStamped()
t.header.stamp = self.get_clock().now().to_msg()
get_clock()->now() 또는 get_clock().now()는 노드의 시계 설정에 따라 시스템 시간(system time)이나 시뮬레이션 시간(ROS time)을 반환한다. use_sim_time 파라미터가 true로 설정된 경우, /clock 토픽에서 수신되는 시뮬레이션 시간이 사용된다.
3.3.2 Time(0) 또는 tf2::TimePointZero 사용
변환 조회 시 시간 스탬프를 0으로 설정하면, TF2 버퍼에 저장된 가장 최근의 가용 변환이 반환된다. 이는 변환 발행 시에는 사용하지 않으며, 오직 lookupTransform() 호출 시에만 적용되는 특수한 시간값이다.
// 최신 가용 변환 조회
auto transform = buffer->lookupTransform(
"target_frame", "source_frame", tf2::TimePointZero);
3.4 시간 스탬프 관련 주의 사항
3.4.1 시간 동기화
분산 시스템에서 여러 노드가 변환을 발행하는 경우, 노드 간의 시계 동기화가 중요하다. NTP(Network Time Protocol)나 PTP(Precision Time Protocol)를 통한 시간 동기화가 이루어지지 않으면, 서로 다른 노드에서 발행된 변환의 시간 스탬프가 일관성을 잃게 되어 변환 조회 시 부정확한 결과가 발생할 수 있다.
3.4.2 미래 시간 스탬프
센서 드라이버나 외부 시스템에서 발행된 변환의 시간 스탬프가 현재 시스템 시간보다 미래에 해당하는 경우가 발생할 수 있다. 이 경우 lookupTransform() 호출 시 해당 시간에 대한 변환이 아직 도착하지 않은 것으로 간주되어 ExtrapolationException이 발생한다. 이를 방지하기 위해 waitForTransform() 함수를 사용하여 변환이 가용해질 때까지 대기하는 전략을 적용할 수 있다.
3.4.3 정적 변환에서의 시간 스탬프
정적 변환(static transform)의 경우, 시간 스탬프는 변환이 발행된 시점을 기록하지만, TF2는 정적 변환을 모든 시간에서 유효한 것으로 취급한다. 즉, 정적 변환의 시간 스탬프는 변환 조회 시 무시되며, 어떤 시간으로 조회하더라도 해당 정적 변환이 반환된다.
4. frame_id 필드
4.1 프레임 식별자의 정의
frame_id 필드는 변환의 부모 프레임(parent frame)을 식별하는 문자열이다. TransformStamped 메시지에서 header.frame_id는 변환 관계의 출발점, 즉 변환 트리에서 상위에 위치하는 프레임을 지정한다.
4.2 변환 트리에서의 역할
TF2의 변환 트리는 방향 비순환 그래프(Directed Acyclic Graph, DAG)의 특수한 형태인 트리 구조로 구성된다. header.frame_id는 트리의 간선(edge)에서 부모 노드에 해당하며, child_frame_id와 함께 간선의 방향을 결정한다. 변환 트리에 새로운 간선을 추가할 때, TF2는 header.frame_id를 부모로, child_frame_id를 자식으로 하는 부모-자식 관계를 설정한다.
4.3 프레임 이름 규약
ROS2에서 프레임 이름은 다음과 같은 규약을 따른다.
| 규약 | 설명 | 예시 |
|---|---|---|
| 슬래시 미사용 | ROS2에서는 프레임 이름에 선행 슬래시(/)를 사용하지 않는다 | base_link (O), /base_link (X) |
| 소문자 및 밑줄 | 프레임 이름은 소문자와 밑줄(_)의 조합으로 구성한다 | camera_link, imu_frame |
| 네임스페이스 접두사 | 다중 로봇 시스템에서 네임스페이스로 프레임을 구분한다 | robot1/base_link |
| 의미론적 명명 | 프레임의 물리적 위치나 기능을 반영하는 이름을 부여한다 | left_wheel_link, gripper_frame |
4.4 표준 프레임 이름
REP 105에서 정의한 이동 플랫폼의 표준 프레임 이름은 다음과 같다.
- earth: 지구 고정 프레임으로, 다중 로봇 시스템에서 전역 참조 프레임으로 사용된다.
- map: SLAM 또는 사전 구축된 지도를 기반으로 하는 전역 프레임이다. 장기적으로 정확하나 불연속적(discrete) 보정이 발생할 수 있다.
- odom: 주행 거리 측정(odometry)에 기반한 프레임이다. 단기적으로 정확하고 연속적이나, 시간이 경과함에 따라 누적 오차(drift)가 증가한다.
- base_link: 로봇 본체에 고정된 프레임으로, 로봇의 기하학적 중심 또는 회전 중심에 위치한다.
4.5 frame_id 설정 시 주의 사항
4.5.1 일관성 유지
동일한 변환 관계를 발행하는 경우, frame_id는 항상 동일한 문자열을 사용하여야 한다. 대소문자나 공백의 차이로 인해 TF2가 서로 다른 프레임으로 인식하는 오류가 발생할 수 있다.
4.5.2 빈 문자열 방지
frame_id가 빈 문자열("")인 경우, TF2는 해당 변환을 처리할 수 없으며, InvalidArgumentException이 발생한다. 따라서 TransformStamped 메시지를 생성할 때 반드시 유효한 프레임 이름을 지정하여야 한다.
4.5.3 자기 참조 방지
header.frame_id와 child_frame_id가 동일한 프레임을 참조하는 경우, TF2는 자기 자신으로의 변환(self-referencing transform)으로 판단하여 이를 거부한다. 이러한 설정은 변환 트리에서 길이 0의 간선을 생성하는 것에 해당하며, 의미론적으로 유효하지 않다.
5. Header 필드의 직렬화
Header 메시지의 직렬화 시, CDR(Common Data Representation) 인코딩 규칙에 따라 다음과 같은 바이트 배치가 이루어진다.
- stamp.sec (4바이트, int32): 4바이트 정렬
- stamp.nanosec (4바이트, uint32): 4바이트 정렬
- frame_id (가변 길이): 4바이트 길이 접두사 + UTF-8 인코딩 문자열 + 널 종료 문자
frame_id는 가변 길이 문자열이므로, 직렬화된 메시지의 전체 크기는 frame_id와 child_frame_id의 길이에 따라 달라진다. 따라서 짧고 명확한 프레임 이름을 사용하는 것이 네트워크 대역폭 효율성 측면에서 유리하다.
6. Header 필드와 다른 ROS2 메시지의 비교
std_msgs/msg/Header는 TransformStamped뿐만 아니라 sensor_msgs/msg/LaserScan, sensor_msgs/msg/Image, geometry_msgs/msg/PoseStamped 등 ROS2의 대부분의 스탬프된(stamped) 메시지에서 공통으로 사용되는 표준 헤더이다. 이러한 설계 패턴을 통해 모든 스탬프된 메시지가 동일한 시간적·공간적 메타데이터 구조를 공유하며, TF2를 비롯한 ROS2의 다양한 라이브러리가 일관된 방식으로 메시지의 시공간적 맥락을 처리할 수 있다.
TransformStamped에서의 header.frame_id의 의미는 다른 메시지 타입에서와 차이가 있다. 일반적인 센서 메시지에서 header.frame_id는 해당 데이터가 측정된 좌표 프레임을 의미하지만, TransformStamped에서는 변환 관계의 부모 프레임을 의미한다. 이 구분은 TF2 시스템을 올바르게 활용하기 위해 반드시 이해하여야 하는 핵심 사항이다.
7. 참고 문헌
- ROS2 공식 문서, “std_msgs/msg/Header,” https://docs.ros.org/en/humble/p/std_msgs/
- ROS2 공식 문서, “geometry_msgs/msg/TransformStamped,” 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
- ROS Enhancement Proposal (REP) 105, “Coordinate Frames for Mobile Platforms,” https://www.ros.org/reps/rep-0105.html
- Foote, T., “tf: The transform library,” 2013 IEEE Conference on Technologies for Practical Robot Applications (TePRA), 2013.
- ROS2 Humble Hawksbill 기준 (2022)