659.44 tf2의 캐시 기간 (Cache Duration) 설정
1. 개요
TF2 버퍼(Buffer)의 캐시 기간(cache duration)은 변환 데이터를 메모리에 보관하는 최대 시간을 결정하는 설정이다. 캐시 기간이 10초로 설정되어 있으면, 현재 시간으로부터 최대 10초 이전까지의 변환만 조회할 수 있으며, 그보다 오래된 변환은 캐시에서 자동으로 제거된다. 캐시 기간은 메모리 사용량, 과거 변환 조회 범위, 시스템 응답성 사이의 균형을 결정하는 중요한 설정 파라미터이다.
2. 기본 캐시 기간
2.1 기본값
TF2의 tf2_ros::Buffer 생성 시 별도의 캐시 기간을 지정하지 않으면, 기본값인 10초가 적용된다.
// 기본 캐시 기간 (10초) 사용
auto tf_buffer = std::make_unique<tf2_ros::Buffer>(
node->get_clock());
이 기본값은 대부분의 실시간 로봇 응용에서 충분한 과거 조회 범위를 제공하면서도, 메모리 사용량을 합리적인 수준으로 유지한다.
3. 캐시 기간 설정 방법
3.1 rclcpp에서의 설정
tf2_ros::Buffer 생성자의 두 번째 인자로 캐시 기간을 전달한다.
#include <tf2_ros/buffer.h>
// 30초 캐시 기간 설정
auto tf_buffer = std::make_unique<tf2_ros::Buffer>(
node->get_clock(),
tf2::durationFromSec(30.0));
// TransformListener에 버퍼 전달
auto tf_listener = std::make_shared<tf2_ros::TransformListener>(
*tf_buffer);
tf2::durationFromSec() 함수는 초 단위의 실수를 tf2::Duration(= std::chrono::nanoseconds) 타입으로 변환한다.
// 다양한 캐시 기간 설정 예시
tf2::Duration cache_5s = tf2::durationFromSec(5.0);
tf2::Duration cache_60s = tf2::durationFromSec(60.0);
tf2::Duration cache_300s = tf2::durationFromSec(300.0); // 5분
// std::chrono를 직접 사용
tf2::Duration cache_2min = std::chrono::minutes(2);
tf2::Duration cache_500ms = std::chrono::milliseconds(500);
3.2 rclpy에서의 설정
from tf2_ros import Buffer, TransformListener
from rclpy.duration import Duration
# 30초 캐시 기간 설정
tf_buffer = Buffer(cache_time=Duration(seconds=30.0))
tf_listener = TransformListener(tf_buffer, self)
# 60초 캐시 기간 설정
tf_buffer = Buffer(cache_time=Duration(seconds=60.0))
3.3 런치 파일 또는 파라미터를 통한 동적 설정
캐시 기간을 ROS 2 파라미터로 설정하면, 런치 파일에서 유연하게 제어할 수 있다.
class MyNode : public rclcpp::Node
{
public:
MyNode()
: Node("my_node")
{
// 파라미터로 캐시 기간 설정
this->declare_parameter("tf_cache_duration", 10.0);
double cache_sec =
this->get_parameter("tf_cache_duration")
.as_double();
tf_buffer_ = std::make_unique<tf2_ros::Buffer>(
this->get_clock(),
tf2::durationFromSec(cache_sec));
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(
*tf_buffer_);
}
private:
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
};
<!-- 런치 파일에서 캐시 기간 설정 -->
<launch>
<node pkg="my_package" exec="my_node" name="my_node">
<param name="tf_cache_duration" value="30.0"/>
</node>
</launch>
# Python 런치 파일에서 캐시 기간 설정
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package='my_package',
executable='my_node',
parameters=[{'tf_cache_duration': 30.0}]
),
])
4. 캐시 기간과 내부 구조
4.1 원형 버퍼 (Circular Buffer)
TF2의 내부 캐시는 원형 버퍼(circular buffer) 또는 시간순 정렬 리스트(time-sorted list)로 구현되어 있다. 새로운 변환이 수신되면 버퍼에 추가되고, 캐시 기간을 초과한 오래된 변환은 자동으로 제거된다.
4.2 프레임 쌍별 독립 캐시
캐시는 각 프레임 쌍(부모-자식 관계)별로 독립적으로 관리된다. 예를 들어, odom → base_link와 base_link → camera_link는 별도의 캐시를 가진다. 따라서 캐시 기간 내에 특정 프레임 쌍의 변환만 존재하지 않을 수 있다(해당 프레임의 변환이 발행되지 않은 경우).
4.3 정적 변환의 캐시
정적 변환(static transform)은 캐시 기간의 영향을 받지 않는다. 정적 변환은 한 번 수신되면 버퍼의 수명 동안 유지되며, 캐시 기간과 무관하게 항상 가용하다.
5. 캐시 기간 설정 지침
5.1 용도별 권장 캐시 기간
| 용도 | 권장 캐시 기간 | 근거 |
|---|---|---|
| 실시간 제어 | 10초 (기본값) | 최근 변환만 필요, 메모리 최소화 |
| 센서 퓨전 | 10~30초 | 다중 센서 시간 차이 보상 |
| 내비게이션/SLAM | 30~60초 | 루프 클로저, 맵 갱신 주기 |
| 물체 추적 | 15~30초 | 물체 관측 이력 참조 |
| rosbag 재생/분석 | 60~300초 | 긴 시간 범위의 데이터 분석 |
| 임베디드 시스템 | 5~10초 | 메모리 제약 환경 |
5.2 설정 시 고려 사항
-
최대 센서 지연: 시스템에서 가장 긴 센서 처리 지연보다 캐시 기간이 길어야 한다. 예를 들어, 영상 인식의 처리 지연이 2초라면, 캐시 기간은 최소 2초 이상이어야 한다.
-
변환 발행 주파수와의 관계: 캐시에 저장되는 변환 항목 수는 다음과 같이 계산된다.
N = f \cdot T_{\text{cache}}
여기서 f는 변환 발행 주파수(Hz), T_{\text{cache}}는 캐시 기간(초)이다. 50 Hz 발행에 10초 캐시라면 N = 500개의 변환이 저장된다.
- 다중 프레임의 누적 효과: 시스템에 M개의 동적 프레임 쌍이 존재하면, 전체 캐시 항목 수는 다음과 같다.
N_{\text{total}} = \sum_{i=1}^{M} f_i \cdot T_{\text{cache}}
- 시간 여행 기능의 요구: 과거 데이터의 전역 좌표 투영에 시간 여행(time travel)을 사용하는 경우, 투영하려는 최대 과거 시간까지의 캐시 기간이 필요하다.
6. 캐시 기간 변경의 영향
6.1 캐시 기간 증가 시
| 효과 | 설명 |
|---|---|
| 과거 조회 범위 확대 | 더 오래된 과거 시점의 변환 조회 가능 |
| 메모리 사용량 증가 | 저장되는 변환 항목 수에 비례하여 증가 |
| 캐시 탐색 시간 미세 증가 | 이진 탐색이므로 O(\log N)으로 영향 미미 |
6.2 캐시 기간 감소 시
| 효과 | 설명 |
|---|---|
| 과거 조회 범위 축소 | ExtrapolationException 발생 빈도 증가 가능 |
| 메모리 사용량 감소 | 임베디드 환경에서 유리 |
| 오래된 데이터 빠른 제거 | 데이터 신선도 보장 |
7. 캐시 기간과 메모리 사용량
각 TransformStamped 항목이 차지하는 메모리는 약 100~200 바이트이다(프레임 이름 길이에 따라 변동). 대략적인 메모리 사용량은 다음과 같이 추정할 수 있다.
\text{Memory (bytes)} \approx N_{\text{total}} \times 150
7.1 메모리 사용량 산출 예시
| 동적 프레임 수 | 평균 발행 주파수 | 캐시 기간 | 총 항목 수 | 추정 메모리 |
|---|---|---|---|---|
| 5 | 50 Hz | 10초 | 2,500 | ≈ 375 KB |
| 10 | 50 Hz | 30초 | 15,000 | ≈ 2.2 MB |
| 20 | 100 Hz | 60초 | 120,000 | ≈ 17.6 MB |
| 50 | 100 Hz | 300초 | 1,500,000 | ≈ 214 MB |
위 표에서 볼 수 있듯이, 대부분의 일반적인 로봇 시스템에서 TF2 캐시의 메모리 사용량은 수 MB 이하로 매우 적다. 그러나 프레임 수가 많고, 발행 주파수가 높으며, 캐시 기간이 긴 극단적인 경우에는 수백 MB에 달할 수 있으므로 주의가 필요하다.
8. 캐시 기간 관련 디버깅
8.1 캐시 기간 부족 진단
tf2::ExtrapolationException이 빈번하게 발생하면, 캐시 기간이 부족할 가능성이 있다. 예외 메시지에 포함된 “requested time“과 “earliest data” 사이의 시간 차이를 확인하여 필요한 캐시 기간을 추정할 수 있다.
try {
auto t = tf_buffer_->lookupTransform(
"map", "base_link", past_time);
} catch (const tf2::ExtrapolationException & ex) {
RCLCPP_ERROR(get_logger(),
"Cache duration may be insufficient: %s", ex.what());
// 예외 메시지에서 시간 차이를 분석하여 캐시 기간 조정
}
8.2 tf2_monitor를 이용한 캐시 상태 확인
# 변환 발행 상태 및 지연 시간 모니터링
ros2 run tf2_ros tf2_monitor
tf2_monitor의 출력에서 각 변환의 평균 지연 시간과 최대 지연 시간을 확인하여, 적절한 캐시 기간을 결정할 수 있다.
9. 주의사항
-
캐시 기간은 생성 시에만 설정 가능:
tf2_ros::Buffer의 캐시 기간은 생성자에서만 설정할 수 있으며, 버퍼 생성 이후에는 변경할 수 없다. -
모든 노드에 일괄 적용되지 않음: 캐시 기간은 각 노드의
tf2_ros::Buffer인스턴스별로 독립적으로 설정된다. 시스템 전체에 일괄 적용되는 전역 설정이 아니다. -
정적 변환에는 영향 없음: 캐시 기간은 동적 변환(
/tf토픽)에만 적용되며, 정적 변환(/tf_static토픽)은 캐시 기간과 무관하게 영구 보존된다. -
캐시 기간을 0으로 설정하지 않도록 주의: 캐시 기간이 0이면 변환이 저장되지 않아 모든 조회가 실패한다.
10. 요약
TF2의 캐시 기간은 변환 데이터의 메모리 보관 시간을 제어하는 핵심 설정이다. 기본값 10초는 대부분의 실시간 응용에 적합하며, SLAM, 센서 퓨전, rosbag 분석 등의 용도에 따라 확장할 수 있다. 캐시 기간의 설정은 메모리 사용량, 과거 조회 범위, 시스템 요구사항 사이의 균형을 고려하여 결정해야 하며, 버퍼 생성 시에만 설정 가능하다는 제약 사항을 인지해야 한다.
참고 문헌 및 출처
- ROS 2 공식 문서, “tf2_ros::Buffer Class Reference,” https://docs.ros2.org/latest/api/tf2_ros/classtf2__ros_1_1Buffer.html (ROS 2 Humble Hawksbill)
- ROS 2 소스 코드, “tf2/buffer_core.cpp,” https://github.com/ros2/geometry2 (geometry2 리포지토리)
- Foote, T., “tf: The Transform Library,” Proceedings of IEEE Conference on Technologies for Practical Robot Applications (TePRA), 2013.
- ROS 2 공식 문서, “tf2 Tutorials,” https://docs.ros.org/en/humble/Tutorials/Intermediate/Tf2/Tf2-Main.html