659.27 StaticTransformBroadcaster의 rclcpp 사용법

1. 개요

tf2_ros::StaticTransformBroadcaster는 ROS2의 C++ 클라이언트 라이브러리 rclcpp에서 정적 좌표 변환(static transform)을 발행하기 위한 클래스이다. 정적 변환은 시간에 따라 변하지 않는 프레임 간의 고정된 기하학적 관계를 나타내며, /tf_static 토픽을 통하여 TRANSIENT_LOCAL QoS 정책으로 발행된다. 본 절에서는 StaticTransformBroadcasterrclcpp 기반 사용법을 상세히 기술한다.

2. 헤더 파일 및 의존성

2.1 필수 헤더 파일

#include <rclcpp/rclcpp.hpp>
#include <tf2_ros/static_transform_broadcaster.h>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <tf2/LinearMath/Quaternion.h>

tf2_ros/static_transform_broadcaster.hStaticTransformBroadcaster 클래스가 정의되어 있다. tf2/LinearMath/Quaternion.h는 오일러 각을 쿼터니언으로 변환하는 데 사용된다.

2.2 package.xml 의존성

<depend>rclcpp</depend>
<depend>tf2_ros</depend>
<depend>tf2</depend>
<depend>geometry_msgs</depend>

2.3 CMakeLists.txt 설정

find_package(rclcpp REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(tf2 REQUIRED)
find_package(geometry_msgs REQUIRED)

add_executable(static_tf_broadcaster src/static_tf_broadcaster.cpp)
ament_target_dependencies(static_tf_broadcaster
  rclcpp
  tf2_ros
  tf2
  geometry_msgs
)

3. StaticTransformBroadcaster 클래스의 인터페이스

3.1 생성자

StaticTransformBroadcaster는 다음의 생성자 시그니처를 제공한다.

explicit StaticTransformBroadcaster(rclcpp::Node * node);
explicit StaticTransformBroadcaster(rclcpp::Node::SharedPtr node);

TransformBroadcaster와 동일하게 원시 포인터(raw pointer)와 공유 포인터(shared pointer) 양쪽을 지원한다.

3.2 sendTransform 메서드

void sendTransform(const geometry_msgs::msg::TransformStamped & transform);
void sendTransform(const std::vector<geometry_msgs::msg::TransformStamped> & transforms);

sendTransform() 메서드는 단일 변환 또는 복수의 변환을 인자로 받는다. 내부적으로 이전에 발행한 모든 정적 변환을 축적(accumulate)하며, 매 호출 시 축적된 전체 변환을 하나의 TFMessage로 재발행한다.

4. 기본 사용 패턴

4.1 생성자에서의 일회 발행

정적 변환의 가장 기본적인 사용 패턴은 노드 생성자에서 한 번 발행하는 것이다.

#include <rclcpp/rclcpp.hpp>
#include <tf2_ros/static_transform_broadcaster.h>
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <tf2/LinearMath/Quaternion.h>

class StaticFramePublisher : public rclcpp::Node
{
public:
  StaticFramePublisher()
  : Node("static_frame_publisher")
  {
    static_broadcaster_ =
      std::make_shared<tf2_ros::StaticTransformBroadcaster>(this);

    publish_static_transforms();
  }

private:
  void publish_static_transforms()
  {
    geometry_msgs::msg::TransformStamped t;

    t.header.stamp = this->get_clock()->now();
    t.header.frame_id = "base_link";
    t.child_frame_id = "lidar_link";

    t.transform.translation.x = 0.20;
    t.transform.translation.y = 0.00;
    t.transform.translation.z = 0.35;

    tf2::Quaternion q;
    q.setRPY(0.0, 0.0, 0.0);
    t.transform.rotation.x = q.x();
    t.transform.rotation.y = q.y();
    t.transform.rotation.z = q.z();
    t.transform.rotation.w = q.w();

    static_broadcaster_->sendTransform(t);
    RCLCPP_INFO(this->get_logger(),
      "Published static transform: base_link -> lidar_link");
  }

  std::shared_ptr<tf2_ros::StaticTransformBroadcaster> static_broadcaster_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<StaticFramePublisher>());
  rclcpp::shutdown();
  return 0;
}

