659.39 과거 시점의 변환 조회 방법

1. 개요

TF2에서 과거 시점의 변환을 조회하는 것은 센서 데이터 처리의 핵심 과정이다. 센서는 관측 시점의 타임스탬프(timestamp)를 메시지에 기록하며, 해당 데이터를 다른 좌표 프레임으로 변환하려면 관측 시점에서의 프레임 간 변환이 필요하다. TF2의 tf2::Buffer는 일정 기간 동안의 변환 이력을 캐시(cache)에 저장하므로, 캐시 범위 내의 과거 시점에 대한 변환 조회가 가능하다. 본 절에서는 과거 시점 변환 조회의 메커니즘, 구체적 사용법, 그리고 제약 사항을 체계적으로 기술한다.

2. 과거 시점 변환 조회의 필요성

2.1 센서 데이터의 시간 지연

로봇 시스템에서 센서 데이터가 처리 노드에 도달할 때까지 다음과 같은 지연이 발생한다.

  1. 캡처 지연(Capture Latency): 센서가 물리적 신호를 디지털 데이터로 변환하는 시간
  2. 통신 지연(Communication Latency): DDS(Data Distribution Service)를 통해 메시지가 전달되는 시간
  3. 처리 지연(Processing Latency): 수신한 데이터를 알고리즘이 처리하는 시간

이러한 지연으로 인해, 처리 노드가 데이터를 수신하는 시점에서의 로봇 자세(pose)는 센서가 데이터를 캡처한 시점의 자세와 다르다. 정확한 좌표 변환을 위해서는 캡처 시점, 즉 센서 메시지의 header.stamp에 기록된 과거 시간에서의 변환을 사용해야 한다.

2.2 센서 퓨전에서의 시간 정합

여러 센서의 데이터를 융합(fusion)할 때, 각 센서의 타임스탬프가 서로 다를 수 있다. 모든 센서 데이터를 공통 좌표 프레임으로 변환하되, 각 데이터의 캡처 시점에서의 변환을 사용해야 정확한 공간적 정합이 보장된다.

3. 기본 과거 시점 조회 방법

3.1 rclcpp에서의 과거 시점 변환 조회

lookupTransform()의 세 번째 인자에 과거 시점을 지정한다.

void sensorCallback(
    const sensor_msgs::msg::PointCloud2::SharedPtr cloud_msg)
{
    // 센서 메시지의 타임스탬프를 변환 조회 시간으로 사용
    rclcpp::Time sensor_time = cloud_msg->header.stamp;

    try {
        auto transform = tf_buffer_->lookupTransform(
            "map",                         // 타깃 프레임
            cloud_msg->header.frame_id,    // 소스 프레임 (센서 프레임)
            sensor_time);                  // 과거 시점 (센서 캡처 시간)

        // 변환 적용
        sensor_msgs::msg::PointCloud2 cloud_in_map;
        tf2::doTransform(*cloud_msg, cloud_in_map, transform);

    } catch (const tf2::TransformException & ex) {
        RCLCPP_WARN(get_logger(),
            "Past transform lookup failed: %s", ex.what());
    }
}

3.2 rclpy에서의 과거 시점 변환 조회

def sensor_callback(self, cloud_msg):
    sensor_time = cloud_msg.header.stamp

    try:
        transform = self.tf_buffer.lookup_transform(
            'map',
            cloud_msg.header.frame_id,
            rclpy.time.Time.from_msg(sensor_time))

        # 변환 적용
        cloud_in_map = do_transform_cloud(cloud_msg, transform)

    except TransformException as ex:
        self.get_logger().warn(
            f'Past transform lookup failed: {ex}')

4. 과거 시점 조회 시 발생하는 예외 상황

4.1 ExtrapolationException

가장 빈번하게 발생하는 예외로, 조회하려는 시간이 버퍼의 캐시 범위를 벗어날 때 발생한다.

tf2::ExtrapolationException: Lookup would require extrapolation
into the past. Requested time 1616000000.000000000 but the
earliest data is at 1616000005.000000000

이 예외의 원인은 크게 두 가지이다.

  1. 캐시 기간 초과: 조회하려는 시간이 버퍼의 캐시 기간(기본값: 10초)보다 오래된 과거이다.
  2. 변환 미수신: 조회하려는 시간에 해당하는 변환이 아직 수신되지 않았다. 로봇 시스템이 방금 시작되어 충분한 변환 이력이 축적되지 않은 경우에 해당한다.

4.2 LookupException

