659.22 /tf와 /tf_static의 QoS 정책 차이
1. 개요
ROS2 TF2 시스템에서 좌표 변환 데이터는 /tf와 /tf_static이라는 두 개의 표준 토픽을 통해 전파된다. 두 토픽은 동일한 메시지 타입(tf2_msgs/msg/TFMessage)을 사용하지만, QoS(Quality of Service) 정책이 근본적으로 상이하다. 이 차이는 동적 변환과 정적 변환이 지닌 본질적으로 다른 통신 요구 사항을 반영한 설계 결정이다. QoS 정책의 차이를 정확히 이해하는 것은 TF2 시스템의 동작을 예측하고, 사용자 정의 토픽 구성 시 발생할 수 있는 호환성 문제를 방지하기 위해 필수적이다.
2. ROS2 QoS 정책 기초
ROS2의 QoS 정책은 DDS(Data Distribution Service) 미들웨어에서 제공하는 통신 품질 제어 메커니즘이다. 토픽 통신에 적용되는 주요 QoS 정책은 다음과 같다.
| QoS 정책 | 설명 | 선택지 |
|---|---|---|
| Reliability | 메시지 전달 보장 수준 | RELIABLE, BEST_EFFORT |
| Durability | 구독 이전 메시지의 보존 여부 | VOLATILE, TRANSIENT_LOCAL |
| History | 메시지 이력 보관 방식 | KEEP_LAST(N), KEEP_ALL |
| Liveliness | 발행자 생존 확인 방식 | AUTOMATIC, MANUAL_BY_TOPIC |
| Deadline | 메시지 도착 기한 | 시간 값 |
| Lifespan | 메시지 유효 기간 | 시간 값 |
TF2는 이 중에서 Reliability, Durability, History 정책을 핵심적으로 활용한다.
3. /tf 토픽의 QoS 정책
3.1 상세 설정
// /tf 토픽의 QoS 설정 (개념적)
rclcpp::QoS tf_qos(100); // KEEP_LAST, depth=100
tf_qos.reliable(); // RELIABLE
// durability는 기본값 VOLATILE
| QoS 정책 | /tf 설정 값 | 근거 |
|---|---|---|
| Reliability | RELIABLE | 변환 데이터의 누락 방지 |
| Durability | VOLATILE | 주기적 갱신으로 과거 데이터 불필요 |
| History | KEEP_LAST | 최근 메시지만 유지 |
| Depth | 100 | 처리 지연 시 버퍼링 여유 확보 |
3.2 VOLATILE 선택의 근거
동적 변환은 주기적으로 발행되므로, 구독자가 이전에 발행된 메시지를 수신하지 못하더라도 다음 발행 주기에서 최신 변환을 수신할 수 있다. 따라서 DDS가 과거 메시지를 캐시할 필요가 없으며, VOLATILE 내구성이 적합하다.
이 설정의 동작 특성은 다음과 같다.
- 구독자가 연결된 이후에 발행되는 메시지만 수신된다.
- 구독자 연결 이전의 메시지는 영구적으로 수신 불가이다.
- DDS 미들웨어의 메모리 및 저장 공간 부하가 최소화된다.
3.3 KEEP_LAST(100)의 동작
KEEP_LAST 히스토리 정책과 depth 100의 설정은 수신 측의 메시지 큐 크기를 결정한다. 수신 콜백의 처리가 발행 속도를 따라가지 못하는 경우, 최대 100개의 메시지가 큐에 보관된다. 큐가 가득 차면 가장 오래된 메시지부터 폐기된다.
4. /tf_static 토픽의 QoS 정책
4.1 상세 설정
// /tf_static 토픽의 QoS 설정 (개념적)
rclcpp::QoS tf_static_qos(rclcpp::KeepAll());
tf_static_qos.reliable(); // RELIABLE
tf_static_qos.transient_local(); // TRANSIENT_LOCAL
| QoS 정책 | /tf_static 설정 값 | 근거 |
|---|---|---|
| Reliability | RELIABLE | 일회성 발행이므로 누락 불허 |
| Durability | TRANSIENT_LOCAL | 지연 합류 구독자의 수신 보장 |
| History | KEEP_ALL | 모든 정적 변환 보존 |
4.2 TRANSIENT_LOCAL 선택의 근거
정적 변환은 한 번만 발행되며 재발행되지 않는다. 따라서 나중에 시스템에 참여하는 구독자(late-joiner)가 이미 발행된 정적 변환을 수신할 수 있는 메커니즘이 필수적이다. TRANSIENT_LOCAL 내구성은 발행자 측의 DDS 캐시에 메시지를 보관하여, 새로 연결된 구독자에게 자동으로 캐시된 메시지를 전달한다.
이 설정의 동작 특성은 다음과 같다.
- 구독자 연결 이전에 발행된 메시지도 DDS 캐시를 통해 수신 가능하다.
- 발행자 노드가 활성 상태인 한, 캐시가 유지된다.
- 발행자 노드가 종료되면 캐시도 소멸된다.
4.3 KEEP_ALL의 동작
KEEP_ALL 히스토리 정책은 수신된 모든 정적 변환 메시지를 보관한다. 정적 변환은 발행 빈도가 매우 낮으므로(일반적으로 시스템 시작 시 1회), 메시지 수가 제한적이어서 메모리 부담이 미미하다.
5. QoS 정책 비교 요약
| QoS 정책 | /tf | /tf_static |
|---|---|---|
| Reliability | RELIABLE | RELIABLE |
| Durability | VOLATILE | TRANSIENT_LOCAL |
| History | KEEP_LAST | KEEP_ALL |
| Depth | 100 | N/A (KEEP_ALL) |
핵심적인 차이는 Durability와 History 정책에 있다.
6. QoS 호환성 규칙
6.1 DDS QoS 호환성 원칙
ROS2에서 발행자와 구독자 간의 통신이 성립하려면, QoS 정책이 호환(compatible)되어야 한다. 호환되지 않는 QoS 설정은 연결 거부(connection rejection)를 초래한다.
6.1.1 Reliability 호환성
| 발행자 | 구독자 | 호환 여부 |
|---|---|---|
| RELIABLE | RELIABLE | ✓ |
| RELIABLE | BEST_EFFORT | ✓ |
| BEST_EFFORT | RELIABLE | ✗ |
| BEST_EFFORT | BEST_EFFORT | ✓ |
규칙: 발행자의 Reliability ≥ 구독자의 Reliability
6.1.2 Durability 호환성
| 발행자 | 구독자 | 호환 여부 |
|---|---|---|
| TRANSIENT_LOCAL | TRANSIENT_LOCAL | ✓ |
| TRANSIENT_LOCAL | VOLATILE | ✓ |
| VOLATILE | TRANSIENT_LOCAL | ✗ |
| VOLATILE | VOLATILE | ✓ |
규칙: 발행자의 Durability ≥ 구독자의 Durability
6.2 TF2에서의 호환성 주의 사항
TransformListener는 두 토픽 각각에 적합한 QoS로 구독자를 생성하므로 호환성 문제가 발생하지 않는다. 그러나 사용자가 직접 /tf 또는 /tf_static 토픽의 발행자나 구독자를 생성하는 경우, 다음 사항에 주의하여야 한다.
/tf_static을 구독할 때VOLATILE내구성을 사용하면, 이미 발행된 정적 변환을 수신할 수 없다./tf에 발행할 때TRANSIENT_LOCAL내구성을 사용하면, 불필요한 캐시 부담이 발생한다./tf_static에 발행할 때BEST_EFFORT신뢰도를 사용하면,TransformListener의RELIABLE구독자와 호환되지 않아 연결이 거부된다.
7. QoS 정책이 시스템 동작에 미치는 영향
7.1 시나리오 1: 정상 시작 순서
- 정적 변환 발행자 노드 시작 →
/tf_static에 정적 변환 발행 - 동적 변환 발행자 노드 시작 →
/tf에 주기적 변환 발행 TransformListener포함 노드 시작
이 경우 TRANSIENT_LOCAL 정책에 의해, 단계 3에서 TransformListener가 단계 1에서 발행된 정적 변환을 DDS 캐시를 통해 즉시 수신한다. 동적 변환은 다음 발행 주기에서 수신한다.
7.2 시나리오 2: 정적 변환 발행자 지연 시작
TransformListener포함 노드 시작- 정적 변환 발행자 노드 시작 →
/tf_static에 정적 변환 발행
이 경우에도 정상적으로 동작한다. TransformListener가 이미 /tf_static을 구독하고 있으므로, 단계 2에서 발행된 메시지를 즉시 수신한다.
7.3 시나리오 3: 정적 변환 발행자 종료 후 재시작
- 정적 변환 발행자 노드 시작 → 정적 변환 발행
- 정적 변환 발행자 노드 종료 → DDS 캐시 소멸
- 새로운
TransformListener노드 시작
이 경우 단계 3의 TransformListener는 정적 변환을 수신할 수 없다. TRANSIENT_LOCAL 캐시는 발행자의 수명에 종속되기 때문이다. 이를 방지하기 위해 정적 변환 발행자 노드는 시스템 전체 생명주기 동안 유지되어야 한다.
8. 사용자 정의 QoS 구성
8.1 C++ (rclcpp) 예시
#include <rclcpp/rclcpp.hpp>
#include <tf2_msgs/msg/tf_message.hpp>
// /tf 토픽 QoS 구성
rclcpp::QoS tf_qos(100);
tf_qos.reliable();
// durability는 기본 VOLATILE
auto tf_publisher = node->create_publisher<tf2_msgs::msg::TFMessage>(
"/tf", tf_qos);
// /tf_static 토픽 QoS 구성
rclcpp::QoS tf_static_qos(rclcpp::KeepAll());
tf_static_qos.reliable();
tf_static_qos.transient_local();
auto tf_static_publisher = node->create_publisher<tf2_msgs::msg::TFMessage>(
"/tf_static", tf_static_qos);
8.2 Python (rclpy) 예시
from rclpy.qos import QoSProfile, DurabilityPolicy, ReliabilityPolicy, HistoryPolicy
from tf2_msgs.msg import TFMessage
# /tf 토픽 QoS 구성
tf_qos = QoSProfile(
reliability=ReliabilityPolicy.RELIABLE,
durability=DurabilityPolicy.VOLATILE,
history=HistoryPolicy.KEEP_LAST,
depth=100
)
tf_publisher = node.create_publisher(TFMessage, '/tf', tf_qos)
# /tf_static 토픽 QoS 구성
tf_static_qos = QoSProfile(
reliability=ReliabilityPolicy.RELIABLE,
durability=DurabilityPolicy.TRANSIENT_LOCAL,
history=HistoryPolicy.KEEP_ALL,
depth=0 # KEEP_ALL에서는 무시
)
tf_static_publisher = node.create_publisher(TFMessage, '/tf_static', tf_static_qos)
9. QoS 진단
9.1 토픽 QoS 확인 명령
# /tf 토픽의 QoS 정보 확인
ros2 topic info /tf --verbose
# /tf_static 토픽의 QoS 정보 확인
ros2 topic info /tf_static --verbose
--verbose 옵션을 사용하면 각 발행자와 구독자의 QoS 설정을 상세히 확인할 수 있다. QoS 비호환으로 인한 연결 실패 시, 이 명령을 통해 발행자와 구독자의 QoS 설정을 비교하여 원인을 진단할 수 있다.
9.2 일반적인 QoS 문제와 해결
| 증상 | 원인 | 해결 방법 |
|---|---|---|
| 정적 변환 수신 불가 | 구독자의 Durability가 VOLATILE | TRANSIENT_LOCAL로 변경 |
| 동적 변환 수신 불가 | Reliability 비호환 | 발행자/구독자의 Reliability 일치 |
| 지연 합류 시 정적 변환 누락 | 발행자 노드 종료됨 | 발행자 노드 생존 보장 |
| 메시지 큐 오버플로우 | depth 부족 | depth 증가 또는 콜백 처리 최적화 |
10. 참고 문헌
- ROS2 공식 문서, “About Quality of Service Settings,” https://docs.ros.org/en/humble/Concepts/About-Quality-of-Service-Settings.html
- ROS2 공식 문서, “tf2_ros API,” https://docs.ros.org/en/humble/p/tf2_ros/
- OMG, “Data Distribution Service (DDS) Specification,” Version 1.4, Object Management Group, 2015.
- Foote, T., “tf: The transform library,” 2013 IEEE Conference on Technologies for Practical Robot Applications (TePRA), 2013.
- ROS2 Humble Hawksbill 기준 (2022)