659.28 StaticTransformBroadcaster의 rclpy 사용법

1. 개요

StaticTransformBroadcastertf2_ros 패키지에서 제공하는 클래스로서, Python 클라이언트 라이브러리 rclpy를 통하여 정적 좌표 변환(static transform)을 /tf_static 토픽으로 발행하는 역할을 담당한다. 정적 변환은 시간에 따라 변하지 않는 고정된 프레임 간의 관계를 나타내며, TRANSIENT_LOCAL QoS 정책에 의하여 한 번 발행되면 늦은 참여(late joining) 구독자도 수신할 수 있다. 본 절에서는 StaticTransformBroadcasterrclpy 기반 사용법을 상세히 기술한다.

2. 필수 모듈 및 의존성

2.1 Python 임포트

import rclpy
from rclpy.node import Node
from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster
from geometry_msgs.msg import TransformStamped

tf2_ros.static_transform_broadcaster 모듈에서 StaticTransformBroadcaster 클래스를 임포트한다. 쿼터니언 변환을 위해서는 추가 모듈이 필요하다.

from tf_transformations import quaternion_from_euler

또는 scipy를 사용할 수 있다.

from scipy.spatial.transform import Rotation
import numpy as np

2.2 package.xml 의존성

<exec_depend>rclpy</exec_depend>
<exec_depend>tf2_ros_py</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>tf_transformations</exec_depend>

2.3 setup.py 설정

entry_points={
    'console_scripts': [
        'static_tf_publisher = my_robot_tf.static_tf_publisher:main',
    ],
},

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

3.1 생성자

StaticTransformBroadcaster(node, qos=QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL))

node 인자는 rclpy.node.Node 인스턴스이다. QoS 프로파일은 기본적으로 TRANSIENT_LOCAL 내구성을 사용하며, 일반적으로 기본값을 그대로 사용한다.

3.2 sendTransform 메서드

sendTransform(transform)

transform 인자는 단일 TransformStamped 메시지 또는 TransformStamped 메시지의 리스트이다. 내부적으로 이전에 발행한 모든 정적 변환을 축적하며, 매 호출 시 축적된 전체 변환을 재발행한다.

4. 기본 사용 패턴

4.1 생성자에서의 일회 발행

import rclpy
from rclpy.node import Node
from tf2_ros.static_transform_broadcaster import StaticTransformBroadcaster
from geometry_msgs.msg import TransformStamped
from tf_transformations import quaternion_from_euler


class StaticFramePublisher(Node):
    def __init__(self):
        super().__init__('static_frame_publisher')
        self.static_broadcaster = StaticTransformBroadcaster(self)

        self.publish_static_transform()

    def publish_static_transform(self):
        t = TransformStamped()

        t.header.stamp = self.get_clock().now().to_msg()
        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

        q = quaternion_from_euler(0.0, 0.0, 0.0)
        t.transform.rotation.x = q[0]
        t.transform.rotation.y = q[1]
        t.transform.rotation.z = q[2]
        t.transform.rotation.w = q[3]

        self.static_broadcaster.sendTransform(t)
        self.get_logger().info(
            'Published static transform: base_link -> lidar_link')


def main(args=None):
    rclpy.init(args=args)
    node = StaticFramePublisher()
    try:
        rclpy.spin(node)
    except KeyboardInterrupt:
        pass
    finally:
        node.destroy_node()
        rclpy.shutdown()


if __name__ == '__main__':
    main()

rclpy.spin()을 호출하여 노드를 활성 상태로 유지하는 것이 중요하다. 노드가 종료되면 발행자가 소멸하여 TRANSIENT_LOCAL 캐시도 사라지므로, 이후 참여하는 구독자가 정적 변환을 수신할 수 없게 된다.

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

5.1 헬퍼 함수를 이용한 일괄 발행

import math


