659.38 tf2 시간 여행 (Time Travel) 개념

1. 개요

TF2의 시간 여행(Time Travel)은 서로 다른 시간에서의 좌표 변환을 조합하여, 과거 시점에서 관측된 데이터를 현재 또는 다른 시점의 좌표 프레임으로 변환하는 고급 기능이다. 일반적인 lookupTransform()은 단일 시간에서의 변환만 조회하지만, 시간 여행 기능을 사용하면 소스 프레임과 타깃 프레임의 조회 시간을 독립적으로 지정할 수 있다. 이 기능은 이동 중인 로봇이 과거에 관측한 센서 데이터를 현재 시점의 전역 좌표계로 정확하게 투영해야 하는 경우에 필수적이다.

2. 시간 여행이 필요한 문제 상황

2.1 이동 로봇의 센서 데이터 변환 문제

이동 로봇이 시간 t_0에서 카메라로 물체를 감지했다고 가정하자. 카메라 프레임(camera_link)에서 물체의 좌표가 (x_c, y_c, z_c)로 측정되었다. 이 물체의 좌표를 전역 맵 프레임(map)으로 변환하려면, 다음과 같은 변환 체인이 필요하다.

\mathbf{p}_{\text{map}} = T_{\text{map}}^{\text{camera}}(t) \cdot \mathbf{p}_{\text{camera}}

여기서 핵심적인 문제는 어느 시점 t의 변환을 사용해야 하는가이다.

2.2 단순 접근의 한계

현재 시간($ t_1 $)의 변환을 사용하는 경우: 로봇이 t_0에서 t_1으로 이동하는 동안 위치와 자세가 변했으므로, 현재 시간의 map → camera_link 변환은 과거 관측 시점의 것과 다르다. 따라서 물체의 전역 좌표가 부정확해진다.

관측 시간($ t_0 $)의 변환을 사용하는 경우: lookupTransform("map", "camera_link", t_0)으로 조회하면 정확한 결과를 얻을 수 있지만, 이 방법에는 한 가지 전제가 있다. map → camera_link 경로의 모든 변환이 시간 t_0에서 가용해야 한다는 것이다. 그런데 map → odom 변환은 SLAM(Simultaneous Localization and Mapping) 또는 위치 추정 노드가 발행하며, 해당 노드가 t_0 시점에서는 아직 보정을 완료하지 않았거나 변환을 발행하지 않았을 수 있다.

2.3 시간 여행이 해결하는 문제

시간 여행은 변환 체인을 두 부분으로 나누어, 각 부분에 서로 다른 시간을 적용한다.

  • 소스 프레임 측: 관측 시점 t_0의 변환을 사용한다(camera_link → odomt_0에서 조회).
  • 타깃 프레임 측: 현재 시점 t_1의 변환을 사용한다(map → odomt_1에서 조회).

이 접근은 odom 프레임이 연속적이고 단기적으로 정확하다는 특성을 활용한다.

3. 시간 여행의 수학적 원리

3.1 고정 프레임을 매개로 한 변환 합성

시간 여행에서 핵심 개념은 **고정 프레임(fixed frame)**이다. 고정 프레임은 두 시간 사이에서 일종의 중간 다리(bridge) 역할을 한다. 수학적으로, 시간 여행 변환은 다음과 같이 정의된다.

T_{\text{target}}^{\text{source}}(t_{\text{target}}, t_{\text{source}}) = T_{\text{fixed}}^{\text{target}}(t_{\text{target}}) \cdot \left( T_{\text{fixed}}^{\text{source}}(t_{\text{source}}) \right)^{-1}

여기서:

  • T_{\text{fixed}}^{\text{target}}(t_{\text{target}}): 시간 t_{\text{target}}에서의 고정 프레임에서 타깃 프레임으로의 변환
  • T_{\text{fixed}}^{\text{source}}(t_{\text{source}}): 시간 t_{\text{source}}에서의 고정 프레임에서 소스 프레임으로의 변환
  • (\cdot)^{-1}: 변환의 역변환

3.2 변환 경로 분해

