659.23 TransformBroadcaster를 이용한 동적 변환 발행

1. 개요

tf2_ros::TransformBroadcaster는 ROS2 TF2 시스템에서 동적 변환(dynamic transform)을 /tf 토픽에 발행하기 위한 표준 인터페이스이다. 이 클래스는 geometry_msgs/msg/TransformStamped 메시지를 tf2_msgs/msg/TFMessage로 캡슐화하여 적절한 QoS 정책과 함께 발행하는 과정을 추상화한다. 로봇의 주행 거리 측정(odometry), 위치 추정(localization), 관절 상태 갱신 등 시간에 따라 변화하는 좌표 변환을 전파할 때 사용된다.

2. TransformBroadcaster의 역할

TransformBroadcaster는 TF2 변환 발행 파이프라인에서 다음과 같은 역할을 수행한다.

[사용자 코드]
    ↓ (TransformStamped 생성)
[TransformBroadcaster.sendTransform()]
    ↓ (TFMessage 구성, QoS 적용)
[/tf 토픽 발행]
    ↓ (DDS 전송)
[TransformListener 수신 → Buffer 저장]

TransformBroadcaster는 다음 세 가지 핵심 기능을 수행한다.

  1. 내부 발행자 관리: /tf 토픽에 대한 rclcpp::Publisher 또는 rclpy.Publisher를 내부적으로 생성하고 관리한다.
  2. QoS 정책 적용: 동적 변환에 적합한 QoS 정책(RELIABLE, VOLATILE, KEEP_LAST)을 자동으로 설정한다.
  3. 메시지 캡슐화: TransformStamped 메시지를 TFMessage 형태로 변환하여 발행한다.

3. 클래스 인터페이스

3.1 C++ (rclcpp) 인터페이스

namespace tf2_ros {

class TransformBroadcaster {
public:
    // 생성자
    explicit TransformBroadcaster(rclcpp::Node::SharedPtr node);
    explicit TransformBroadcaster(rclcpp::Node& node);

    // 단일 변환 발행
    void sendTransform(const geometry_msgs::msg::TransformStamped& transform);

    // 다중 변환 일괄 발행
    void sendTransform(
        const std::vector<geometry_msgs::msg::TransformStamped>& transforms);
};

}  // namespace tf2_ros

3.2 Python (rclpy) 인터페이스

class TransformBroadcaster:
    def __init__(self, node: Node, qos: QoSProfile = None):
        ...

    def sendTransform(self,
        transform: Union[TransformStamped, List[TransformStamped]]) -> None:
        ...

4. 생성 및 초기화

4.1 노드 내에서의 생성

TransformBroadcaster는 반드시 ROS2 노드의 컨텍스트 내에서 생성되어야 한다. 생성 시 내부적으로 /tf 토픽에 대한 발행자가 자동으로 생성된다.

C++ 예시:

#include <tf2_ros/transform_broadcaster.h>

class MyNode : public rclcpp::Node {
public:
    MyNode() : Node("my_node") {
        // TransformBroadcaster 생성
        tf_broadcaster_ = std::make_unique<tf2_ros::TransformBroadcaster>(*this);
    }

private:
    std::unique_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
};

Python 예시:

from tf2_ros import TransformBroadcaster

class MyNode(Node):
    def __init__(self):
        super().__init__('my_node')
        # TransformBroadcaster 생성
        self.tf_broadcaster = TransformBroadcaster(self)

4.2 생성 시점

TransformBroadcaster는 일반적으로 노드의 생성자(constructor)에서 한 번 생성하고, 노드의 수명 동안 재사용한다. 콜백 함수 내에서 반복적으로 생성하는 것은 불필요한 오버헤드를 야기하므로 피하여야 한다.

5. 변환 발행

5.1 단일 변환 발행

가장 기본적인 사용 패턴은 단일 TransformStamped 메시지를 발행하는 것이다.

