659.33 tf2::Buffer의 스레드 안전성
1. 개요
tf2::BufferCore(및 이를 상속하는 tf2_ros::Buffer)는 멀티스레드 환경에서의 동시 접근을 안전하게 처리할 수 있도록 설계되어 있다. 로봇 시스템에서는 TransformListener의 콜백 스레드가 변환을 저장(write)하는 동시에, 사용자의 타이머 콜백이나 구독자 콜백에서 변환을 조회(read)하는 상황이 빈번하게 발생한다. 본 절에서는 tf2::Buffer의 스레드 안전성 메커니즘과 멀티스레드 환경에서의 올바른 사용법을 기술한다.
2. 멀티스레드 접근 시나리오
2.1 일반적인 동시 접근 패턴
ROS2 노드에서 tf2::Buffer에 대한 동시 접근은 다음의 시나리오에서 발생한다.
| 시나리오 | 쓰기 스레드 | 읽기 스레드 |
|---|---|---|
| Listener 전용 스레드 + 타이머 콜백 | TransformListener 내부 스레드 | 사용자 타이머 콜백 |
| Listener 전용 스레드 + 구독 콜백 | TransformListener 내부 스레드 | 센서 데이터 구독 콜백 |
| MultiThreadedExecutor | 콜백 스레드 A (TF 수신) | 콜백 스레드 B (변환 조회) |
| 복수 노드 공유 Buffer | 노드 A의 Listener 콜백 | 노드 B의 조회 호출 |
2.2 읽기-쓰기 경합
스레드 안전성이 보장되지 않으면, 다음과 같은 경합(race condition)이 발생할 수 있다.
스레드 1 (쓰기): 스레드 2 (읽기):
setTransform(A→B, t=1.0) lookupTransform("A", "B", t=0.5)
↓ ↓
캐시 내부 자료구조 수정 중 캐시 내부 자료구조 읽기 중
↓ ↓
→ 데이터 불일치 가능!
3. BufferCore의 동기화 메커니즘
3.1 내부 뮤텍스 구조
tf2::BufferCore는 내부적으로 std::mutex를 사용하여 프레임 데이터에 대한 접근을 동기화한다. 핵심적인 동기화 지점은 다음과 같다.
- 프레임 맵 접근: 새로운 프레임의 등록 또는 기존 프레임의 탐색 시 뮤텍스가 사용된다.
- 시간 캐시 접근: 특정 프레임의 시간 캐시(TimeCache)에 변환을 추가하거나 조회할 때 뮤텍스가 사용된다.
// BufferCore 내부 (개념적 표현)
class BufferCore {
private:
mutable std::mutex frame_mutex_;
std::unordered_map<CompactFrameID, TimeCacheInterfacePtr> frames_;
// 변환 저장
bool setTransformImpl(...) {
std::lock_guard<std::mutex> lock(frame_mutex_);
// 캐시에 변환 추가
}
// 변환 조회
TransformStamped lookupTransformImpl(...) const {
std::lock_guard<std::mutex> lock(frame_mutex_);
// 캐시에서 변환 탐색
}
};
3.2 잠금 범위 (Lock Scope)
BufferCore의 뮤텍스는 각 공개 메서드 호출의 전체 범위에 걸쳐 획득된다. 이는 다음과 같은 의미를 갖는다.
- 원자적 조회:
lookupTransform()호출 중에 다른 스레드가 변환을 추가하거나 삭제할 수 없다. 따라서 조회 결과는 항상 일관된 상태를 반영한다. - 원자적 설정:
setTransform()호출 중에 다른 스레드가 캐시를 읽을 수 없다. 따라서 부분적으로 갱신된 캐시가 관측되는 상황이 방지된다.
3.3 성능 영향
뮤텍스 잠금은 성능에 미미한 영향을 미친다. 잠금의 지속 시간은 변환 트리의 경로 탐색과 보간 연산에 소요되는 시간에 비례하며, 일반적인 로봇 시스템에서 이 시간은 마이크로초(µs) 단위이다.
그러나 고주기 조회(예: 1000Hz 이상)와 고주기 변환 수신이 동시에 발생하는 극한 상황에서는 잠금 경합(lock contention)에 의한 지연이 관측될 수 있다.
4. Executor 모델별 스레드 안전성
4.1 SingleThreadedExecutor
rclcpp::spin(node);
SingleThreadedExecutor에서는 모든 콜백이 단일 스레드에서 순차적으로 실행된다. 그러나 TransformListener가 기본 설정(spin_thread=true)으로 생성된 경우, 별도의 전용 스레드가 변환 수신을 처리하므로, 이 경우에도 멀티스레드 접근이 발생한다.
[전용 스레드] → Buffer.setTransform() (쓰기)
[메인 스레드] → Buffer.lookupTransform() (읽기)
Buffer의 내부 뮤텍스가 이 상황을 안전하게 처리한다.
4.2 MultiThreadedExecutor
rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(node);
executor.spin();
MultiThreadedExecutor에서는 복수의 콜백이 병렬로 실행되므로, Buffer에 대한 동시 읽기-쓰기 접근이 자연스럽게 발생한다. Buffer의 내부 뮤텍스가 스레드 안전성을 보장한다.
4.3 spin_thread=false 모드
TransformListener를 spin_thread=false로 생성한 경우에는 전용 스레드가 생성되지 않으므로, 모든 콜백이 사용자의 Executor에 의하여 처리된다.
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(
*tf_buffer_, this, false); // spin_thread=false
SingleThreadedExecutor에서 spin_thread=false를 사용하면, 변환 수신 콜백과 변환 조회가 동일한 스레드에서 순차적으로 실행되므로, 동시 접근 문제가 원천적으로 발생하지 않는다. 이 구성은 가장 단순하고 안전한 모드이다.
5. Python(rclpy)에서의 스레드 안전성
5.1 GIL의 역할
Python의 GIL(Global Interpreter Lock)은 동시에 하나의 스레드만 Python 바이트코드를 실행할 수 있도록 제한한다. 이로 인하여 순수 Python 코드에서는 데이터 경합이 발생하지 않는다.
그러나 tf2_ros의 핵심 로직은 C++ 확장 모듈로 구현되어 있으며, C++ 코드 실행 중에는 GIL이 해제될 수 있다. 따라서 tf2::BufferCore의 내부 뮤텍스에 의한 스레드 안전성이 여전히 중요한 역할을 한다.
5.2 spin_thread=True (기본값)
self.tf_listener = TransformListener(self.tf_buffer, self, spin_thread=True)
Python에서 spin_thread=True로 설정하면, 별도의 스레드에서 변환 메시지를 수신한다. 이 경우에도 BufferCore의 C++ 뮤텍스가 스레드 안전성을 보장한다.
6. 안전한 사용 패턴
6.1 패턴 1: 기본 권장 패턴
class SafeTFUser : public rclcpp::Node
{
public:
SafeTFUser() : Node("safe_tf_user")
{
tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
timer_ = this->create_wall_timer(
std::chrono::milliseconds(100),
std::bind(&SafeTFUser::on_timer, this));
}
private:
void on_timer()
{
// Buffer의 내부 뮤텍스에 의하여 스레드 안전
try {
auto t = tf_buffer_->lookupTransform(
"map", "base_link", tf2::TimePointZero);
} catch (const tf2::TransformException & ex) {
RCLCPP_DEBUG(this->get_logger(), "%s", ex.what());
}
}
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
rclcpp::TimerBase::SharedPtr timer_;
};
이 패턴에서 TransformListener의 전용 스레드가 /tf 토픽을 수신하여 Buffer에 저장하는 동안, 타이머 콜백에서 lookupTransform()을 호출하여도 안전하다.
6.2 패턴 2: 복수 콜백에서의 동시 조회
class MultiCallbackNode : public rclcpp::Node
{
public:
MultiCallbackNode() : Node("multi_callback_node")
{
tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
timer_fast_ = this->create_wall_timer(
std::chrono::milliseconds(10),
std::bind(&MultiCallbackNode::fast_callback, this));
timer_slow_ = this->create_wall_timer(
std::chrono::seconds(1),
std::bind(&MultiCallbackNode::slow_callback, this));
laser_sub_ = this->create_subscription<sensor_msgs::msg::LaserScan>(
"scan", 10,
std::bind(&MultiCallbackNode::laser_callback, this,
std::placeholders::_1));
}
private:
void fast_callback()
{
// 100Hz 제어 루프에서의 변환 조회
try {
auto t = tf_buffer_->lookupTransform(
"base_link", "tool_link", tf2::TimePointZero);
} catch (const tf2::TransformException &) {}
}
void slow_callback()
{
// 1Hz 모니터링에서의 변환 조회
try {
auto t = tf_buffer_->lookupTransform(
"map", "base_link", tf2::TimePointZero);
} catch (const tf2::TransformException &) {}
}
void laser_callback(const sensor_msgs::msg::LaserScan::SharedPtr msg)
{
// 센서 콜백에서의 변환 조회
try {
auto t = tf_buffer_->lookupTransform(
"base_link", msg->header.frame_id, tf2::TimePointZero);
} catch (const tf2::TransformException &) {}
}
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
rclcpp::TimerBase::SharedPtr timer_fast_, timer_slow_;
rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr laser_sub_;
};
MultiThreadedExecutor에서 위의 세 콜백이 병렬로 실행되어도, Buffer의 내부 뮤텍스에 의하여 도시 접근이 안전하게 처리된다.
7. 주의사항
7.1 Buffer 포인터의 수명 관리
Buffer의 포인터를 복수의 스레드에서 공유하는 경우, Buffer 객체가 모든 사용자보다 오래 존속하도록 보장하여야 한다. std::shared_ptr을 사용하면 참조 계수(reference counting)에 의하여 안전하게 관리할 수 있다.
7.2 lookupTransform 결과의 사용
lookupTransform()이 반환하는 TransformStamped 메시지는 복사본(copy)이므로, 반환 이후에는 Buffer의 뮤텍스와 무관하게 안전하게 사용할 수 있다.
auto t = tf_buffer_->lookupTransform(...);
// 이 시점 이후 t는 Buffer와 독립적
// 다른 스레드에서 Buffer가 갱신되어도 t에는 영향 없음
7.3 인위적 잠금 사용 금지
Buffer의 공개 메서드는 이미 내부적으로 뮤텍스를 사용하므로, 사용자가 별도의 뮤텍스로 Buffer 접근을 감싸는 것은 불필요하며, 교착 상태(deadlock)를 유발할 위험이 있다.
// 불필요한 코드 (안티패턴)
{
std::lock_guard<std::mutex> lock(my_mutex_);
auto t = tf_buffer_->lookupTransform(...); // 내부에서 이미 잠금 사용
}
7.4 장시간 잠금 방지
lookupTransform() 호출 후 반환값을 사용하여 장시간 연산을 수행하는 것은 문제가 되지 않으나, Buffer의 내부 메서드를 연속으로 호출하는 경우 각 호출 사이에 다른 스레드의 쓰기가 개입할 수 있음을 인지하여야 한다.
// 두 조회 사이에 Buffer가 갱신될 수 있음
auto t1 = tf_buffer_->lookupTransform("map", "odom", tf2::TimePointZero);
// ← 이 시점에 다른 스레드가 새로운 변환을 추가할 수 있음
auto t2 = tf_buffer_->lookupTransform("odom", "base_link", tf2::TimePointZero);
두 변환의 시간적 일관성이 중요한 경우, 동일한 타임스탬프를 명시적으로 지정하여야 한다.
8. 참고 자료
- tf2 소스 코드,
buffer_core.cpp, https://github.com/ros2/geometry2 - C++ 표준 라이브러리,
std::mutex, https://en.cppreference.com/w/cpp/thread/mutex - ROS2 MultiThreadedExecutor 문서, https://docs.ros.org/en/humble/Concepts/Intermediate/About-Executors.html
- ROS2 Humble Hawksbill