위 수식을 풀어 쓰면, 다음과 같은 세 단계의 변환으로 분해된다.

  1. 소스 프레임 → 고정 프레임 (시간 t_{\text{source}}): 소스 프레임에서 표현된 점을 과거 시점의 고정 프레임으로 변환한다.
  2. 고정 프레임(과거) → 고정 프레임(현재): 고정 프레임은 시간에 걸쳐 자기 자신과 동일하므로, 이 단계는 항등 변환(identity transform)이다. 이것이 “고정” 프레임이라는 이름의 본질이다.
  3. 고정 프레임 → 타깃 프레임 (시간 t_{\text{target}}): 현재 시점의 고정 프레임에서 타깃 프레임으로 변환한다.

3.3 고정 프레임의 선택 기준

고정 프레임으로 적합한 프레임은 다음 조건을 만족해야 한다.

  • 소스 프레임과의 변환이 t_{\text{source}}에서 가용: 소스 프레임에서 고정 프레임까지의 변환이 관측 시점에 존재해야 한다.
  • 타깃 프레임과의 변환이 t_{\text{target}}에서 가용: 타깃 프레임에서 고정 프레임까지의 변환이 조회 시점에 존재해야 한다.
  • 두 시간 사이에서 의미적으로 연속: 고정 프레임의 의미가 두 시간 사이에서 변하지 않아야 한다.

실제 로봇 시스템에서 odom 프레임은 시간 여행의 고정 프레임으로 가장 널리 사용된다. 오도메트리(odometry)는 연속적이고 매 순간 발행되므로, 과거와 현재 사이의 다리 역할을 수행하기에 적합하다.

4. API 사용법

4.1 rclcpp에서의 시간 여행 호출

// 시간 여행 lookupTransform
auto t = tf_buffer_->lookupTransform(
    "map",            // 타깃 프레임
    now,              // 타깃 시간 (현재)
    "camera_link",    // 소스 프레임
    past_time,        // 소스 시간 (관측 시점)
    "odom");          // 고정 프레임

// 반환된 변환을 적용하여 과거 관측 데이터를 현재 맵 좌표로 변환
geometry_msgs::msg::PointStamped point_in_map;
tf2::doTransform(point_in_camera, point_in_map, t);

4.2 rclpy에서의 시간 여행 호출

from rclpy.time import Time
from rclpy.duration import Duration

# 과거 관측 시간
observation_time = Time(seconds=observation_stamp_sec,
                        nanoseconds=observation_stamp_nsec)

# 현재 시간
current_time = self.get_clock().now()

# 시간 여행 변환 조회
t = self.tf_buffer.lookup_transform_full(
    'map',               # 타깃 프레임
    current_time,        # 타깃 시간
    'camera_link',       # 소스 프레임
    observation_time,    # 소스 시간
    'odom',             # 고정 프레임
    timeout=Duration(seconds=1.0))

5. 시간 여행의 실제 응용 사례

5.1 사례 1: 지연된 물체 감지 결과의 투영

카메라 기반 물체 감지(object detection)는 연산 시간이 소요된다. 이미지가 시간 t_0에 캡처되었지만, 감지 결과는 시간 t_1 = t_0 + \Delta t에 산출된다. 이 사이에 로봇이 이동했으므로, 감지 결과를 전역 맵에 정확히 투영하려면 시간 여행이 필요하다.

void detectionCallback(
    const vision_msgs::msg::Detection3DArray::SharedPtr detections)
{
    rclcpp::Time detection_time = detections->header.stamp;
    rclcpp::Time current_time = this->get_clock()->now();

    try {
        auto t = tf_buffer_->lookupTransform(
            "map",
            current_time,
            detections->header.frame_id,
            detection_time,
            "odom");

        for (const auto & det : detections->detections) {
            geometry_msgs::msg::PoseStamped det_pose;
            det_pose.header = detections->header;
            det_pose.pose = det.results[0].pose.pose;

            geometry_msgs::msg::PoseStamped map_pose;
            tf2::doTransform(det_pose, map_pose, t);

            publishDetectionInMap(map_pose);
        }
    } catch (const tf2::TransformException & ex) {
        RCLCPP_WARN(get_logger(), "%s", ex.what());
    }
}

