659.20 /tf 토픽의 동작 원리
1. 개요
/tf 토픽은 ROS2 TF2 시스템에서 동적 변환(dynamic transform)을 전파하기 위한 핵심 통신 채널이다. 이 토픽을 통해 시간에 따라 변화하는 좌표 프레임 간의 변환 정보가 시스템 전체에 배포되며, TransformBroadcaster가 발행하고 TransformListener가 수신하는 발행-구독(publish-subscribe) 모델을 따른다. /tf 토픽의 정확한 동작 원리를 이해하는 것은 TF2 기반 로봇 소프트웨어의 설계와 디버깅에 필수적이다.
2. 토픽 기본 정보
/tf 토픽의 기본 속성은 다음과 같다.
| 속성 | 값 |
|---|---|
| 토픽 이름 | /tf |
| 메시지 타입 | tf2_msgs/msg/TFMessage |
| 목적 | 동적 좌표 변환 전파 |
| 발행 주기 | 변환 소스에 따라 다양 (일반적으로 10–100 Hz) |
| 발행자 | TransformBroadcaster 또는 직접 발행 노드 |
| 구독자 | TransformListener |
3. 발행 메커니즘
3.1 TransformBroadcaster를 통한 발행
/tf 토픽에의 변환 발행은 대부분 tf2_ros::TransformBroadcaster를 통해 이루어진다. TransformBroadcaster는 내부적으로 /tf 토픽에 대한 발행자(publisher)를 생성하고, sendTransform() 메서드가 호출될 때마다 tf2_msgs/msg/TFMessage 메시지를 구성하여 발행한다.
// TransformBroadcaster 내부 동작 (개념적)
class TransformBroadcaster {
rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr publisher_;
public:
TransformBroadcaster(rclcpp::Node::SharedPtr node) {
publisher_ = node->create_publisher<tf2_msgs::msg::TFMessage>(
"/tf", rclcpp::QoS(100));
}
void sendTransform(const geometry_msgs::msg::TransformStamped& transform) {
tf2_msgs::msg::TFMessage message;
message.transforms.push_back(transform);
publisher_->publish(message);
}
};
3.2 다중 발행자 모델
ROS2의 DDS 기반 통신 모델에서, /tf 토픽에는 동시에 다수의 발행자가 존재할 수 있다. 각 발행자는 자신이 관리하는 프레임 관계에 대한 변환만을 발행하며, 모든 발행자의 메시지가 /tf를 구독하는 모든 TransformListener에게 전달된다.
전형적인 로봇 시스템에서 /tf에 변환을 발행하는 노드의 예는 다음과 같다.
| 발행 노드 | 발행 변환 | 발행 주파수 |
|---|---|---|
| 주행 거리 측정(odometry) 노드 | odom → base_link | 50–100 Hz |
| 위치 추정(localization) 노드 | map → odom | 10–30 Hz |
| robot_state_publisher | base_link → 각 링크 | 관절 상태 갱신 시 |
| 센서 장착 위치 보정 노드 | 동적 센서 정렬 | 변경 시 |
3.3 발행 주기와 변환 유효성
/tf 토픽을 통해 발행되는 동적 변환은 주기적으로 갱신되어야 한다. 변환의 발행이 중단되면, TF2 버퍼에 저장된 해당 변환은 시간이 경과함에 따라 만료(stale)되며, 현재 시간으로의 변환 조회 시 ExtrapolationException이 발생한다.
적절한 발행 주기는 변환이 변화하는 속도에 따라 결정된다. 빠르게 움직이는 로봇의 주행 거리 변환은 높은 주파수(50–100 Hz)로 발행하여야 하고, 비교적 느리게 갱신되는 위치 추정 변환은 낮은 주파수(10–30 Hz)로도 충분하다.
4. QoS 정책
4.1 기본 QoS 설정
/tf 토픽의 QoS(Quality of Service) 정책은 동적 변환의 특성에 맞게 설정된다.
| QoS 정책 | 설정 값 | 설명 |
|---|---|---|
| Reliability | RELIABLE | 메시지 전달 보장 |
| Durability | VOLATILE | 과거 메시지 보관하지 않음 |
| History | KEEP_LAST | 최근 메시지만 유지 |
| Depth | 100 | 큐 크기 100 |
4.2 VOLATILE 내구성의 의미
VOLATILE 내구성(durability) 설정은 /tf 토픽의 핵심적인 동작 특성을 결정한다. 이 설정에 의해:
- 구독자가 토픽에 연결되기 이전에 발행된 메시지는 수신되지 않는다.
- 구독자 연결 이후에 발행되는 메시지만 수신된다.
- DDS 미들웨어는 과거 메시지를 캐시하지 않는다.
동적 변환은 주기적으로 갱신되므로, 과거 메시지를 수신하지 못하더라도 다음 발행 주기에서 최신 변환을 수신할 수 있다. 따라서 VOLATILE 설정이 적합하다.
4.3 KEEP_LAST 히스토리의 역할
KEEP_LAST 히스토리 정책과 depth 100의 설정은, 수신 측의 콜백 처리 지연 시에도 최근 100개의 메시지를 큐에 보관하여 데이터 손실을 최소화한다. 그러나 큐가 가득 찬 상태에서 새로운 메시지가 도착하면 가장 오래된 메시지가 폐기된다.
5. 수신 메커니즘
5.1 TransformListener의 구독 동작
TransformListener는 초기화 시 /tf 토픽에 대한 구독자를 생성하고, 수신 콜백 함수를 등록한다. 메시지가 수신될 때마다 콜백이 실행되어 TFMessage 내의 각 TransformStamped를 tf2::Buffer에 저장한다.
TransformListener 초기화:
1. /tf 구독자 생성 (QoS: RELIABLE, VOLATILE, KEEP_LAST(100))
2. /tf_static 구독자 생성 (QoS: RELIABLE, TRANSIENT_LOCAL)
3. 각 구독자에 수신 콜백 등록
/tf 수신 콜백(TFMessage msg):
for each transform in msg.transforms:
buffer.setTransform(transform, authority="default_authority", is_static=false)
5.2 Buffer에의 변환 등록
Buffer::setTransform() 호출 시 다음과 같은 검증이 수행된다.
- 프레임 ID 유효성 검사:
header.frame_id와child_frame_id가 빈 문자열이 아닌지 확인한다. - 자기 참조 검사: 두 프레임 식별자가 동일하지 않은지 확인한다.
- 쿼터니언 유효성:
rotation쿼터니언의 노름이 유효 범위 내에 있는지 검증한다. - 시간 스탬프 확인: 시간 스탬프가 유효한 값인지 확인한다.
모든 검증을 통과한 변환은 프레임 쌍(header.frame_id, child_frame_id)을 키로 하는 시계열 저장소에 삽입된다.
6. 데이터 흐름
/tf 토픽을 통한 변환 데이터의 전체 흐름은 다음과 같다.
[변환 소스 노드]
↓ (TransformBroadcaster.sendTransform())
[tf2_msgs/msg/TFMessage 생성]
↓ (DDS publish)
[/tf 토픽]
↓ (DDS subscribe, 모든 구독자에 분배)
[TransformListener 수신 콜백]
↓ (Buffer.setTransform())
[tf2::Buffer 내부 저장소]
↓ (lookupTransform() 호출 시)
[TransformStamped 반환]
이 데이터 흐름에서 DDS 미들웨어는 발행자와 구독자 간의 네트워크 통신을 투명하게 처리한다. 동일 프로세스 내에서는 공유 메모리(intra-process communication)를 통해 메시지 복사 없이 데이터가 전달될 수 있다.
7. 네트워크 부하 분석
7.1 메시지 크기
단일 TransformStamped의 직렬화 크기는 고정 필드 부분이 약 64바이트이며, 여기에 frame_id와 child_frame_id 문자열의 길이가 추가된다. 일반적인 프레임 이름(예: base_link, odom)을 사용하는 경우, 단일 TransformStamped의 총 크기는 약 100–120바이트이다.
7.2 대역폭 소비
/tf 토픽의 네트워크 대역폭 소비량은 발행 주파수와 변환의 수에 따라 결정된다. 대략적인 추정은 다음과 같다.
\text{대역폭} \approx \sum_{i} (S_i \times f_i)
여기서 S_i는 i번째 TFMessage의 직렬화 크기, f_i는 해당 메시지의 발행 주파수이다.
예를 들어, 10개의 변환을 50 Hz로 발행하는 시스템에서의 대략적인 대역폭은 다음과 같다.
10 \times 120 \text{ bytes} \times 50 \text{ Hz} = 60{,}000 \text{ bytes/s} \approx 60 \text{ KB/s}
이는 현대 네트워크 환경에서 매우 작은 부하에 해당하지만, 다수의 로봇이 동일 네트워크를 공유하는 환경에서는 누적 대역폭을 고려하여야 한다.
8. 토픽 검사 (Introspection)
8.1 토픽 정보 확인
# /tf 토픽 정보 확인
ros2 topic info /tf
# /tf 토픽의 메시지 실시간 확인
ros2 topic echo /tf
# /tf 토픽의 발행 주파수 확인
ros2 topic hz /tf
# /tf 토픽의 대역폭 확인
ros2 topic bw /tf
8.2 발행자 및 구독자 확인
# /tf 토픽의 발행자 목록
ros2 topic info /tf --verbose
이 명령을 통해 /tf 토픽에 연결된 모든 발행자와 구독자의 노드 이름, QoS 설정 등을 확인할 수 있다.
9. /tf 토픽의 동작 특성 요약
| 특성 | 설명 |
|---|---|
| 발행 방식 | 주기적 발행 (센서 갱신 또는 타이머 기반) |
| 수신 방식 | 콜백 기반 수신 후 Buffer 저장 |
| 과거 메시지 | 수신 불가 (VOLATILE) |
| 지연 합류 | 다음 발행 주기까지 대기 필요 |
| 다중 발행자 | 지원 (DDS 발행-구독 모델) |
| 변환 갱신 | 발행이 중단되면 변환 만료 |
| 캐시 관리 | Buffer의 캐시 기간 설정에 따름 |
10. 참고 문헌
- ROS2 공식 문서, “tf2_ros API,” https://docs.ros.org/en/humble/p/tf2_ros/
- ROS2 공식 문서, “About Quality of Service Settings,” https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html
- Foote, T., “tf: The transform library,” 2013 IEEE Conference on Technologies for Practical Robot Applications (TePRA), 2013.
- OMG, “Data Distribution Service (DDS) Specification,” Version 1.4, Object Management Group, 2015.
- ROS2 Humble Hawksbill 기준 (2022)