void publishTransform() {
    geometry_msgs::msg::TransformStamped t;

    // 시간 스탬프 설정
    t.header.stamp = this->get_clock()->now();

    // 프레임 관계 설정
    t.header.frame_id = "odom";
    t.child_frame_id = "base_link";

    // 병진 변환 설정
    t.transform.translation.x = robot_x_;
    t.transform.translation.y = robot_y_;
    t.transform.translation.z = 0.0;

    // 회전 변환 설정
    tf2::Quaternion q;
    q.setRPY(0.0, 0.0, robot_theta_);
    t.transform.rotation.x = q.x();
    t.transform.rotation.y = q.y();
    t.transform.rotation.z = q.z();
    t.transform.rotation.w = q.w();

    // 변환 발행
    tf_broadcaster_->sendTransform(t);
}

5.2 다중 변환 일괄 발행

관련된 여러 변환을 동시에 발행해야 하는 경우, 벡터를 이용하여 일괄 발행할 수 있다.

void publishMultipleTransforms() {
    std::vector<geometry_msgs::msg::TransformStamped> transforms;

    geometry_msgs::msg::TransformStamped t1;
    t1.header.stamp = this->get_clock()->now();
    t1.header.frame_id = "odom";
    t1.child_frame_id = "base_link";
    // ... 변환 데이터 설정 ...
    transforms.push_back(t1);

    geometry_msgs::msg::TransformStamped t2;
    t2.header.stamp = this->get_clock()->now();
    t2.header.frame_id = "base_link";
    t2.child_frame_id = "sensor_link";
    // ... 변환 데이터 설정 ...
    transforms.push_back(t2);

    // 다중 변환 일괄 발행
    tf_broadcaster_->sendTransform(transforms);
}

일괄 발행은 다수의 변환을 단일 TFMessage에 포함시켜 발행하므로, 개별 발행 대비 네트워크 오버헤드가 절감된다.

6. 주기적 발행 패턴

동적 변환은 주기적으로 갱신되어야 하므로, 타이머(timer) 콜백을 이용한 주기적 발행이 일반적이다.

6.1 타이머 기반 발행

class OdometryBroadcaster : public rclcpp::Node {
public:
    OdometryBroadcaster() : Node("odom_broadcaster") {
        tf_broadcaster_ = std::make_unique<tf2_ros::TransformBroadcaster>(*this);

        // 50Hz 주기 타이머 생성
        timer_ = this->create_wall_timer(
            std::chrono::milliseconds(20),
            std::bind(&OdometryBroadcaster::timerCallback, this));
    }

private:
    void timerCallback() {
        geometry_msgs::msg::TransformStamped t;
        t.header.stamp = this->get_clock()->now();
        t.header.frame_id = "odom";
        t.child_frame_id = "base_link";

        // 현재 로봇 위치와 자세 반영
        t.transform.translation.x = current_x_;
        t.transform.translation.y = current_y_;
        t.transform.translation.z = 0.0;

        tf2::Quaternion q;
        q.setRPY(0.0, 0.0, current_theta_);
        t.transform.rotation = tf2::toMsg(q);

        tf_broadcaster_->sendTransform(t);
    }

    std::unique_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
    rclcpp::TimerBase::SharedPtr timer_;
    double current_x_ = 0.0, current_y_ = 0.0, current_theta_ = 0.0;
};

6.2 구독 콜백 기반 발행

센서 데이터나 주행 거리 메시지를 수신할 때마다 변환을 갱신하여 발행하는 패턴이다.

class OdometrySubscriberBroadcaster : public rclcpp::Node {
public:
    OdometrySubscriberBroadcaster() : Node("odom_sub_broadcaster") {
        tf_broadcaster_ = std::make_unique<tf2_ros::TransformBroadcaster>(*this);

        odom_sub_ = this->create_subscription<nav_msgs::msg::Odometry>(
            "odom", 10,
            std::bind(&OdometrySubscriberBroadcaster::odomCallback,
                      this, std::placeholders::_1));
    }

private:
    void odomCallback(const nav_msgs::msg::Odometry::SharedPtr msg) {
        geometry_msgs::msg::TransformStamped t;

        // 주행 거리 메시지의 시간 스탬프 사용
        t.header.stamp = msg->header.stamp;
        t.header.frame_id = msg->header.frame_id;
        t.child_frame_id = msg->child_frame_id;

        // 포즈 데이터로부터 변환 생성
        t.transform.translation.x = msg->pose.pose.position.x;
        t.transform.translation.y = msg->pose.pose.position.y;
        t.transform.translation.z = msg->pose.pose.position.z;
        t.transform.rotation = msg->pose.pose.orientation;

        tf_broadcaster_->sendTransform(t);
    }