조회하려는 프레임이 해당 시간에 존재하지 않는 경우에 발생한다. 특정 프레임이 시스템 구동 후 일정 시간이 지나야 등록되는 경우가 이에 해당한다.

5. 과거 시점 조회를 위한 전략

5.1 전략 1: 센서 타임스탬프 직접 사용

가장 기본적이고 정확한 방법이다. 센서 메시지의 header.stamp을 그대로 lookupTransform()에 전달한다.

auto t = tf_buffer_->lookupTransform(
    "base_link",
    msg->header.frame_id,
    msg->header.stamp);

장점: 시간적으로 가장 정확한 변환을 얻는다.
단점: 해당 시점의 변환이 아직 수신되지 않았을 수 있다.

5.2 전략 2: 타임아웃을 활용한 대기 후 조회

변환 발행과 센서 데이터 수신 사이의 시간차를 고려하여, 변환이 가용해질 때까지 짧은 시간 대기한다.

auto t = tf_buffer_->lookupTransform(
    "base_link",
    msg->header.frame_id,
    msg->header.stamp,
    tf2::durationFromSec(0.1));  // 100ms 대기

장점: 변환 수신 지연에 대한 내성이 있다.
단점: 블로킹 호출이므로 제어 주기에 영향을 줄 수 있다.

5.3 전략 3: canTransform()을 이용한 조건부 조회

변환이 가용한 경우에만 조회를 수행하고, 그렇지 않으면 데이터를 버리거나 큐에 저장한다.

if (tf_buffer_->canTransform(
        "base_link", msg->header.frame_id,
        msg->header.stamp)) {
    auto t = tf_buffer_->lookupTransform(
        "base_link", msg->header.frame_id,
        msg->header.stamp);
    processData(msg, t);
} else {
    // 데이터를 큐에 저장하여 나중에 재처리
    pending_messages_.push_back(msg);
}

5.4 전략 4: MessageFilter를 이용한 자동 동기화

tf2_ros::MessageFilter를 사용하면, 변환이 가용해질 때까지 메시지를 자동으로 큐에 보관하고, 변환이 가용해지는 시점에 콜백을 호출한다.

// MessageFilter 설정
tf_filter_ = std::make_shared<tf2_ros::MessageFilter<
    sensor_msgs::msg::PointCloud2>>(
        point_sub_, *tf_buffer_, "map", 50,
        get_node_logging_interface(),
        get_node_clock_interface(),
        tf2::durationFromSec(0.5));

tf_filter_->registerCallback(
    std::bind(&Node::filteredCallback, this, _1));

이 방법은 센서 데이터 처리 파이프라인에서 가장 권장되는 방식이다.

6. 보간을 통한 과거 시점 변환 생성

조회하려는 과거 시점이 캐시에 저장된 두 변환 사이에 위치할 경우, TF2는 자동으로 보간(interpolation)을 수행하여 해당 시점의 변환을 생성한다.

6.1 보간 과정

변환 발행 주파수가 f Hz인 경우, 캐시에는 약 1/f 초 간격으로 변환이 저장된다. 예를 들어, 변환이 50 Hz로 발행되고, 조회 시간이 두 변환 사이에 위치하면:

t_{n} < t_{\text{query}} < t_{n+1}

TF2는 t_nt_{n+1}의 변환을 보간하여 t_{\text{query}}의 변환을 생성한다.

  • 병진 성분: 선형 보간(LERP)
  • 회전 성분: 구면 선형 보간(SLERP)

이 보간 과정은 lookupTransform() 내부에서 자동으로 수행되므로, 사용자가 명시적으로 보간을 요청할 필요가 없다.

7. 캐시 기간 설정과 과거 조회 범위

7.1 기본 캐시 기간

tf2_ros::Buffer의 기본 캐시 기간은 10초이다. 이는 최근 10초 이내의 과거 시점에 대해서만 변환 조회가 가능함을 의미한다.

7.2 캐시 기간 확장

더 오래된 과거 시점의 변환이 필요한 경우, 버퍼 생성 시 캐시 기간을 확장한다.

// 캐시 기간을 30초로 확장
tf_buffer_ = std::make_unique<tf2_ros::Buffer>(
    this->get_clock(),
    tf2::durationFromSec(30.0));
# Python에서의 캐시 기간 확장
from rclpy.duration import Duration
self.tf_buffer = Buffer(
    cache_time=Duration(seconds=30.0))

7.3 캐시 기간 설정 지침

