659.14 정적 변환과 동적 변환의 사용 기준

1. 선택 기준 개요

TF2에서 특정 좌표 프레임 간의 변환을 정적 변환(static transform)으로 발행할지, 동적 변환(dynamic transform)으로 발행할지의 결정은 시스템의 성능, 정확성, 그리고 유지보수성에 직접적인 영향을 미친다. 올바른 선택을 위해서는 해당 변환의 물리적 특성과 시스템 요구사항을 정확하게 이해해야 한다.

2. 정적 변환과 동적 변환의 비교

두 유형의 변환은 다음과 같은 측면에서 차이를 가진다.

특성정적 변환동적 변환
시간 의존성시간에 무관 (상수)시간에 따라 변화
발행 토픽/tf_static/tf
발행 빈도한 번만 발행주기적으로 반복 발행
QoS DurabilityTRANSIENT_LOCALVOLATILE
캐시 구조StaticCache (단일 항목)TimeCache (시간대별 이력)
캐시 기간 영향영향 없음 (영구 유지)캐시 기간 초과 시 삭제
시간 보간불필요 (항상 동일 값)필요 (시간에 따른 값 보간)
네트워크 부하최소 (한 번 발행)발행 빈도에 비례
메모리 사용최소 (단일 항목)캐시 기간 × 발행 빈도에 비례
발행 클래스StaticTransformBroadcasterTransformBroadcaster

3. 정적 변환을 사용해야 하는 경우

3.1 판단 기준: 물리적 고정성

정적 변환을 사용하는 핵심 기준은 두 프레임 간의 공간적 관계가 시스템 동작 기간 전체에 걸쳐 변하지 않는 것이다.

3.2 대표적 사용 사례

사용 사례설명
센서 장착 위치로봇 본체에 볼트로 고정된 LiDAR, 카메라, IMU 등의 장착 위치와 방향
카메라 광학 프레임camera_link에서 camera_optical_frame으로의 고정 회전 변환
고정 구조물 간 관계매니퓰레이터 기저와 로봇 본체 간의 고정 오프셋
지면 투영 프레임base_link에서 base_footprint으로의 z축 오프셋 (평탄 지면 가정 시)
고정 URDF 관절<joint type="fixed">로 정의된 관절의 변환

3.3 코드 예시

// 센서 장착 위치를 정적 변환으로 발행
auto static_broadcaster = std::make_shared<tf2_ros::StaticTransformBroadcaster>(node);

geometry_msgs::msg::TransformStamped t;
t.header.stamp = node->get_clock()->now();
t.header.frame_id = "base_link";
t.child_frame_id = "laser_frame";
t.transform.translation.x = 0.3;
t.transform.translation.y = 0.0;
t.transform.translation.z = 0.15;
t.transform.rotation.w = 1.0;  // 회전 없음

static_broadcaster->sendTransform(t);

4. 동적 변환을 사용해야 하는 경우

4.1 판단 기준: 시간적 변동성

동적 변환을 사용하는 핵심 기준은 두 프레임 간의 공간적 관계가 시간에 따라 변하는 것이다.

4.2 대표적 사용 사례

사용 사례설명발행 빈도
오도메트리odom → base_link 변환50~100 Hz
글로벌 위치 추정map → odom 변환1~10 Hz
매니퓰레이터 관절link_i → link_{i+1} 변환제어 루프 주기
팬틸트 메커니즘카메라 팬틸트의 각도10~50 Hz
추적 대상 물체로봇이 추적하는 외부 물체의 위치인식 주기

4.3 코드 예시

// 오도메트리를 동적 변환으로 발행
auto broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(node);

// 제어 루프 콜백에서 매번 호출
geometry_msgs::msg::TransformStamped t;
t.header.stamp = current_time;
t.header.frame_id = "odom";
t.child_frame_id = "base_link";
t.transform.translation.x = odom_x;
t.transform.translation.y = odom_y;
t.transform.translation.z = 0.0;
t.transform.rotation = odom_orientation;