class MultiSensorStaticTF(Node):
    def __init__(self):
        super().__init__('multi_sensor_static_tf')
        self.static_broadcaster = StaticTransformBroadcaster(self)

        self.publish_all_sensor_frames()

    def create_static_transform(self, parent_frame, child_frame,
                                  x, y, z, roll, pitch, yaw):
        t = TransformStamped()
        t.header.stamp = self.get_clock().now().to_msg()
        t.header.frame_id = parent_frame
        t.child_frame_id = child_frame

        t.transform.translation.x = float(x)
        t.transform.translation.y = float(y)
        t.transform.translation.z = float(z)

        q = quaternion_from_euler(roll, pitch, yaw)
        t.transform.rotation.x = q[0]
        t.transform.rotation.y = q[1]
        t.transform.rotation.z = q[2]
        t.transform.rotation.w = q[3]

        return t

    def publish_all_sensor_frames(self):
        transforms = []

        # LiDAR 센서
        transforms.append(
            self.create_static_transform(
                'base_link', 'lidar_link',
                0.20, 0.00, 0.35, 0.0, 0.0, 0.0))

        # 전방 카메라
        transforms.append(
            self.create_static_transform(
                'base_link', 'front_camera_link',
                0.25, 0.00, 0.20, 0.0, 0.0, 0.0))

        # 카메라 광학 프레임
        transforms.append(
            self.create_static_transform(
                'front_camera_link', 'front_camera_optical',
                0.0, 0.0, 0.0,
                -math.pi / 2.0, 0.0, -math.pi / 2.0))

        # IMU 센서
        transforms.append(
            self.create_static_transform(
                'base_link', 'imu_link',
                0.10, 0.00, 0.15, 0.0, 0.0, 0.0))

        # GPS 안테나
        transforms.append(
            self.create_static_transform(
                'base_link', 'gps_link',
                -0.05, 0.00, 0.50, 0.0, 0.0, 0.0))

        self.static_broadcaster.sendTransform(transforms)
        self.get_logger().info(
            f'Published {len(transforms)} static transforms')

create_static_transform() 헬퍼 메서드를 정의하여 반복적인 코드를 최소화하고 가독성을 향상시킨다.

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

ROS2 파라미터를 활용하여 센서 장착 위치를 런타임에 구성하는 패턴이다.

class ParameterizedStaticTF(Node):
    def __init__(self):
        super().__init__('parameterized_static_tf')

        self.declare_parameter('parent_frame', 'base_link')
        self.declare_parameter('child_frame', 'sensor_link')
        self.declare_parameter('x', 0.0)
        self.declare_parameter('y', 0.0)
        self.declare_parameter('z', 0.0)
        self.declare_parameter('roll', 0.0)
        self.declare_parameter('pitch', 0.0)
        self.declare_parameter('yaw', 0.0)

        self.static_broadcaster = StaticTransformBroadcaster(self)
        self.publish_from_parameters()

    def publish_from_parameters(self):
        t = TransformStamped()
        t.header.stamp = self.get_clock().now().to_msg()
        t.header.frame_id = \
            self.get_parameter('parent_frame').value
        t.child_frame_id = \
            self.get_parameter('child_frame').value

        t.transform.translation.x = \
            self.get_parameter('x').value
        t.transform.translation.y = \
            self.get_parameter('y').value
        t.transform.translation.z = \
            self.get_parameter('z').value

        q = quaternion_from_euler(
            self.get_parameter('roll').value,
            self.get_parameter('pitch').value,
            self.get_parameter('yaw').value)
        t.transform.rotation.x = q[0]
        t.transform.rotation.y = q[1]
        t.transform.rotation.z = q[2]
        t.transform.rotation.w = q[3]

        self.static_broadcaster.sendTransform(t)

6.1 런치 파일에서의 파라미터 설정

from launch import LaunchDescription
from launch_ros.actions import Node


def generate_launch_description():
    return LaunchDescription([
        # LiDAR 정적 변환
        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,
            }],
        ),
        # 카메라 정적 변환
        Node(
            package='my_robot_tf',
            executable='parameterized_static_tf',
            name='camera_static_tf',
            parameters=[{
                'parent_frame': 'base_link',
                'child_frame': 'camera_link',
                'x': 0.25,
                'y': 0.00,
                'z': 0.20,
                'yaw': 0.0,
            }],
        ),
    ])

7. YAML 파일 기반 구성

복수의 센서 보정(calibration) 결과를 YAML 파일에서 읽어 발행하는 고급 패턴이다.

import yaml