rclcpp::spin()을 호출하여 노드를 활성 상태로 유지하는 것이 필수적이다. 노드가 종료되면 TRANSIENT_LOCAL QoS에 의한 메시지 캐시가 소멸하여, 이후 참여하는 구독자가 정적 변환을 수신할 수 없게 된다.

5. 복수 센서의 정적 변환 발행

로봇에 다수의 센서가 장착된 경우, 각 센서의 장착 위치를 정적 변환으로 동시에 발행할 수 있다.

5.1 벡터를 이용한 일괄 발행

class MultiSensorTFPublisher : public rclcpp::Node
{
public:
  MultiSensorTFPublisher()
  : Node("multi_sensor_tf_publisher")
  {
    static_broadcaster_ =
      std::make_shared<tf2_ros::StaticTransformBroadcaster>(this);

    publish_all_sensor_frames();
  }

private:
  void publish_all_sensor_frames()
  {
    std::vector<geometry_msgs::msg::TransformStamped> static_transforms;
    auto stamp = this->get_clock()->now();

    // LiDAR 센서
    static_transforms.push_back(
      create_static_transform(stamp,
        "base_link", "lidar_link",
        0.20, 0.00, 0.35,
        0.0, 0.0, 0.0));

    // 전방 카메라
    static_transforms.push_back(
      create_static_transform(stamp,
        "base_link", "front_camera_link",
        0.25, 0.00, 0.20,
        0.0, 0.0, 0.0));

    // 카메라 광학 프레임
    static_transforms.push_back(
      create_static_transform(stamp,
        "front_camera_link", "front_camera_optical",
        0.0, 0.0, 0.0,
        -M_PI / 2.0, 0.0, -M_PI / 2.0));

    // IMU 센서
    static_transforms.push_back(
      create_static_transform(stamp,
        "base_link", "imu_link",
        0.10, 0.00, 0.15,
        0.0, 0.0, 0.0));

    // GPS 안테나
    static_transforms.push_back(
      create_static_transform(stamp,
        "base_link", "gps_link",
        -0.05, 0.00, 0.50,
        0.0, 0.0, 0.0));

    static_broadcaster_->sendTransform(static_transforms);
    RCLCPP_INFO(this->get_logger(),
      "Published %zu static transforms", static_transforms.size());
  }

  geometry_msgs::msg::TransformStamped create_static_transform(
    const rclcpp::Time & stamp,
    const std::string & parent_frame,
    const std::string & child_frame,
    double x, double y, double z,
    double roll, double pitch, double yaw)
  {
    geometry_msgs::msg::TransformStamped t;
    t.header.stamp = stamp;
    t.header.frame_id = parent_frame;
    t.child_frame_id = child_frame;

    t.transform.translation.x = x;
    t.transform.translation.y = y;
    t.transform.translation.z = z;

    tf2::Quaternion q;
    q.setRPY(roll, pitch, yaw);
    t.transform.rotation.x = q.x();
    t.transform.rotation.y = q.y();
    t.transform.rotation.z = q.z();
    t.transform.rotation.w = q.w();

    return t;
  }

  std::shared_ptr<tf2_ros::StaticTransformBroadcaster> static_broadcaster_;
};

create_static_transform() 헬퍼 함수를 정의하여 코드의 가독성과 유지보수성을 향상시킨다. 모든 센서 프레임을 벡터에 축적한 후 sendTransform()을 한 번 호출하여 일괄 발행한다.

6. 파라미터 기반 동적 구성

센서 장착 위치를 하드코딩하지 않고, ROS2 파라미터를 통하여 런타임에 구성하는 패턴이다.