broadcaster->sendTransform(t);

5. 경계 사례의 판단

5.1 드물게 변하는 변환

어떤 변환이 대부분의 시간 동안 고정되어 있지만, 특정 이벤트 발생 시에만 극히 드물게 변하는 경우가 있다. 예를 들어, 캘리브레이션 갱신에 의해 센서 위치가 미세하게 조정되는 경우이다.

권장 방법: 이런 경우에는 정적 변환을 사용하되, 변경이 필요할 때 새로운 정적 변환을 재발행하는 방식이 적절하다. StaticTransformBroadcastersendTransform()을 다시 호출하면, 동일한 프레임 쌍에 대한 기존 정적 변환이 갱신된다.

5.2 매우 느리게 변하는 변환

매우 느린 속도로 변하는 변환(예: 온도에 의한 기계적 열팽창)은 이론적으로 동적 변환이지만, 변화 속도가 무시할 수 있을 만큼 느린 경우 정적 변환으로 처리할 수 있다.

판단 기준: 변환의 변화량이 시스템의 허용 오차 이내라면 정적 변환으로, 허용 오차를 초과하면 동적 변환으로 처리한다.

5.3 base_link → base_footprint 변환

base_link → base_footprint 변환은 시스템 설계에 따라 정적 또는 동적 변환이 될 수 있다.

조건변환 유형근거
평탄 지면 가정정적 변환로봇의 roll, pitch가 변하지 않음
비평탄 지형동적 변환IMU 데이터에 따라 roll, pitch가 변함

6. 잘못된 선택의 영향

6.1 동적 변환을 정적 변환으로 잘못 분류한 경우

시간에 따라 변하는 변환을 정적 변환으로 발행하면, 변화가 반영되지 않아 좌표 변환 결과가 부정확해진다. 예를 들어, 매니퓰레이터의 관절 변환을 정적으로 발행하면, 로봇 팔이 움직여도 TF2는 초기 위치로 고정된 변환을 반환한다.

6.2 정적 변환을 동적 변환으로 잘못 분류한 경우

시간에 따라 변하지 않는 변환을 동적으로 발행하면, 기능적으로는 올바르게 작동하지만 다음과 같은 비효율이 발생한다.

  1. 불필요한 네트워크 트래픽: 변하지 않는 데이터를 반복적으로 전송하여 대역폭을 낭비한다.
  2. 불필요한 메모리 사용: TimeCache에 동일한 데이터가 반복 저장된다.
  3. 시작 순서 의존성: VOLATILE durability로 인해, 발행자보다 늦게 시작된 노드는 첫 번째 발행까지 변환을 사용할 수 없다.
  4. 캐시 기간 만료 위험: 발행이 일시적으로 중단되면(예: 발행 노드의 과부하), 캐시 기간 만료로 인해 변환을 조회할 수 없게 된다.

7. 의사 결정 흐름도

변환 유형의 선택은 다음과 같은 의사 결정 과정을 따른다.

  1. 질문: 두 프레임 간의 공간적 관계가 시스템 실행 중 변하는가?
  • 아니오정적 변환 사용
  • → 2단계로 진행
  1. 질문: 변화 속도가 시스템의 허용 오차를 초과하는가?
  • 아니오정적 변환 사용 (근사적 정적 처리)
  • 동적 변환 사용
  1. 동적 변환인 경우: 적절한 발행 주기를 결정한다.

참고 문헌 및 출처:

  • Open Robotics, “tf2 — ROS 2 Documentation,” ROS 2 Jazzy Jalisco, 2024.
  • Foote, T., “tf: The transform library,” 2013 IEEE Conference on Technologies for Practical Robot Applications (TePRA), pp. 1-6, 2013.
  • REP 105, “Coordinate Frames for Mobile Platforms,” Open Robotics, 2010.