659.21 /tf_static 토픽의 동작 원리
1. 개요
/tf_static 토픽은 ROS2 TF2 시스템에서 정적 변환(static transform)을 전파하기 위한 전용 통신 채널이다. 정적 변환은 시간에 따라 변하지 않는 좌표 프레임 간의 고정적인 공간 관계를 기술하며, 센서 장착 위치, 로봇 링크 간의 고정 관절(fixed joint), 기준 프레임 간의 불변 관계 등이 이에 해당한다. /tf_static 토픽은 /tf 토픽과 동일한 메시지 타입(tf2_msgs/msg/TFMessage)을 사용하지만, QoS 정책과 의미론적 동작이 근본적으로 상이하다.
2. 토픽 기본 정보
| 속성 | 값 |
|---|---|
| 토픽 이름 | /tf_static |
| 메시지 타입 | tf2_msgs/msg/TFMessage |
| 목적 | 정적(시불변) 좌표 변환 전파 |
| 발행 방식 | 일회성 발행 (publish once) |
| 발행자 | StaticTransformBroadcaster 또는 static_transform_publisher 노드 |
| 구독자 | TransformListener |
3. /tf_static의 핵심 특성
3.1 일회성 발행 (Publish Once)
/tf_static 토픽의 가장 중요한 특성은 일회성 발행 원칙이다. 정적 변환은 시간이 경과하여도 변하지 않으므로, 발행자는 해당 변환을 한 번만 발행하면 된다. /tf 토픽과 달리 주기적인 재발행이 불필요하며, 이는 시스템의 대역폭 효율성을 크게 향상시킨다.
3.2 지연 합류 지원 (Late-Joining Support)
정적 변환이 한 번만 발행되므로, 나중에 시스템에 참여하는 구독자(late-joiner)가 이전에 발행된 정적 변환을 수신할 수 있어야 한다. 이를 위해 /tf_static 토픽은 TRANSIENT_LOCAL 내구성(durability) QoS 정책을 사용한다. 이 정책에 의해 DDS 미들웨어가 발행된 메시지를 캐시에 보관하고, 새로 연결된 구독자에게 캐시된 메시지를 즉시 전달한다.
3.3 시간 불변성 (Time Invariance)
TF2 시스템은 /tf_static 토픽을 통해 수신된 변환을 모든 시간에서 유효한 것으로 취급한다. 이는 lookupTransform() 호출 시 어떤 시간을 지정하더라도, 정적 변환은 항상 가용한 것으로 간주됨을 의미한다. Buffer는 정적 변환을 시계열(time series) 형태가 아닌, 프레임 쌍에 대한 단일 불변 값으로 저장한다.
4. QoS 정책
4.1 기본 QoS 설정
| QoS 정책 | 설정 값 | 설명 |
|---|---|---|
| Reliability | RELIABLE | 메시지 전달 보장 |
| Durability | TRANSIENT_LOCAL | 지연 합류 구독자를 위한 메시지 캐싱 |
| History | KEEP_ALL 또는 KEEP_LAST(큰 depth) | 모든 정적 변환 보관 |
4.2 TRANSIENT_LOCAL 내구성의 동작
TRANSIENT_LOCAL 내구성은 /tf_static 토픽의 핵심 기능을 구현하는 메커니즘이다. 이 설정의 동작 과정은 다음과 같다.
- 발행 시:
StaticTransformBroadcaster가 TFMessage를 발행하면, DDS 미들웨어는 해당 메시지를 발행자 측의 로컬 캐시에 저장한다. - 기존 구독자 수신: 이미 연결된 구독자는 즉시 메시지를 수신한다.
- 지연 합류: 나중에 연결된 구독자는 DDS 발견(discovery) 과정에서 발행자의 캐시에 보관된 모든 메시지를 수신한다.
- 메시지 보존: 발행자 노드가 살아있는 한, 캐시된 메시지는 보존된다. 발행자 노드가 종료되면 캐시도 소멸된다.
4.3 RELIABLE 신뢰도의 필요성
정적 변환은 한 번만 발행되므로, 메시지 손실은 회복이 불가능하다(재발행되지 않기 때문). 따라서 RELIABLE 신뢰도 정책을 사용하여 메시지의 확실한 전달을 보장한다. BEST_EFFORT 정책은 정적 변환에 부적합하다.
5. 발행 메커니즘
5.1 StaticTransformBroadcaster의 내부 동작
StaticTransformBroadcaster는 /tf_static 토픽에 대한 발행자를 TRANSIENT_LOCAL QoS로 생성하고, sendTransform() 호출 시 TFMessage를 발행한다.
// StaticTransformBroadcaster 내부 동작 (개념적)
class StaticTransformBroadcaster {
rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr publisher_;
tf2_msgs::msg::TFMessage net_message_; // 누적 저장소
public:
StaticTransformBroadcaster(rclcpp::Node::SharedPtr node) {
rclcpp::QoS qos(rclcpp::KeepAll());
qos.transient_local();
qos.reliable();
publisher_ = node->create_publisher<tf2_msgs::msg::TFMessage>(
"/tf_static", qos);
}
void sendTransform(const geometry_msgs::msg::TransformStamped& transform) {
// 기존 변환 목록에 추가 (동일 프레임 쌍은 갱신)
bool found = false;
for (auto& t : net_message_.transforms) {
if (t.child_frame_id == transform.child_frame_id) {
t = transform;
found = true;
break;
}
}
if (!found) {
net_message_.transforms.push_back(transform);
}
publisher_->publish(net_message_);
}
};
주목할 점은, StaticTransformBroadcaster가 내부적으로 이전에 발행된 모든 정적 변환을 누적하여 저장하고, 새 변환이 추가될 때마다 전체 목록을 한꺼번에 재발행한다는 것이다. 이는 TRANSIENT_LOCAL 캐시에 최신 상태의 완전한 정적 변환 집합이 유지되도록 보장한다.
5.2 static_transform_publisher 노드
ROS2는 런치 파일에서 정적 변환을 편리하게 발행하기 위한 static_transform_publisher 유틸리티 노드를 제공한다.
# 명령행에서의 사용
ros2 run tf2_ros static_transform_publisher \
--x 0.1 --y 0.0 --z 0.2 \
--roll 0.0 --pitch 0.0 --yaw 0.0 \
--frame-id base_link --child-frame-id camera_link
이 노드는 지정된 프레임 간의 정적 변환을 /tf_static 토픽에 발행하며, 노드가 활성 상태인 동안 TRANSIENT_LOCAL 캐시를 통해 지연 합류 구독자에게도 변환을 제공한다.
6. 수신 메커니즘
6.1 TransformListener의 /tf_static 구독
TransformListener는 초기화 시 /tf_static 토픽에 대한 구독자를 TRANSIENT_LOCAL QoS로 생성한다. 이를 통해 이미 발행된 정적 변환을 구독 즉시 수신할 수 있다.
TransformListener 초기화:
/tf_static 구독자 생성 (QoS: RELIABLE, TRANSIENT_LOCAL, KEEP_ALL)
/tf_static 수신 콜백(TFMessage msg):
for each transform in msg.transforms:
buffer.setTransform(transform, authority, is_static=true)
is_static=true 플래그는 Buffer에게 해당 변환이 정적 변환임을 알려주며, Buffer는 이 변환을 시간 무관 저장소에 보관한다.
6.2 Buffer에서의 정적 변환 저장
Buffer는 정적 변환을 동적 변환과 분리된 저장 공간에 보관한다. 정적 변환은 다음과 같은 특성을 갖는다.
- 시간 스탬프에 의한 인덱싱이 적용되지 않는다.
- 캐시 기간(cache duration)의 제약을 받지 않는다.
- 어떤 시간으로 조회하여도 항상 반환된다.
- 보간이나 외삽 연산이 적용되지 않는다.
7. 데이터 흐름
[정적 변환 소스]
↓ (StaticTransformBroadcaster.sendTransform())
[tf2_msgs/msg/TFMessage 생성]
↓ (DDS publish, TRANSIENT_LOCAL)
[/tf_static 토픽 + DDS 캐시]
↓ (DDS subscribe, 즉시 + 지연 합류)
[TransformListener 수신 콜백]
↓ (Buffer.setTransform(..., is_static=true))
[tf2::Buffer 정적 저장소]
↓ (lookupTransform() 호출 시, 모든 시간에서 유효)
[TransformStamped 반환]
8. /tf와의 주요 차이점 요약
| 특성 | /tf | /tf_static |
|---|---|---|
| 변환 유형 | 동적 (시변) | 정적 (시불변) |
| 발행 방식 | 주기적 발행 | 일회성 발행 |
| QoS Durability | VOLATILE | TRANSIENT_LOCAL |
| 지연 합류 | 다음 발행까지 대기 | DDS 캐시로 즉시 수신 |
| 변환 만료 | 발행 중단 시 만료 | 만료되지 않음 |
| 시간 의존성 | 시간 기반 저장/조회 | 시간 무관 저장/조회 |
| 보간/외삽 | 적용 가능 | 적용 불가 |
| 네트워크 부하 | 주기적 트래픽 | 발행 시에만 트래픽 |
9. 정적 변환의 대표적 사용 사례
9.1 센서 장착 위치
로봇 본체에 고정 장착된 센서의 위치와 방향은 정적 변환으로 정의한다.
base_link → camera_link # 카메라 장착 위치
base_link → imu_link # IMU 장착 위치
base_link → lidar_link # LiDAR 장착 위치
base_link → gps_link # GPS 안테나 위치
9.2 고정 관절 (Fixed Joint)
URDF에서 fixed 타입으로 정의된 관절은 robot_state_publisher에 의해 /tf_static을 통해 발행된다.
9.3 프레임 보정 (Frame Calibration)
센서 외부 파라미터(extrinsic parameters) 보정 결과로 얻어진 센서 간의 상대 위치는 정적 변환으로 설정한다. 예를 들어, 카메라-LiDAR 보정(calibration) 결과는 두 센서 프레임 간의 정적 변환으로 표현된다.
10. 주의 사항
10.1 발행자 수명
TRANSIENT_LOCAL 내구성은 발행자 노드가 활성 상태인 동안에만 유효하다. 발행자 노드가 종료되면 DDS 캐시도 소멸되므로, 이후에 합류하는 구독자는 해당 정적 변환을 수신할 수 없다. 따라서 정적 변환 발행 노드는 시스템 전체 생명주기 동안 유지되어야 한다.
10.2 정적 변환의 갱신
정적 변환은 원칙적으로 불변이지만, 동일한 child_frame_id에 대해 새로운 정적 변환을 발행하면 이전 값이 대체된다. 다만, 이는 런타임 중에 센서 위치를 변경하는 등의 비정상적 상황에서만 사용하여야 하며, 빈번한 갱신이 필요한 경우에는 /tf 토픽을 통한 동적 변환을 사용하여야 한다.
10.3 QoS 호환성
/tf_static을 수신하려면 구독자의 QoS가 발행자의 QoS와 호환되어야 한다. 특히 구독자의 durability가 VOLATILE로 설정되어 있으면 TRANSIENT_LOCAL 발행자의 캐시된 메시지를 수신할 수 없다. TransformListener는 이를 올바르게 설정하지만, 직접 구독자를 생성하는 경우 주의하여야 한다.
11. 참고 문헌
- 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)