class ParameterizedStaticTF : public rclcpp::Node
{
public:
  ParameterizedStaticTF()
  : Node("parameterized_static_tf")
  {
    this->declare_parameter("parent_frame", "base_link");
    this->declare_parameter("child_frame", "sensor_link");
    this->declare_parameter("x", 0.0);
    this->declare_parameter("y", 0.0);
    this->declare_parameter("z", 0.0);
    this->declare_parameter("roll", 0.0);
    this->declare_parameter("pitch", 0.0);
    this->declare_parameter("yaw", 0.0);

    static_broadcaster_ =
      std::make_shared<tf2_ros::StaticTransformBroadcaster>(this);

    publish_from_parameters();
  }

private:
  void publish_from_parameters()
  {
    geometry_msgs::msg::TransformStamped t;
    t.header.stamp = this->get_clock()->now();
    t.header.frame_id = this->get_parameter("parent_frame").as_string();
    t.child_frame_id = this->get_parameter("child_frame").as_string();

    t.transform.translation.x = this->get_parameter("x").as_double();
    t.transform.translation.y = this->get_parameter("y").as_double();
    t.transform.translation.z = this->get_parameter("z").as_double();

    tf2::Quaternion q;
    q.setRPY(
      this->get_parameter("roll").as_double(),
      this->get_parameter("pitch").as_double(),
      this->get_parameter("yaw").as_double());
    t.transform.rotation.x = q.x();
    t.transform.rotation.y = q.y();
    t.transform.rotation.z = q.z();
    t.transform.rotation.w = q.w();

    static_broadcaster_->sendTransform(t);
  }

  std::shared_ptr<tf2_ros::StaticTransformBroadcaster> static_broadcaster_;
};

이 패턴을 사용하면 런치 파일에서 센서 장착 위치를 외부적으로 지정할 수 있다.

Node(
    package='my_robot_tf',
    executable='parameterized_static_tf',
    name='lidar_static_tf',
    parameters=[{
        'parent_frame': 'base_link',
        'child_frame': 'lidar_link',
        'x': 0.20,
        'y': 0.00,
        'z': 0.35,
        'roll': 0.0,
        'pitch': 0.0,
        'yaw': 0.0,
    }],
)

7. 생명주기 노드에서의 사용

rclcpp_lifecycle::LifecycleNode를 사용하는 경우, on_configure 또는 on_activate 콜백에서 정적 변환을 발행할 수 있다.

#include <rclcpp_lifecycle/lifecycle_node.hpp>

class LifecycleStaticTF : public rclcpp_lifecycle::LifecycleNode
{
public:
  LifecycleStaticTF()
  : rclcpp_lifecycle::LifecycleNode("lifecycle_static_tf")
  {}

  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
  on_configure(const rclcpp_lifecycle::State &)
  {
    static_broadcaster_ =
      std::make_shared<tf2_ros::StaticTransformBroadcaster>(
        this->shared_from_this());

    geometry_msgs::msg::TransformStamped t;
    t.header.stamp = this->get_clock()->now();
    t.header.frame_id = "base_link";
    t.child_frame_id = "sensor_link";
    t.transform.translation.x = 0.1;
    t.transform.rotation.w = 1.0;

    static_broadcaster_->sendTransform(t);

    return rclcpp_lifecycle::node_interfaces::
      LifecycleNodeInterface::CallbackReturn::SUCCESS;
  }

private:
  std::shared_ptr<tf2_ros::StaticTransformBroadcaster> static_broadcaster_;
};

정적 변환은 구성(configure) 단계에서 발행하는 것이 적절하다. 활성화(activate) 단계에서는 동적 변환의 발행을 시작하는 것이 일반적인 패턴이다.

8. Component 노드로서의 구성

컴포넌트 아키텍처를 활용하면 동일 프로세스 내에서 정적 변환 발행 노드를 동적으로 로딩할 수 있다.

#include <rclcpp_components/register_node_macro.hpp>

