659.13 동적 변환 (Dynamic Transform)의 정의와 특성
1. 동적 변환의 정의
동적 변환(dynamic transform)은 시간에 따라 변하는 좌표 프레임 간의 공간적 관계를 정의하는 변환이다. 수학적으로, 동적 변환 {}^{P}T_{C}(t)는 시간 t의 함수이다.
\frac{d}{dt} {}^{P}T_{C}(t) \neq 0
즉, 부모 프레임 \{P\}에서 관측한 자식 프레임 \{C\}의 위치와 방향이 시간에 따라 변화한다.
2. 동적 변환의 물리적 의미
동적 변환은 물리적으로 상대적 운동이 존재하는 두 좌표 프레임 간의 관계를 나타낸다.
2.1 로봇의 운동
이동 로봇이 환경 내에서 이동할 때, 로봇 본체 프레임과 환경 프레임 간의 관계는 시간에 따라 변한다.
| 변환 | 발행 소스 | 변화 원인 |
|---|---|---|
odom → base_link | 오도메트리 노드 | 로봇의 주행에 의한 위치·방향 변화 |
map → odom | 위치 추정 노드 (AMCL, SLAM) | 위치 추정 보정에 의한 오프셋 갱신 |
2.2 관절 운동
매니퓰레이터의 관절이 회전하거나 직선 운동을 할 때, 인접한 링크 프레임 간의 관계가 동적으로 변한다. 회전 관절(revolute joint)의 경우 관절 각도 \theta(t)에 따라 변하며, 직선 관절(prismatic joint)의 경우 관절 변위 d(t)에 따라 변한다.
{}^{P}T_{C}(t) = T_{\text{fixed}} \cdot \begin{cases} R_{\hat{u}}(\theta(t)) & \text{회전 관절} \\ D_{\hat{u}}(d(t)) & \text{직선 관절} \end{cases}
여기서 T_{\text{fixed}}는 관절의 고정 오프셋, R_{\hat{u}}(\theta)는 관절 축 \hat{u} 주위의 회전, D_{\hat{u}}(d)는 관절 축 방향의 병진이다.
2.3 환경 내 이동 물체
로봇이 추적하는 외부 물체의 위치가 시간에 따라 변하는 경우에도 동적 변환이 사용된다.
3. TF2에서의 동적 변환 관리
3.1 /tf 토픽
동적 변환은 /tf 토픽을 통해 주기적으로 발행된다. /tf 토픽의 QoS 설정은 다음과 같다.
| QoS 설정 | 값 | 설명 |
|---|---|---|
| Reliability | RELIABLE | 메시지 전달 보장 |
| Durability | VOLATILE | 늦게 참여하는 구독자에게는 이전 메시지 전달 안 함 |
| History | KEEP_LAST(100) | 최근 100개 메시지 유지 |
VOLATILE durability 설정은 정적 변환의 TRANSIENT_LOCAL과 대비되는 특성으로, 동적 변환은 지속적으로 갱신되므로 과거 데이터의 보존이 필요하지 않다.
3.2 TransformBroadcaster
동적 변환은 tf2_ros::TransformBroadcaster 클래스를 통해 발행한다.
// C++ 예시
auto broadcaster = std::make_shared<tf2_ros::TransformBroadcaster>(node);
geometry_msgs::msg::TransformStamped transform;
transform.header.stamp = node->get_clock()->now();
transform.header.frame_id = "odom";
transform.child_frame_id = "base_link";
transform.transform.translation.x = current_x;
transform.transform.translation.y = current_y;
transform.transform.translation.z = 0.0;
transform.transform.rotation = current_orientation;
broadcaster->sendTransform(transform);
3.3 TimeCache에서의 저장
BufferCore 내부에서 동적 변환은 TimeCache에 저장된다. TimeCache는 각 프레임 쌍에 대해 시간순으로 정렬된 변환 이력을 유지하며, 다음과 같은 특성을 가진다.
| 특성 | 설명 |
|---|---|
| 시간순 정렬 | 변환 데이터가 타임스탬프 순서로 저장된다 |
| 캐시 기간 제한 | 기본 10초 범위의 이력만 유지하며, 오래된 데이터는 자동 삭제된다 |
| 시간 보간 지원 | 캐시된 데이터 사이의 임의 시점에 대한 변환을 보간으로 계산한다 |
4. 동적 변환의 특성
4.1 시간 의존성
동적 변환은 조회 시간에 따라 다른 값을 반환한다. lookupTransform(target, source, time)에서 time 인자에 따라 반환되는 변환이 달라지며, 이를 통해 과거 특정 시점의 좌표 관계를 정확하게 조회할 수 있다.
4.2 주기적 발행 필요
동적 변환은 변화를 반영하기 위해 주기적으로 재발행되어야 한다. 발행 주기는 변환의 변화 속도와 시스템의 시간적 정밀도 요구사항에 따라 결정된다.
| 애플리케이션 | 일반적 발행 주기 | 근거 |
|---|---|---|
| 오도메트리 (이동 로봇) | 20~100 Hz | 로봇 주행 속도에 따른 위치 갱신 |
| 관절 상태 (매니퓰레이터) | 50~500 Hz | 제어 루프 주기와 일치 |
| 글로벌 위치 추정 | 1~10 Hz | 위치 추정 알고리즘의 갱신 주기 |
| 저속 팬틸트 (pan-tilt) | 10~50 Hz | 기계적 움직임의 속도 |
4.3 보간 가능성
동적 변환은 TimeCache에 저장된 데이터를 기반으로 시간 보간이 수행된다. 요청된 시간 t가 두 캐시 항목의 시간 t_1과 t_2 사이에 위치할 때 (t_1 < t < t_2), TF2는 보간 계수 \alpha를 계산한다.
\alpha = \frac{t - t_1}{t_2 - t_1}, \quad 0 \leq \alpha \leq 1
병진 성분은 선형 보간(LERP)으로:
t(\alpha) = (1 - \alpha) \cdot t_1 + \alpha \cdot t_2
회전 성분은 구면 선형 보간(SLERP)으로 계산된다:
q(\alpha) = \text{SLERP}(q_1, q_2, \alpha)
4.4 외삽 제한
TF2는 기본적으로 캐시된 데이터의 시간 범위를 벗어나는 외삽(extrapolation)을 허용하지 않는다. 요청된 시간이 캐시의 최신 데이터보다 미래이거나 최고(oldest) 데이터보다 과거인 경우, ExtrapolationException이 발생한다.
4.5 캐시 기간의 영향
동적 변환은 BufferCore의 캐시 기간(cache duration) 설정에 영향을 받는다. 캐시 기간을 초과한 과거 데이터는 자동으로 삭제되므로, 캐시 기간보다 오래된 시간의 변환을 조회할 수 없다.
캐시 기간의 기본값은 10초이며, Buffer 생성 시 다음과 같이 변경할 수 있다.
// 캐시 기간을 30초로 설정
auto buffer = std::make_shared<tf2_ros::Buffer>(
node->get_clock(),
tf2::Duration(std::chrono::seconds(30))
);
5. 동적 변환 발행 시 주의사항
5.1 타임스탬프의 정확성
동적 변환의 header.stamp은 해당 변환이 유효한 시점을 정확하게 나타내야 한다. 센서 데이터로부터 계산된 변환의 경우, 센서 측정 시점의 타임스탬프를 사용해야 하며, 변환 발행 시점의 타임스탬프를 사용하면 시간 지연(latency)에 의한 오차가 발생할 수 있다.
5.2 단조 증가하는 타임스탬프
동일한 프레임 쌍에 대해 발행되는 변환의 타임스탬프는 단조 증가(monotonically increasing)해야 한다. 과거 시간의 타임스탬프를 가진 변환이 나중에 발행되면, TF2는 이를 무시하고 경고 메시지를 출력한다.
5.3 발행 지연 최소화
변환 데이터의 발행 지연(publishing latency)은 시스템의 시간적 정확도에 직접적인 영향을 미친다. 변환은 가능한 한 계산 직후 즉시 발행해야 하며, 불필요한 처리 지연을 피해야 한다.
참고 문헌 및 출처:
- 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.
- Craig, J.J., Introduction to Robotics: Mechanics and Control, 4th ed., Pearson, 2018.