5.2 사례 2: 과거 레이저 스캔의 전역 맵 정합

SLAM이나 맵 구축 과정에서, 과거의 레이저 스캔 데이터를 현재의 보정된 맵 프레임으로 재투영하는 경우에 시간 여행을 활용한다.

5.3 사례 3: 궤적 이력 시각화

로봇의 과거 궤적을 현재 맵 프레임에서 시각화할 때, 각 궤적 지점의 관측 시간에서의 변환을 사용하여 정확한 궤적을 복원한다.

6. 시간 여행의 제약 사항과 주의점

6.1 캐시 기간의 한계

TF2 버퍼는 유한한 캐시 기간(기본값: 10초)을 가진다. 시간 여행에서 source_time이 캐시 기간을 초과하는 과거를 참조하면 tf2::ExtrapolationException이 발생한다. 오래된 데이터를 시간 여행에 활용해야 하는 경우, 버퍼의 캐시 기간을 적절히 늘려야 한다.

// 캐시 기간을 60초로 확장
tf_buffer_ = std::make_unique<tf2_ros::Buffer>(
    this->get_clock(),
    tf2::durationFromSec(60.0));

6.2 고정 프레임의 부재

적절한 고정 프레임이 존재하지 않으면 시간 여행을 사용할 수 없다. 예를 들어, 소스 프레임과 타깃 프레임이 서로 다른 변환 트리에 속하고, 두 트리를 연결할 공통 프레임이 없는 경우가 이에 해당한다.

6.3 고정 프레임의 정확도

고정 프레임의 변환이 두 시간 사이에서 큰 오차를 가지면, 시간 여행 결과의 정확도도 저하된다. odom 프레임을 고정 프레임으로 사용할 때, 오도메트리 드리프트(drift)가 큰 경우에는 긴 시간 간격의 시간 여행에서 오차가 누적될 수 있다.

6.4 두 시간 모두에서의 변환 가용성

시간 여행은 소스 시간과 타깃 시간 모두에서 해당 변환이 가용해야 한다. 어느 한쪽의 시간에서 변환이 없으면 조회가 실패한다.

7. 시간 여행과 일반 조회의 비교

특성일반 lookupTransform()시간 여행 lookupTransform()
시간 파라미터단일 시간소스 시간 + 타깃 시간
고정 프레임불필요필수
사용 시나리오동일 시점의 프레임 간 변환서로 다른 시점 간 변환
인자 수 (rclcpp)3~4개5~6개
연산 복잡도단일 경로 탐색이중 경로 탐색 + 역변환

8. 요약

TF2의 시간 여행은 과거 시점의 센서 관측 데이터를 현재 시점의 좌표 프레임으로 정확하게 변환하기 위한 핵심 메커니즘이다. 고정 프레임을 매개로 서로 다른 시간의 변환을 합성하며, odom 프레임이 고정 프레임으로 가장 널리 사용된다. 이 기능은 센서 데이터의 처리 지연이 있는 시스템, 과거 데이터의 전역 좌표 투영, 궤적 복원 등에서 필수적으로 활용된다. 다만, 캐시 기간, 고정 프레임의 적절성, 양쪽 시간에서의 변환 가용성 등의 제약 조건을 고려하여 사용해야 한다.


참고 문헌 및 출처

  • ROS 2 공식 문서, “Using Time (tf2 Tutorial),” https://docs.ros.org/en/humble/Tutorials/Intermediate/Tf2/Learning-About-Tf2-And-Time-Cpp.html (ROS 2 Humble Hawksbill)
  • ROS 2 공식 문서, “Time Travel with tf2,” https://docs.ros.org/en/humble/Tutorials/Intermediate/Tf2/Time-Travel-With-Tf2-Cpp.html
  • Foote, T., “tf: The Transform Library,” Proceedings of IEEE Conference on Technologies for Practical Robot Applications (TePRA), 2013.
  • REP 105, “Coordinate Frames for Mobile Platforms,” https://www.ros.org/reps/rep-0105.html
  • ROS 2 소스 코드, “geometry2 리포지토리,” https://github.com/ros2/geometry2