class YAMLStaticTFPublisher(Node):
    def __init__(self):
        super().__init__('yaml_static_tf_publisher')
        self.declare_parameter('calibration_file', '')

        self.static_broadcaster = StaticTransformBroadcaster(self)

        calibration_file = \
            self.get_parameter('calibration_file').value

        if calibration_file:
            self.load_and_publish(calibration_file)
        else:
            self.get_logger().warn(
                'No calibration file specified')

    def load_and_publish(self, filepath):
        with open(filepath, 'r') as f:
            config = yaml.safe_load(f)

        transforms = []
        for sensor in config.get('sensors', []):
            t = TransformStamped()
            t.header.stamp = self.get_clock().now().to_msg()
            t.header.frame_id = sensor['parent_frame']
            t.child_frame_id = sensor['child_frame']

            t.transform.translation.x = float(sensor['x'])
            t.transform.translation.y = float(sensor['y'])
            t.transform.translation.z = float(sensor['z'])

            q = quaternion_from_euler(
                float(sensor.get('roll', 0.0)),
                float(sensor.get('pitch', 0.0)),
                float(sensor.get('yaw', 0.0)))
            t.transform.rotation.x = q[0]
            t.transform.rotation.y = q[1]
            t.transform.rotation.z = q[2]
            t.transform.rotation.w = q[3]

            transforms.append(t)

        self.static_broadcaster.sendTransform(transforms)
        self.get_logger().info(
            f'Published {len(transforms)} transforms from {filepath}')

YAML 보정 파일의 형식은 다음과 같다.

sensors:
  - 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
  - parent_frame: base_link
    child_frame: camera_link
    x: 0.25
    y: 0.00
    z: 0.20
    roll: 0.0
    pitch: -0.1
    yaw: 0.0

8. 축적 메커니즘

StaticTransformBroadcaster는 내부적으로 발행된 모든 정적 변환을 축적한다.

# 첫 번째 호출
self.static_broadcaster.sendTransform(transform_a_to_b)
# 내부 버퍼: {A→B}, 발행: TFMessage{A→B}

# 두 번째 호출
self.static_broadcaster.sendTransform(transform_a_to_c)
# 내부 버퍼: {A→B, A→C}, 발행: TFMessage{A→B, A→C}

동일한 부모-자식 프레임 쌍에 대한 새로운 변환이 전달되면 기존 값이 갱신된다. 매 sendTransform() 호출 시 축적된 전체 변환이 재발행되므로, TRANSIENT_LOCAL QoS에서 늦은 참여 구독자가 최신 전체 상태를 수신할 수 있다.

9. rclcpp 구현과의 차이점

항목rclcpp (C++)rclpy (Python)
임포트 경로tf2_ros/static_transform_broadcaster.htf2_ros.static_transform_broadcaster
생성자 인자this 또는 shared_from_this()self
타임스탬프this->get_clock()->now()self.get_clock().now().to_msg()
쿼터니언 생성tf2::Quaternion::setRPY()quaternion_from_euler()
메모리 관리std::shared_ptr / std::unique_ptrPython 가비지 컬렉션
복수 변환 컨테이너std::vectorPython 리스트

Python 구현에서 .to_msg() 호출이 필수적이라는 점에 유의한다.

10. 주의사항

10.1 노드 생존 유지

정적 변환 발행 후에도 노드를 rclpy.spin()으로 유지하여야 한다. 노드가 종료되면 TRANSIENT_LOCAL 캐시가 소멸한다.

10.2 TransformBroadcaster와의 구분

정적 변환은 반드시 StaticTransformBroadcaster를 통하여 /tf_static으로 발행하여야 한다. TransformBroadcaster를 사용하여 /tf로 정적 변환을 주기적으로 발행하는 것은 불필요한 네트워크 부하를 발생시키는 안티패턴이다.

10.3 타임스탬프

정적 변환에서 header.stamp는 실질적인 의미를 갖지 않는다. tf2_ros.Buffer는 정적 변환을 모든 시간에 대하여 유효한 것으로 처리한다. 관례적으로 발행 시점의 현재 시간을 설정한다.

10.4 프레임 ID 유효성

frame_idchild_frame_id는 빈 문자열이어서는 안 된다. 빈 프레임 ID는 변환 트리의 무결성을 훼손한다.

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

12. 참고 자료

  • ROS2 공식 문서, “Writing a tf2 static broadcaster (Python)”, https://docs.ros.org/en/humble/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Static-Broadcaster-Py.html
  • tf2_ros API 문서, https://docs.ros2.org/latest/api/tf2_ros/
  • tf_transformations 패키지, https://github.com/DLu/tf_transformations
  • REP 103 – Standard Units of Measure and Coordinate Conventions, https://www.ros.org/reps/rep-0103.html
  • ROS2 Humble Hawksbill