사용 사례권장 캐시 기간근거
실시간 제어10초 (기본값)최근 데이터만 필요
센서 퓨전10~30초다중 센서 지연 보상
SLAM30~60초루프 클로저 처리
궤적 이력 분석60~120초장시간 궤적 재구성
데이터 로그 재생용도에 따라 결정rosbag 데이터 특성 고려

캐시 기간을 증가시키면 메모리 사용량도 비례하여 증가하므로, 시스템의 가용 메모리와 변환 발행 주파수를 고려하여 적절한 값을 설정해야 한다.

8. 실전 예제: 지연된 센서 데이터 처리

8.1 카메라 이미지에서 감지된 물체의 전역 좌표 계산

void detectionCallback(
    const vision_msgs::msg::Detection3DArray::SharedPtr detections)
{
    // 이미지 캡처 시간 (과거 시점)
    rclcpp::Time capture_time = detections->header.stamp;

    // 현재 시간과의 차이 계산
    rclcpp::Duration age =
        this->get_clock()->now() - capture_time;

    RCLCPP_DEBUG(get_logger(),
        "Processing detections from %.3f seconds ago",
        age.seconds());

    try {
        // 과거 시점의 변환 조회
        auto camera_to_map = tf_buffer_->lookupTransform(
            "map",
            detections->header.frame_id,
            capture_time,
            tf2::durationFromSec(0.2));  // 최대 200ms 대기

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

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

            // 맵 좌표에서의 물체 위치 발행
            publishObjectPosition(map_pose);
        }
    } catch (const tf2::ExtrapolationException & ex) {
        RCLCPP_WARN(get_logger(),
            "Detection too old for TF buffer: %s", ex.what());
    } catch (const tf2::TransformException & ex) {
        RCLCPP_WARN(get_logger(),
            "Transform failed: %s", ex.what());
    }
}

8.2 과거 레이저 스캔의 맵 정합

void scanCallback(
    const sensor_msgs::msg::LaserScan::SharedPtr scan)
{
    rclcpp::Time scan_time = scan->header.stamp;

    if (!tf_buffer_->canTransform(
            "map", scan->header.frame_id, scan_time)) {
        RCLCPP_DEBUG(get_logger(),
            "Transform not yet available for scan at time %.3f",
            scan_time.seconds());
        return;
    }

    try {
        auto t = tf_buffer_->lookupTransform(
            "map", scan->header.frame_id, scan_time);

        // 레이저 스캔을 맵 좌표로 변환하여 점유 격자에 반영
        projectScanToMap(scan, t);

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

9. 과거 시점 조회의 한계와 대안

9.1 정적 변환의 시간 독립성

정적 변환(static transform)은 시간에 독립적이므로, 과거 시점을 지정하더라도 항상 동일한 결과를 반환한다. 정적 변환은 시간 파라미터를 무시하고, 가장 최근에 발행된 변환을 반환한다.

9.2 버퍼 시작 전 시간의 조회

시스템이 시작되기 전의 시간에 대한 변환은 조회할 수 없다. tf2::Buffer는 버퍼가 생성된 이후에 수신한 변환만 저장하므로, 버퍼 생성 시점 이전의 변환은 캐시에 존재하지 않는다.

9.3 rosbag 재생 시의 고려사항

rosbag 데이터를 재생할 때, use_sim_time 파라미터를 활성화하여 시뮬레이션 시간을 사용해야 한다. 그렇지 않으면 현재 시스템 시간과 rosbag의 기록 시간 사이의 차이로 인해 과거 시점 변환 조회가 모두 실패한다.

ros2 bag play my_bag --clock

10. 요약

과거 시점의 변환 조회는 lookupTransform()의 시간 파라미터에 센서 메시지의 타임스탬프를 직접 전달하여 수행한다. TF2 버퍼의 캐시 기간 내에서 자동 보간을 통해 임의 시점의 변환을 생성할 수 있으며, tf2_ros::MessageFilter를 활용하면 변환 가용성과 센서 데이터 수신을 자동으로 동기화할 수 있다. 캐시 기간의 적절한 설정과 예외 처리 패턴의 구현이 안정적인 과거 시점 변환 조회의 핵심이다.


참고 문헌 및 출처

  • 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 공식 문서, “tf2_ros::Buffer API Reference,” https://docs.ros2.org/latest/api/tf2_ros/classtf2__ros_1_1Buffer.html
  • Foote, T., “tf: The Transform Library,” Proceedings of IEEE Conference on Technologies for Practical Robot Applications (TePRA), 2013.
  • ROS 2 소스 코드, “geometry2 리포지토리,” https://github.com/ros2/geometry2