659.26 StaticTransformBroadcaster를 이용한 정적 변환 발행
1. 개요
StaticTransformBroadcaster는 tf2_ros 패키지에서 제공하는 클래스로서, 정적 좌표 변환(static transform)을 /tf_static 토픽으로 발행하는 역할을 담당한다. 정적 변환은 시간에 따라 변화하지 않는 고정된 좌표 프레임 간의 관계를 나타내며, 센서 장착 위치, 로봇 본체 내 고정된 링크 간의 관계 등을 기술하는 데 사용된다. 본 절에서는 StaticTransformBroadcaster의 동작 원리, 사용 시나리오, 그리고 동적 변환 발행과의 차이점을 체계적으로 기술한다.
2. 정적 변환의 개념
2.1 정의
정적 변환(static transform)이란, 로봇 시스템의 운용 기간 동안 일정하게 유지되는 좌표 프레임 간의 기하학적 관계를 의미한다. 수학적으로 표현하면, 정적 변환 T_{static}은 시간 t에 대하여 다음의 조건을 만족한다.
T_{static}(t) = T_{static}(t_0), \quad \forall t \geq t_0
여기서 t_0는 변환이 최초로 정의된 시각이다. 즉, 정적 변환은 한 번 설정된 이후 시간이 경과하여도 변하지 않는다.
2.2 정적 변환의 적용 대상
정적 변환이 적합한 대표적인 상황은 다음과 같다.
| 적용 대상 | 설명 |
|---|---|
| 센서 장착 위치 | LiDAR, 카메라, IMU 등 센서의 로봇 본체 대비 장착 위치 |
| 고정 링크 간 관계 | URDF에서 fixed 조인트로 연결된 링크 간의 관계 |
| 기준 프레임 오프셋 | base_link와 base_footprint 간의 높이 오프셋 |
| 센서 광학 프레임 | 카메라 물리 프레임과 광학(optical) 프레임 간의 관계 |
| 다중 센서 정합 | 동일 로봇에 장착된 복수 센서 간의 외부 보정(extrinsic calibration) 결과 |
3. StaticTransformBroadcaster와 TransformBroadcaster의 차이
StaticTransformBroadcaster와 TransformBroadcaster는 유사한 인터페이스를 제공하나, 내부 동작과 발행 토픽에서 근본적인 차이가 존재한다.
3.1 발행 토픽
TransformBroadcaster:/tf토픽으로 발행StaticTransformBroadcaster:/tf_static토픽으로 발행
3.2 QoS 정책 차이
두 발행자의 핵심적인 차이는 QoS(Quality of Service) 정책에 있다.
| QoS 항목 | /tf (동적) | /tf_static (정적) |
|---|---|---|
| Reliability | RELIABLE | RELIABLE |
| Durability | VOLATILE | TRANSIENT_LOCAL |
| History | KEEP_LAST | KEEP_ALL |
| Depth | 100 | — |
/tf_static 토픽의 QoS 정책에서 가장 중요한 특성은 TRANSIENT_LOCAL 내구성(durability)이다. 이 설정으로 인하여 다음의 동작이 보장된다.
- 늦은 참여(late joining) 지원: 발행자가 메시지를 발행한 이후에 구독을 시작한 노드도, 이전에 발행된 정적 변환을 수신할 수 있다.
- 캐시 독립성:
tf2::Buffer의 캐시 기간(cache duration)이 만료되어도 정적 변환은 유효하다. - 재발행 불필요: 한 번 발행된 정적 변환은 시스템이 종료될 때까지 유효하므로, 주기적 재발행이 필요하지 않다.
3.3 발행 빈도
TransformBroadcaster: 타이머 또는 콜백을 통하여 주기적으로 변환을 발행하여야 한다.StaticTransformBroadcaster: 한 번만 발행하면 충분하다. 이후 변환은 QoS 정책에 의하여 자동으로 전달된다.
4. 내부 동작 메커니즘
4.1 발행 과정
StaticTransformBroadcaster의 내부 동작은 다음의 단계로 구성된다.
- 발행자 생성: 생성자에서
/tf_static토픽에 대한 발행자를TRANSIENT_LOCALQoS로 생성한다. - 변환 축적:
sendTransform()호출 시 전달된 변환을 내부 버퍼에 축적한다. - 일괄 발행: 축적된 모든 정적 변환을 하나의
tf2_msgs/TFMessage메시지로 묶어 발행한다.
이 축적(accumulation) 메커니즘이 중요한 이유는, TRANSIENT_LOCAL QoS에서 늦은 참여 구독자에게 전달되는 메시지가 가장 마지막에 발행된 메시지이기 때문이다. 따라서 매 sendTransform() 호출 시 이전에 발행된 정적 변환을 포함하여 모든 정적 변환을 재발행한다.
4.2 구독자 측 처리
tf2_ros::TransformListener는 /tf_static 토픽을 TRANSIENT_LOCAL QoS로 구독하며, 수신한 정적 변환을 tf2::Buffer에 무한대의 유효 기간으로 저장한다.
[StaticTransformBroadcaster] --(/tf_static)--> [TransformListener] --> [tf2::Buffer]
(cache_time = ∞)
이로 인하여 정적 변환은 tf2::Buffer의 캐시 기간 설정과 무관하게 항상 조회 가능하다.
5. 기본 사용 패턴 (rclcpp)
5.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 StaticTFPublisher : public rclcpp::Node
{
public:
StaticTFPublisher()
: Node("static_tf_publisher")
{
static_tf_broadcaster_ =
std::make_shared<tf2_ros::StaticTransformBroadcaster>(this);
// 센서 장착 위치 발행
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.2;
t.transform.translation.y = 0.0;
t.transform.translation.z = 0.3;
tf2::Quaternion q;
q.setRPY(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_tf_broadcaster_->sendTransform(t);
RCLCPP_INFO(this->get_logger(),
"Published static transform: base_link -> lidar_link");
}
private:
std::shared_ptr<tf2_ros::StaticTransformBroadcaster> static_tf_broadcaster_;
};
위 예제에서 LiDAR 센서가 base_link 프레임으로부터 x축 방향 0.2m, z축 방향 0.3m 위치에 장착되어 있음을 정적 변환으로 발행한다.
타임스탬프(stamp)는 정적 변환에서는 실질적인 의미를 갖지 않는다. tf2::Buffer는 정적 변환을 타임스탬프와 무관하게 항상 유효한 것으로 처리한다.
6. 기본 사용 패턴 (rclpy)
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 StaticTFPublisher(Node):
def __init__(self):
super().__init__('static_tf_publisher')
self.static_tf_broadcaster = StaticTransformBroadcaster(self)
t = TransformStamped()
t.header.stamp = self.get_clock().now().to_msg()
t.header.frame_id = 'base_link'
t.child_frame_id = 'camera_link'
t.transform.translation.x = 0.1
t.transform.translation.y = 0.0
t.transform.translation.z = 0.2
q = quaternion_from_euler(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_tf_broadcaster.sendTransform(t)
self.get_logger().info(
'Published static transform: base_link -> camera_link')
def main(args=None):
rclpy.init(args=args)
node = StaticTFPublisher()
try:
rclpy.spin(node)
except KeyboardInterrupt:
pass
finally:
node.destroy_node()
rclpy.shutdown()
rclpy.spin()을 호출하여 노드를 활성 상태로 유지하는 것이 중요하다. 노드가 종료되면 발행자도 소멸하므로, 늦은 참여 구독자가 정적 변환을 수신할 수 없게 된다.
7. 복수 정적 변환의 발행
하나의 노드에서 여러 정적 변환을 발행하는 경우, 개별적으로 sendTransform()을 호출하거나 리스트로 일괄 전달할 수 있다.
7.1 순차적 개별 발행
// 첫 번째 정적 변환
geometry_msgs::msg::TransformStamped t1;
t1.header.frame_id = "base_link";
t1.child_frame_id = "lidar_link";
// ... 변환 값 설정 ...
static_tf_broadcaster_->sendTransform(t1);
// 두 번째 정적 변환
geometry_msgs::msg::TransformStamped t2;
t2.header.frame_id = "base_link";
t2.child_frame_id = "camera_link";
// ... 변환 값 설정 ...
static_tf_broadcaster_->sendTransform(t2);
내부적으로 축적 메커니즘이 동작하므로, 두 번째 sendTransform() 호출 시 첫 번째 변환도 함께 재발행된다.
7.2 벡터를 이용한 일괄 발행
std::vector<geometry_msgs::msg::TransformStamped> static_transforms;
geometry_msgs::msg::TransformStamped t1;
t1.header.frame_id = "base_link";
t1.child_frame_id = "lidar_link";
// ... 설정 ...
static_transforms.push_back(t1);
geometry_msgs::msg::TransformStamped t2;
t2.header.frame_id = "base_link";
t2.child_frame_id = "camera_link";
// ... 설정 ...
static_transforms.push_back(t2);
geometry_msgs::msg::TransformStamped t3;
t3.header.frame_id = "base_link";
t3.child_frame_id = "imu_link";
// ... 설정 ...
static_transforms.push_back(t3);
static_tf_broadcaster_->sendTransform(static_transforms);
8. 명령행 도구: static_transform_publisher
ROS2는 코드를 작성하지 않고도 정적 변환을 발행할 수 있는 명령행 도구를 제공한다.
8.1 쿼터니언 지정 방식
ros2 run tf2_ros static_transform_publisher \
--x 0.2 --y 0.0 --z 0.3 \
--qx 0.0 --qy 0.0 --qz 0.0 --qw 1.0 \
--frame-id base_link --child-frame-id lidar_link
8.2 오일러 각 지정 방식
ros2 run tf2_ros static_transform_publisher \
--x 0.1 --y 0.0 --z 0.2 \
--roll 0.0 --pitch 0.0 --yaw 1.5708 \
--frame-id base_link --child-frame-id camera_link
8.3 런치 파일에서의 사용
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package='tf2_ros',
executable='static_transform_publisher',
arguments=[
'--x', '0.2', '--y', '0.0', '--z', '0.3',
'--roll', '0.0', '--pitch', '0.0', '--yaw', '0.0',
'--frame-id', 'base_link',
'--child-frame-id', 'lidar_link'
],
),
Node(
package='tf2_ros',
executable='static_transform_publisher',
arguments=[
'--x', '0.1', '--y', '0.0', '--z', '0.2',
'--roll', '-1.5708', '--pitch', '0.0', '--yaw', '-1.5708',
'--frame-id', 'camera_link',
'--child-frame-id', 'camera_optical_link'
],
),
])
9. 정적 변환 발행 시 주의사항
9.1 동적 변환으로 정적 변환을 대체하지 말 것
정적 변환을 TransformBroadcaster를 사용하여 /tf 토픽으로 주기적으로 발행하는 것은 안티패턴(anti-pattern)이다. 이 방식은 다음의 문제를 야기한다.
- 불필요한 네트워크 부하: 변하지 않는 변환을 매 주기 반복하여 전송함으로써 대역폭이 낭비된다.
- 캐시 만료 문제: 발행이 중단되면 캐시 기간 경과 후 변환 조회가 실패한다.
- 의미적 혼동: 시스템 관리자가 해당 변환이 동적으로 변하는 것으로 오해할 수 있다.
9.2 정적 변환의 갱신
정적 변환은 원칙적으로 불변이나, 동일한 부모-자식 프레임 쌍에 대하여 새로운 정적 변환을 발행하면 이전 값이 갱신된다. 이를 활용하여 센서 보정(calibration) 결과를 런타임에 반영할 수 있다.
// 보정 결과를 반영한 갱신
void update_calibration(double x, double y, double z,
double roll, double pitch, double yaw)
{
geometry_msgs::msg::TransformStamped t;
t.header.stamp = this->get_clock()->now();
t.header.frame_id = "base_link";
t.child_frame_id = "camera_link";
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();
static_tf_broadcaster_->sendTransform(t);
}
9.3 노드 생존 유지
StaticTransformBroadcaster를 포함하는 노드는 시스템 운용 기간 동안 활성 상태를 유지하여야 한다. 노드가 종료되면 TRANSIENT_LOCAL QoS에 의한 메시지 캐시도 소멸하므로, 이후에 참여하는 구독자는 정적 변환을 수신할 수 없게 된다.
10. 성능 고려 사항
10.1 메모리 사용량
정적 변환은 tf2::Buffer에 무한대의 유효 기간으로 저장되므로, 정적 변환의 수가 과도하게 많으면 메모리 사용량이 증가한다. 그러나 일반적인 로봇 시스템에서 정적 변환의 수는 수십 개 이내이므로, 실질적인 메모리 부담은 미미하다.
10.2 네트워크 효율성
정적 변환은 한 번만 발행되므로(갱신 시 제외), 동적 변환에 비하여 네트워크 부하가 극히 낮다. 이는 대역폭이 제한된 무선 통신 환경에서 특히 유리하다.
11. 참고 자료
- ROS2 공식 문서, “Writing a tf2 static broadcaster”, 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/
- ROS2 DDS QoS 정책, https://docs.ros.org/en/humble/Concepts/Intermediate/About-Quality-of-Service-Settings.html
- REP 103 – Standard Units of Measure and Coordinate Conventions, https://www.ros.org/reps/rep-0103.html
- ROS2 Humble Hawksbill