    std::unique_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster_;
    rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr odom_sub_;
};

7. 내부 동작 메커니즘

7.1 sendTransform() 처리 과정

sendTransform() 메서드가 호출되면 내부적으로 다음 단계가 수행된다.

  1. tf2_msgs::msg::TFMessage 객체를 생성한다.
  2. 입력된 TransformStamped(또는 벡터)를 TFMessage.transforms 배열에 추가한다.
  3. 내부 발행자를 통해 /tf 토픽에 TFMessage를 발행한다.

이 과정에서 별도의 입력 검증(validation)은 수행되지 않는다. 쿼터니언의 정규화, 프레임 이름의 유효성 등은 발행 측에서 보장하여야 하며, 수신 측의 Buffer::setTransform()에서 검증이 이루어진다.

8. 발행 주파수 선택 기준

동적 변환의 발행 주파수는 다음 요인을 고려하여 결정한다.

요인설명지침
변환 변화 속도프레임 관계가 얼마나 빠르게 변하는가변화 속도에 비례
소비자 요구 주파수변환을 사용하는 노드의 데이터 처리 주파수소비자 주파수 이상
네트워크 대역폭사용 가능한 네트워크 자원불필요한 고주파 발행 지양
보간 정확도TF2 보간의 정확도 요구 수준높은 정확도 → 높은 주파수

일반적인 권장 주파수는 다음과 같다.

  • 주행 거리 변환 (odom → base_link): 50–100 Hz
  • 위치 추정 변환 (map → odom): 10–30 Hz
  • 관절 상태 변환: 센서 갱신 주파수에 동기화

9. 주의 사항

9.1 시간 스탬프의 정확성

TransformStamped의 header.stamp는 변환이 유효한 정확한 시점을 반영하여야 한다. 센서 데이터로부터 변환을 생성하는 경우, 센서 데이터의 시간 스탬프를 사용하는 것이 권장된다. this->get_clock()->now()를 사용하면 처리 지연으로 인한 시간 불일치가 발생할 수 있다.

9.2 쿼터니언 유효성

발행 시 rotation 필드의 쿼터니언이 단위 노름 조건(\lVert q \rVert = 1)을 만족하는지 확인하여야 한다. 기본 초기화 값 (0, 0, 0, 0)은 유효하지 않으므로, 반드시 유효한 쿼터니언을 설정하여야 한다.

9.3 단일 발행자 원칙

하나의 프레임 쌍(parent-child pair)에 대해서는 하나의 발행자만 존재하여야 한다. 동일한 프레임 쌍에 대해 두 개 이상의 노드가 변환을 발행하면, TF2 시스템에서 경합 조건(race condition)이 발생하여 변환의 일관성이 보장되지 않는다.

9.4 패키지 의존성

TransformBroadcaster를 사용하기 위해서는 tf2_ros 패키지에 대한 의존성을 선언하여야 한다.

package.xml:

<depend>tf2_ros</depend>
<depend>geometry_msgs</depend>

CMakeLists.txt:

find_package(tf2_ros REQUIRED)
find_package(geometry_msgs REQUIRED)

ament_target_dependencies(my_node
    tf2_ros
    geometry_msgs
)

10. 참고 문헌

  • ROS2 공식 문서, “tf2_ros::TransformBroadcaster,” https://docs.ros.org/en/humble/p/tf2_ros/
  • ROS2 공식 튜토리얼, “Writing a tf2 broadcaster (C++),” https://docs.ros.org/en/humble/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Broadcaster-Cpp.html
  • Foote, T., “tf: The transform library,” 2013 IEEE Conference on Technologies for Practical Robot Applications (TePRA), 2013.
  • ROS2 Humble Hawksbill 기준 (2022)