659.77 tf2_ros에서의 콜백 그룹 구성
1. 개요
ROS2의 콜백 그룹(callback group)은 노드 내의 콜백 함수들의 실행을 조직화하고 동시성(concurrency)을 제어하는 메커니즘이다. tf2_ros의 TransformListener는 /tf 및 /tf_static 토픽의 구독 콜백을 처리해야 하므로, 콜백 그룹의 구성이 시스템의 동작 안정성과 성능에 직접적인 영향을 미친다. 특히, 사용자 콜백 내에서 lookupTransform()을 호출하는 패턴에서 데드락(deadlock)을 방지하기 위해서는 콜백 그룹의 올바른 구성이 필수적이다.
2. ROS2 콜백 그룹의 기본 개념
2.1 콜백 그룹 유형
ROS2는 두 가지 유형의 콜백 그룹을 제공한다.
| 유형 | 클래스 | 특성 |
|---|---|---|
| 상호 배제 (MutuallyExclusive) | rclcpp::callback_group::MutuallyExclusive | 그룹 내 콜백이 동시에 실행되지 않음 |
| 재진입 가능 (Reentrant) | rclcpp::callback_group::Reentrant | 그룹 내 콜백이 동시에 실행될 수 있음 |
기본적으로 노드의 모든 콜백(구독, 타이머, 서비스 등)은 하나의 기본 MutuallyExclusive 콜백 그룹에 소속된다.
2.2 Executor와의 관계
- SingleThreadedExecutor: 하나의 스레드에서 모든 콜백을 순차적으로 처리한다. 동일 콜백 그룹의 콜백이 동시에 실행될 수 없으므로, 콜백 내에서 자체 토픽의 구독 콜백을 대기하면 데드락이 발생한다.
- MultiThreadedExecutor: 다수의 스레드에서 콜백을 병렬 처리한다. 서로 다른 콜백 그룹에 소속된 콜백은 동시에 실행될 수 있다.
3. TransformListener의 콜백 그룹 동작
3.1 spin_thread = true (기본)
기본 설정에서 TransformListener는 내부적으로 전용 콜백 그룹과 전용 SingleThreadedExecutor를 생성하고, 별도의 스레드에서 이 Executor를 실행한다.
사용자 스레드 (메인 Executor):
└── 사용자 콜백 (기본 콜백 그룹)
└── lookupTransform() 호출 → Buffer에서 데이터 조회
TF2 전용 스레드 (내부 Executor):
└── TF2 콜백 그룹 (MutuallyExclusive)
├── /tf 구독 콜백 → Buffer에 변환 저장
└── /tf_static 구독 콜백 → Buffer에 정적 변환 저장
이 구성에서는 사용자 콜백과 TF2 콜백이 서로 다른 스레드에서 실행되므로, 사용자 콜백 내에서 lookupTransform()을 호출해도 TF2 콜백의 실행이 차단되지 않는다.
3.2 spin_thread = false
전용 스레드를 사용하지 않는 경우, TF2 구독 콜백은 노드의 기본 콜백 그룹 또는 사용자가 지정한 콜백 그룹에서 실행된다.
4. 데드락 시나리오
4.1 SingleThreadedExecutor + 공유 콜백 그룹
다음 구성에서 데드락이 발생할 수 있다.
// 위험한 구성
auto tf_buffer = std::make_shared<tf2_ros::Buffer>(node->get_clock());
auto tf_listener = std::make_shared<tf2_ros::TransformListener>(
*tf_buffer, node, false); // spin_thread = false
// 타이머 콜백에서 lookupTransform 호출
auto timer = node->create_wall_timer(
std::chrono::milliseconds(100),
[&tf_buffer]() {
auto transform = tf_buffer->lookupTransform(
"map", "base_link",
rclcpp::Time(0),
rclcpp::Duration::from_seconds(1.0)); // 1초 대기
// 이 대기 중에 /tf 콜백이 실행되어야 하지만,
// SingleThreadedExecutor에서는 현재 콜백이 완료될 때까지
// 다른 콜백이 실행되지 않으므로 데드락 발생
});
rclcpp::spin(node); // SingleThreadedExecutor
4.2 데드락 발생 메커니즘
- 타이머 콜백이 실행된다
lookupTransform()이 타임아웃 내에서 변환을 대기한다/tf콜백이 실행되어야 새로운 변환 데이터가 Buffer에 저장된다- 그러나
SingleThreadedExecutor에서는 현재 실행 중인 타이머 콜백이 완료될 때까지/tf콜백이 실행될 수 없다 - 결과: 타이머 콜백은 변환을 대기하고,
/tf콜백은 타이머 콜백의 완료를 대기하는 순환 대기(circular wait) 발생
5. 안전한 콜백 그룹 구성
5.1 방법 1: 기본 설정 사용 (spin_thread = true)
가장 간단하고 권장되는 방법이다.
auto tf_buffer = std::make_shared<tf2_ros::Buffer>(node->get_clock());
auto tf_listener = std::make_shared<tf2_ros::TransformListener>(
*tf_buffer); // spin_thread = true (기본)
5.2 방법 2: 별도 콜백 그룹 + MultiThreadedExecutor
// 사용자 콜백 그룹
auto user_cb_group = node->create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive);
// TF2 전용 콜백 그룹
auto tf_cb_group = node->create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive);
auto tf_buffer = std::make_shared<tf2_ros::Buffer>(node->get_clock());
// TransformListener에 전용 콜백 그룹 지정
// (고급 생성자 또는 구독 옵션을 통해)
// MultiThreadedExecutor 사용
rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(node);
executor.spin();
5.3 방법 3: 타임아웃 없는 조회
lookupTransform()에서 타임아웃을 사용하지 않으면 대기가 발생하지 않으므로 데드락이 방지된다.
try {
auto transform = tf_buffer->lookupTransform(
"map", "base_link",
tf2::TimePointZero); // 타임아웃 없이 최신 변환 조회
} catch (const tf2::TransformException & ex) {
// 변환이 아직 가용하지 않은 경우 처리
}
5.4 방법 4: canTransform()으로 사전 확인
if (tf_buffer->canTransform("map", "base_link", tf2::TimePointZero)) {
auto transform = tf_buffer->lookupTransform(
"map", "base_link", tf2::TimePointZero);
// 변환 사용
}
6. ComponentNode에서의 구성
6.1 Composable Node에서의 고려사항
ROS2의 컴포넌트 노드(component node)에서는 단일 프로세스 내에 다수의 노드가 공존한다. 이 환경에서 각 노드가 자체 TransformListener를 갖는 경우, 전용 스레드의 수가 노드 수에 비례하여 증가한다. 리소스 효율을 위해 공유 Buffer와 단일 TransformListener를 사용하거나, spin_thread = false와 MultiThreadedExecutor를 조합하여 스레드 수를 제한할 수 있다.
7. Python에서의 콜백 그룹
Python에서도 동일한 원칙이 적용된다.
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup
from rclpy.executors import MultiThreadedExecutor
from tf2_ros import Buffer, TransformListener
# TF2 전용 콜백 그룹
tf_cb_group = MutuallyExclusiveCallbackGroup()
tf_buffer = Buffer()
tf_listener = TransformListener(
tf_buffer, node,
spin_thread=True) # 기본: True
# 또는 MultiThreadedExecutor와 함께 사용
executor = MultiThreadedExecutor()
executor.add_node(node)
executor.spin()
8. 참고 문헌
- Open Robotics, “Using callback groups,” ROS 2 Documentation, https://docs.ros.org/en/rolling/How-To-Guides/Using-callback-groups.html
- Open Robotics, “tf2_ros: TransformListener,” ROS 2 Source Code, https://github.com/ros2/geometry2
- Open Robotics, “Executors,” ROS 2 Documentation, https://docs.ros.org/en/rolling/Concepts/Intermediate/About-Executors.html
버전: 2026-03-26