659.100 정적 변환 런치 파일 (static_transform_publisher) 설정

1. 개요

static_transform_publishertf2_ros 패키지에 포함된 명령행 도구이자 ROS2 노드로, 고정된 좌표 변환을 /tf_static 토픽으로 발행한다. URDF에 정의되지 않은 프레임 간의 정적 변환을 런치 파일에서 간편하게 설정할 수 있으며, 센서 캘리브레이션 결과의 적용이나 임시 프레임 추가에 활용된다.

2. 사용 방법

2.1 명령행 형식

# XYZ + RPY (6개 인자)
ros2 run tf2_ros static_transform_publisher \
  x y z yaw pitch roll \
  parent_frame child_frame

# XYZ + 쿼터니언 (7개 인자)
ros2 run tf2_ros static_transform_publisher \
  x y z qx qy qz qw \
  parent_frame child_frame

RPY 형식에서 각도의 순서는 yaw, pitch, roll(Z-Y-X)임에 유의하여야 한다. 이는 tf2_ros의 관례이며, URDF의 RPY(roll, pitch, yaw) 순서와 다르다.

2.2 명령행 옵션 형식 (ROS2 Humble 이후)

ros2 run tf2_ros static_transform_publisher \
  --x 0.3 --y 0.0 --z 0.15 \
  --roll 0 --pitch 0 --yaw 0 \
  --frame-id base_link --child-frame-id laser_link

이 형식은 각 인자의 의미가 명시적이므로 오류를 줄일 수 있다.

3. 런치 파일에서의 설정

3.1 Python 런치 파일

from launch import LaunchDescription
from launch_ros.actions import Node


def generate_launch_description():
    return LaunchDescription([
        # 기본 형식 (위치 인자)
        Node(
            package='tf2_ros',
            executable='static_transform_publisher',
            name='base_to_laser_tf',
            arguments=[
                '0.3', '0.0', '0.15',    # x, y, z
                '0', '0', '0',            # yaw, pitch, roll (rad)
                'base_link', 'laser_link'  # parent, child
            ],
        ),

        # 쿼터니언 형식
        Node(
            package='tf2_ros',
            executable='static_transform_publisher',
            name='base_to_camera_tf',
            arguments=[
                '0.2', '0.0', '0.3',              # x, y, z
                '0.0', '0.0', '0.0', '1.0',       # qx, qy, qz, qw
                'base_link', 'camera_link'          # parent, child
            ],
        ),

        # 옵션 형식 (Humble 이후)
        Node(
            package='tf2_ros',
            executable='static_transform_publisher',
            name='camera_to_optical_tf',
            arguments=[
                '--x', '0', '--y', '0', '--z', '0',
                '--roll', '-1.5708', '--pitch', '0', '--yaw', '-1.5708',
                '--frame-id', 'camera_link',
                '--child-frame-id', 'camera_optical_frame',
            ],
        ),
    ])

3.2 XML 런치 파일

<launch>
  <node pkg="tf2_ros" exec="static_transform_publisher"
        name="base_to_laser_tf"
        args="0.3 0.0 0.15 0 0 0 base_link laser_link"/>
</launch>

4. URDF 대비 static_transform_publisher의 선택 기준

기준URDF + robot_state_publisherstatic_transform_publisher
프레임 수다수의 프레임을 체계적으로 관리소수의 독립적 프레임에 적합
유지보수모델 파일 중앙 관리런치 파일에 분산
시각화 지원RViz2에서 로봇 모델 렌더링프레임만 표시, 모델 없음
캘리브레이션 적용URDF 수정 필요런치 파일 인자 변경으로 간편
임시 프레임기존 URDF 변경 필요독립적으로 추가 가능

4.1 권장 사용 시나리오

  • 센서 캘리브레이션 결과 적용: 센서 외부 캘리브레이션(extrinsic calibration) 결과를 런치 파일의 인자로 직접 설정하여 빠른 변경 반영
  • 외부 장비와의 프레임 연결: 로봇과 독립된 외부 장비(예: 고정 카메라, 기지국 마커)의 프레임 추가
  • 디버깅용 임시 프레임: 문제 진단을 위하여 일시적으로 프레임을 추가하는 경우
  • URDF 없는 시스템: URDF를 사용하지 않는 단순 센서 시스템의 프레임 구성

5. 다중 정적 변환 설정

복수의 정적 변환이 필요한 경우, 각 변환을 별도의 static_transform_publisher 노드로 실행한다. 각 노드는 고유한 이름(name)을 가져야 한다.

static_transforms = [
    ('0.3', '0.0', '0.15', '0', '0', '0', 'base_link', 'front_laser_link'),
    ('-0.3', '0.0', '0.15', '3.14159', '0', '0', 'base_link', 'rear_laser_link'),
    ('0.0', '0.0', '0.5', '0', '0', '0', 'base_link', 'top_lidar_link'),
]

nodes = []
for i, args in enumerate(static_transforms):
    nodes.append(Node(
        package='tf2_ros',
        executable='static_transform_publisher',
        name=f'static_tf_{i}',
        arguments=list(args),
    ))

6. 검증

6.1 발행된 변환 확인

# 정적 변환 목록 확인
ros2 topic echo /tf_static --once

# 특정 변환 확인
ros2 run tf2_ros tf2_echo base_link laser_link

6.2 일반적인 오류

오류원인해결
변환이 발행되지 않음인자 개수 불일치 (6/8 또는 7/9)인자 개수 확인
RPY 순서 오류URDF의 RPY(roll-pitch-yaw)와 혼동tf2의 순서는 yaw-pitch-roll
부모-자식 방향 오류parent와 child 프레임이 뒤바뀜프레임 방향 확인

7. 요약

static_transform_publisher는 URDF 없이 정적 좌표 변환을 발행하는 간편한 도구로, 런치 파일의 인자를 통하여 프레임 간의 위치와 자세 관계를 설정한다. 센서 캘리브레이션 결과의 적용, 임시 프레임 추가, 외부 장비 연결 등에 활용되며, URDF 기반 관리와 상호 보완적으로 사용된다.


참고 문헌 및 출처

  • tf2_ros 패키지, https://github.com/ros2/geometry2 (ROS2 Humble 브랜치)
  • ROS2 공식 문서, “Using tf2_ros static_transform_publisher”, https://docs.ros.org/en/humble/Tutorials/Intermediate/Tf2/ (ROS2 Humble Hawksbill)