class StaticTFComponent : public rclcpp::Node
{
public:
  explicit StaticTFComponent(const rclcpp::NodeOptions & options)
  : Node("static_tf_component", options)
  {
    static_broadcaster_ =
      std::make_shared<tf2_ros::StaticTransformBroadcaster>(this);

    // 파라미터로부터 정적 변환 발행
    publish_static_transform();
  }

private:
  void publish_static_transform()
  {
    geometry_msgs::msg::TransformStamped t;
    t.header.stamp = this->get_clock()->now();
    t.header.frame_id = "base_link";
    t.child_frame_id = "sensor_link";
    t.transform.translation.z = 0.3;
    t.transform.rotation.w = 1.0;

    static_broadcaster_->sendTransform(t);
  }

  std::shared_ptr<tf2_ros::StaticTransformBroadcaster> static_broadcaster_;
};

RCLCPP_COMPONENTS_REGISTER_NODE(StaticTFComponent)

9. 축적 메커니즘의 동작

StaticTransformBroadcaster의 축적(accumulation) 메커니즘은 내부적으로 다음과 같이 동작한다.

호출 1: sendTransform(A→B)
  → 내부 버퍼: {A→B}
  → 발행: TFMessage{A→B}

호출 2: sendTransform(A→C)
  → 내부 버퍼: {A→B, A→C}
  → 발행: TFMessage{A→B, A→C}

호출 3: sendTransform(A→B')  (A→B 갱신)
  → 내부 버퍼: {A→B', A→C}
  → 발행: TFMessage{A→B', A→C}

동일한 부모-자식 프레임 쌍에 대하여 새로운 변환을 발행하면 기존 값이 갱신된다. 그리고 항상 누적된 전체 변환이 재발행되므로, TRANSIENT_LOCAL QoS에서 늦은 참여 구독자가 최신 상태의 전체 정적 변환을 수신할 수 있다.

10. 주의사항

10.1 std::shared_ptr vs std::unique_ptr

StaticTransformBroadcaster는 내부적으로 축적 버퍼를 유지하므로, 노드의 수명 동안 유효해야 한다. std::shared_ptr 또는 std::unique_ptr 중 어느 것이든 사용 가능하나, 생명주기 노드에서 shared_from_this()를 사용하는 경우에는 std::shared_ptr을 사용하여야 한다.

10.2 타임스탬프의 의미

정적 변환에서 header.stamp 필드는 실질적인 의미를 갖지 않는다. tf2::Buffer는 정적 변환의 타임스탬프와 무관하게 모든 시간에 대하여 유효한 것으로 처리한다. 그러나 관례적으로 발행 시점의 현재 시간을 설정하는 것이 권장된다.

10.3 TransformBroadcaster와의 혼동 방지

동일한 프레임 쌍에 대하여 StaticTransformBroadcasterTransformBroadcaster를 동시에 사용하면 안 된다. 정적 변환은 반드시 StaticTransformBroadcaster를 통하여 /tf_static 토픽으로 발행하여야 하며, 동적 변환은 TransformBroadcaster를 통하여 /tf 토픽으로 발행하여야 한다.

11. 디버깅

11.1 발행된 정적 변환 확인

ros2 topic echo /tf_static

11.2 특정 프레임 간 변환 확인

ros2 run tf2_ros tf2_echo base_link lidar_link

11.3 변환 트리 시각화

ros2 run tf2_tools view_frames

이 명령은 현재 발행 중인 모든 변환을 포함하는 프레임 트리를 PDF 파일로 생성한다.

12. 참고 자료

  • ROS2 공식 문서, “Writing a tf2 static broadcaster (C++)”, https://docs.ros.org/en/humble/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Static-Broadcaster-Cpp.html
  • tf2_ros API 문서, https://docs.ros2.org/latest/api/tf2_ros/
  • REP 103 – Standard Units of Measure and Coordinate Conventions, https://www.ros.org/reps/rep-0103.html
  • REP 105 – Coordinate Frames for Mobile Platforms, https://www.ros.org/reps/rep-0105.html
  • ROS2 Humble Hawksbill