659.114 TF2의 동시성 이슈와 스레드 안전성 (TF2 Concurrency Issues and Thread Safety)
1. 동시성 문제의 발생 배경
ROS2는 DDS 기반의 비동기 메시지 전달 체계를 채택하고 있으며, 다중 스레드 실행기(multi-threaded executor)를 통해 복수의 콜백을 병렬로 처리할 수 있다. TF2 프레임워크의 핵심 자료 구조인 tf2::Buffer는 변환 데이터의 수신(쓰기)과 조회(읽기)가 비동기적으로 발생하는 공유 자원(shared resource)이며, 이에 따라 동시성 제어(concurrency control)가 정확하게 이루어지지 않으면 데이터 경합(data race), 불일치한 변환 결과, 또는 프로그램의 비정상 종료(segmentation fault)와 같은 심각한 문제가 발생할 수 있다.
본 절에서는 TF2 사용 시 발생할 수 있는 동시성 이슈의 유형을 체계적으로 분류하고, tf2::Buffer의 내부 동기화 메커니즘을 분석하며, 스레드 안전한 TF2 활용을 위한 설계 원칙과 구현 패턴을 기술한다.
2. tf2::Buffer의 내부 동기화 메커니즘
2.1 읽기-쓰기 잠금 구조
tf2::Buffer는 내부적으로 tf2::BufferCore를 상속하며, BufferCore는 변환 데이터를 프레임 쌍별 시계열(time series)로 관리한다. BufferCore의 소스 코드(ROS2 geometry2 리포지터리)를 분석하면, 내부의 변환 저장소에 대한 접근은 std::mutex 기반의 상호 배제(mutual exclusion) 잠금으로 보호되어 있다.
주요 공개 메서드의 스레드 안전성은 다음과 같다.
| 메서드 | 연산 유형 | 내부 잠금 | 스레드 안전성 |
|---|---|---|---|
setTransform() | 쓰기 | std::mutex 잠금 | 안전 |
lookupTransform() | 읽기 | std::mutex 잠금 | 안전 |
canTransform() | 읽기 | std::mutex 잠금 | 안전 |
clear() | 쓰기 | std::mutex 잠금 | 안전 |
BufferCore의 내부 잠금 메커니즘은 단일 std::mutex를 사용하여 모든 읽기와 쓰기 연산을 순차적으로 직렬화한다. 이 설계는 스레드 안전성을 강하게 보장하나, 고빈도 접근 환경에서 잠금 경합(lock contention)이 발생하여 성능 저하의 원인이 될 수 있다.
2.2 잠금 경합의 발생 조건
tf2::Buffer에 대한 잠금 경합은 다음의 조건에서 심화된다.
- 다수의 변환 발행자가 존재하는 경우:
TransformListener의 내부 콜백이 수신된 변환을Buffer에 삽입(setTransform)할 때마다 잠금을 획득한다. 발행 주파수가 높고 변환 채널 수가 많을수록 쓰기 잠금 빈도가 증가한다. - 다수의 스레드가 동시에 변환을 조회하는 경우:
lookupTransform()호출이 다중 스레드에서 동시에 발생하면, 읽기 연산도 동일한std::mutex를 획득하여야 하므로 순차적으로 처리된다. - 복잡한 변환 트리에서의 경로 탐색이 긴 경우:
lookupTransform()이 변환 트리의 경로를 탐색하고 합성하는 연산은 잠금 보유 시간을 증가시킨다.
3. ROS2 실행기 모델과 TF2의 상호작용
3.1 SingleThreadedExecutor에서의 동작
SingleThreadedExecutor는 모든 콜백을 단일 스레드에서 순차적으로 실행한다. 이 환경에서는 TransformListener의 수신 콜백과 사용자 콜백이 동시에 실행될 수 없으므로, tf2::Buffer에 대한 동시 접근이 원천적으로 차단된다. 따라서 단일 스레드 실행기 환경에서는 TF2의 동시성 문제가 발생하지 않는다.
그러나 이 모델의 제약은 TransformListener의 수신 콜백이 변환 메시지를 처리하는 동안 사용자 콜백이 대기하여야 한다는 점이다. 고빈도 변환 수신 환경에서 이러한 대기는 사용자 콜백의 실행 지연을 유발할 수 있다.
3.2 MultiThreadedExecutor에서의 동작
MultiThreadedExecutor는 복수의 스레드 풀(thread pool)에서 콜백을 병렬로 실행한다. 이 환경에서는 TransformListener의 수신 콜백(쓰기)과 사용자 콜백 내의 lookupTransform() 호출(읽기)이 동시에 실행될 수 있다.
tf2::BufferCore의 내부 잠금 메커니즘이 이러한 동시 접근을 보호하므로, 데이터 경합은 발생하지 않는다. 그러나 다음의 상위 수준 동시성 문제가 발생할 수 있다.
3.2.1 TOCTOU(Time of Check to Time of Use) 경합
canTransform()으로 변환의 가용성을 확인한 후 lookupTransform()을 호출하는 패턴에서, 두 호출 사이에 다른 스레드의 clear() 호출 또는 변환 데이터의 캐시 만료가 발생하면, canTransform()의 결과가 lookupTransform() 시점에서는 유효하지 않을 수 있다.
// TOCTOU 경합에 취약한 패턴
if (buffer->canTransform("target", "source", tf2::TimePointZero)) {
// 이 시점에서 변환이 삭제될 수 있다
auto transform = buffer->lookupTransform("target", "source",
tf2::TimePointZero);
}
이 문제의 해결 방안은 canTransform()의 결과에 의존하지 않고, lookupTransform()을 직접 호출하면서 예외를 처리하는 패턴을 채택하는 것이다.
// 예외 기반 패턴 (TOCTOU 방지)
try {
auto transform = buffer->lookupTransform("target", "source",
tf2::TimePointZero);
// 변환 사용
} catch (const tf2::TransformException& ex) {
RCLCPP_WARN(this->get_logger(), "변환 조회 실패: %s", ex.what());
}
3.2.2 콜백 그룹을 이용한 동시 실행 제어
ROS2의 콜백 그룹(callback group)은 특정 콜백들의 동시 실행을 제어하는 메커니즘을 제공한다. MutuallyExclusiveCallbackGroup에 할당된 콜백들은 동시에 실행되지 않으므로, TransformListener의 수신 콜백과 사용자 콜백을 동일한 상호 배제 콜백 그룹에 배치하면 tf2::Buffer에 대한 동시 접근을 방지할 수 있다.
#include <rclcpp/rclcpp.hpp>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/buffer.h>
class ThreadSafeTFNode : public rclcpp::Node
{
public:
ThreadSafeTFNode()
: Node("thread_safe_tf_node")
{
// tf2::Buffer 생성
tf_buffer_ = std::make_unique<tf2_ros::Buffer>(this->get_clock());
// 콜백 그룹 생성
callback_group_ = this->create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive);
// TransformListener를 특정 콜백 그룹에 연결
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(
*tf_buffer_, this, false);
// 사용자 타이머를 동일 콜백 그룹에 연결
timer_ = this->create_wall_timer(
std::chrono::milliseconds(100),
std::bind(&ThreadSafeTFNode::onTimer, this),
callback_group_);
}
private:
void onTimer()
{
try {
auto transform = tf_buffer_->lookupTransform(
"map", "base_link", tf2::TimePointZero);
// 변환 처리
} catch (const tf2::TransformException& ex) {
RCLCPP_WARN(this->get_logger(), "%s", ex.what());
}
}
std::unique_ptr<tf2_ros::Buffer> tf_buffer_;
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
rclcpp::CallbackGroup::SharedPtr callback_group_;
rclcpp::TimerBase::SharedPtr timer_;
};
그러나 이 방식은 TransformListener의 수신 콜백과 사용자 콜백 간의 병렬성을 포기하는 것이므로, 성능상의 트레이드오프를 고려하여 적용하여야 한다.
4. 멀티 노드 환경에서의 Buffer 공유 문제
4.1 단일 프로세스 내 복수 노드
ROS2의 Component 모델을 사용하면 단일 프로세스 내에서 복수의 노드를 실행할 수 있다. 이때 각 노드가 독립적인 tf2::Buffer와 TransformListener를 생성하면, 동일한 변환 데이터가 복수의 Buffer 인스턴스에 중복 저장되어 메모리가 낭비된다.
이를 최적화하기 위해 단일 tf2::Buffer 인스턴스를 복수의 노드 간에 공유하는 설계가 고려될 수 있으나, 이 경우 Buffer 인스턴스에 대한 접근이 더욱 빈번해지므로 잠금 경합이 심화될 수 있다. 공유 Buffer를 사용하는 경우에는 다음의 사항에 유의하여야 한다.
Buffer인스턴스의 생명 주기(lifetime)가 모든 사용자 노드의 생명 주기를 포함하여야 한다.TransformListener는 단일 인스턴스만 생성하여야 하며, 복수의TransformListener가 동일한Buffer에 연결되면 동일한 변환이 중복 삽입될 수 있다.Buffer에 연결된 시계(clock) 소스가 모든 사용자 노드의 시간 기준과 일치하여야 한다.
4.2 Buffer 인스턴스의 소유권 관리
tf2::Buffer를 std::shared_ptr로 관리하여 복수의 컴포넌트 간에 소유권을 공유하는 것이 안전한 생명 주기 관리 방법이다.
// Buffer를 std::shared_ptr로 생성하여 복수 컴포넌트에서 공유
auto shared_buffer = std::make_shared<tf2_ros::Buffer>(clock);
auto tf_listener = std::make_shared<tf2_ros::TransformListener>(*shared_buffer);
// 복수의 컴포넌트에 Buffer 참조 전달
auto component_a = std::make_shared<ComponentA>(shared_buffer);
auto component_b = std::make_shared<ComponentB>(shared_buffer);
5. 비동기 변환 조회와 스레드 안전성
5.1 waitForTransform()의 동작 메커니즘
waitForTransform()은 요청된 변환이 Buffer에 수신될 때까지 호출 스레드를 차단(block)하는 동기 대기 함수이다. 내부적으로 조건 변수(condition variable)를 사용하여 setTransform() 호출 시 대기 중인 스레드를 통지(notify)한다.
SingleThreadedExecutor 환경에서 waitForTransform()을 콜백 내에서 호출하면 교착 상태(deadlock)가 발생한다. 사용자 콜백이 waitForTransform()에서 차단되면, TransformListener의 수신 콜백이 실행될 수 없으므로 새로운 변환이 Buffer에 삽입되지 않고, 따라서 대기 조건이 영원히 충족되지 않기 때문이다.
// SingleThreadedExecutor에서 교착 상태를 유발하는 패턴
void timerCallback()
{
// 경고: 단일 스레드 실행기에서 이 호출은 교착을 유발한다
auto transform = tf_buffer_->lookupTransform(
"target", "source",
tf2::TimePoint(std::chrono::seconds(0)),
std::chrono::seconds(5)); // 5초 타임아웃 대기
}
5.2 교착 방지를 위한 설계 패턴
SingleThreadedExecutor 환경에서 변환 대기가 필요한 경우, 다음의 비차단(non-blocking) 패턴을 채택하여야 한다.
폴링 기반 재시도 패턴: canTransform()으로 가용성을 확인하고, 불가능한 경우 콜백을 종료하여 다음 주기에 재시도한다.
void timerCallback()
{
if (!tf_buffer_->canTransform("target", "source",
tf2::TimePointZero)) {
RCLCPP_INFO_THROTTLE(this->get_logger(),
*this->get_clock(), 1000,
"변환 대기 중...");
return; // 콜백 종료, 다음 주기에 재시도
}
try {
auto transform = tf_buffer_->lookupTransform(
"target", "source", tf2::TimePointZero);
// 변환 사용
} catch (const tf2::TransformException& ex) {
RCLCPP_WARN(this->get_logger(), "%s", ex.what());
}
}
MultiThreadedExecutor 전환: 복수 스레드를 사용하면 waitForTransform()이 사용자 콜백 스레드를 차단하는 동안에도 TransformListener의 수신 콜백이 다른 스레드에서 실행될 수 있다. 단, 이 경우에도 충분한 스레드 수를 확보하여야 하며, ReentrantCallbackGroup을 적절히 구성하여야 한다.
6. 실시간 시스템에서의 동시성 고려 사항
실시간(real-time) 로봇 제어 시스템에서 tf2::Buffer의 std::mutex 기반 잠금은 우선순위 역전(priority inversion) 문제를 유발할 수 있다. 높은 우선순위의 제어 스레드가 lookupTransform()을 호출할 때, 낮은 우선순위의 TransformListener 수신 스레드가 잠금을 보유하고 있으면, 높은 우선순위의 스레드가 잠금 해제까지 대기하게 된다.
이 문제를 완화하기 위한 전략은 다음과 같다.
-
변환 데이터의 로컬 복사본 유지: 주기적으로
lookupTransform()을 호출하여 최신 변환을 로컬 변수에 복사하고, 실시간 제어 루프에서는 로컬 복사본을 사용한다. 이로써 제어 루프가tf2::Buffer의 잠금에 직접적으로 의존하지 않게 된다. -
잠금 없는 자료 구조 활용: 가장 최근의 변환 값을
std::atomic또는std::atomic<std::shared_ptr>기반의 잠금 없는(lock-free) 자료 구조로 관리하면, 실시간 스레드에서의 변환 접근 시 잠금 경합을 완전히 제거할 수 있다.
// 잠금 없는 변환 캐시 패턴
class LockFreeTransformCache
{
public:
void update(const geometry_msgs::msg::TransformStamped& transform)
{
auto new_data = std::make_shared<geometry_msgs::msg::TransformStamped>(transform);
std::atomic_store(&cached_transform_, new_data);
}
geometry_msgs::msg::TransformStamped get() const
{
auto data = std::atomic_load(&cached_transform_);
if (!data) {
throw std::runtime_error("변환 캐시가 초기화되지 않음");
}
return *data;
}
private:
std::shared_ptr<geometry_msgs::msg::TransformStamped> cached_transform_;
};
- 우선순위 상속 프로토콜 적용: 리눅스의
PTHREAD_PRIO_INHERIT속성을std::mutex에 적용하면, 잠금을 보유한 낮은 우선순위 스레드의 우선순위가 대기 중인 높은 우선순위 스레드의 수준으로 일시적으로 상승하여, 우선순위 역전의 영향을 최소화할 수 있다. 그러나 이 접근은tf2::BufferCore의 내부 구현을 수정하여야 하므로, 표준 배포판에서는 직접 적용하기 어렵다.
7. 스레드 안전성 검증 방법
TF2 관련 동시성 문제는 비결정적(non-deterministic)으로 발생하므로, 통상적인 기능 테스트로는 검출이 어렵다. 다음의 도구와 기법을 활용하여 동시성 결함을 검증할 수 있다.
| 도구 | 용도 | 적용 방법 |
|---|---|---|
| ThreadSanitizer (TSan) | 데이터 경합 검출 | cmake -DCMAKE_CXX_FLAGS="-fsanitize=thread" |
| AddressSanitizer (ASan) | 메모리 오류 검출 | cmake -DCMAKE_CXX_FLAGS="-fsanitize=address" |
| Helgrind (Valgrind) | 잠금 순서 위반 검출 | valgrind --tool=helgrind ./node |
| 스트레스 테스트 | 경합 조건 재현 | 고부하 환경에서 장시간 실행 |
ThreadSanitizer는 컴파일 시 계측(instrumentation) 코드를 삽입하여 실행 중의 데이터 경합을 동적으로 검출하며, tf2::Buffer를 사용하는 다중 스레드 노드의 정합성 검증에 효과적이다.
참고 문헌 및 출처
- ROS2 geometry2 리포지터리,
tf2및tf2_ros패키지, https://github.com/ros2/geometry2 - Foote, T. (2013). “tf: The transform library.” IEEE International Conference on Technologies for Practical Robot Applications (TePRA), pp. 1–6.
- ROS2 Executors 개념 문서, https://docs.ros.org/en/humble/Concepts/Intermediate/About-Executors.html
- Herlihy, M., Shavit, N. (2012). The Art of Multiprocessor Programming. Morgan Kaufmann.
- Casini, D. et al. (2019). “Response-Time Analysis of ROS 2 Processing Chains Under Reservation-Based Scheduling.” Euromicro Conference on Real-Time Systems (ECRTS).
버전: 1.0