1293.62 다중 스레드 노드에서의 동기화

1. 다중 스레드 동기화의 필요성

행동 트리 노드가 다중 스레드 환경에서 동작하는 경우, 공유 데이터에 대한 동시 접근을 조율하는 동기화(synchronization)가 필수적이다. 동기화가 없으면 데이터 경쟁(data race), 교착 상태(deadlock), 라이브락(livelock) 등의 동시성 오류가 발생할 수 있다. 행동 트리에서 다중 스레드 동기화가 요구되는 경우는 ThreadedAction 사용, ROS2 멀티스레드 실행기 사용, 개발자 정의 작업 스레드 운용 등이다(Faconti, 2022).

2. 동기화가 필요한 데이터 접근 패턴

2.1 Tick 스레드와 콜백 스레드 간 공유

ROS2 MultiThreadedExecutor를 사용하는 경우, 토픽 구독 콜백이 Tick 스레드와 다른 스레드에서 실행될 수 있다. 콜백에서 갱신하는 데이터를 노드의 onRunning()에서 읽는 경우 동기화가 필요하다.

콜백 스레드:  scan_data_ 쓰기
Tick 스레드:  scan_data_ 읽기
→ 동기화 없이 동시 발생 시 정의되지 않은 동작

2.2 Tick 스레드와 작업 스레드 간 공유

ThreadedActiontick()이 별도 스레드에서 실행되면서 노드 멤버 변수나 블랙보드에 접근하는 경우이다.

2.3 복수 콜백 스레드 간 공유

동일한 데이터에 접근하는 복수의 콜백이 서로 다른 스레드에서 동시에 실행되는 경우이다.

3. 뮤텍스 기반 동기화

3.1 std::mutex와 lock_guard

가장 기본적인 동기화 기법으로, 임계 영역(critical section)에 대한 상호 배제를 보장한다.

class SensorFusionNode : public BT::StatefulActionNode {
public:
    void lidarCallback(const sensor_msgs::msg::LaserScan::SharedPtr msg) {
        std::lock_guard<std::mutex> lock(data_mutex_);
        latest_scan_ = *msg;
        scan_updated_ = true;
    }

    void imuCallback(const sensor_msgs::msg::Imu::SharedPtr msg) {
        std::lock_guard<std::mutex> lock(data_mutex_);
        latest_imu_ = *msg;
        imu_updated_ = true;
    }

    BT::NodeStatus onRunning() override {
        std::lock_guard<std::mutex> lock(data_mutex_);
        if (scan_updated_ && imu_updated_) {
            auto result = fuseSensorData(latest_scan_, latest_imu_);
            setOutput("fused_data", result);
            scan_updated_ = false;
            imu_updated_ = false;
            return BT::NodeStatus::SUCCESS;
        }
        return BT::NodeStatus::RUNNING;
    }

private:
    std::mutex data_mutex_;
    sensor_msgs::msg::LaserScan latest_scan_;
    sensor_msgs::msg::Imu latest_imu_;
    bool scan_updated_{false};
    bool imu_updated_{false};
};

3.2 std::unique_lock과 조건 변수

조건 변수(condition variable)를 사용하면 특정 조건이 충족될 때까지 스레드를 대기시킬 수 있다. 그러나 Tick 스레드에서의 대기는 Tick 차단을 유발하므로, 비차단 확인 방식으로 사용해야 한다.

BT::NodeStatus onRunning() override {
    std::unique_lock<std::mutex> lock(mutex_);
    // 비차단 확인: Tick 스레드 차단 방지
    if (result_ready_) {
        auto result = result_value_;
        lock.unlock();
        return processResult(result);
    }
    return BT::NodeStatus::RUNNING;
}

4. 원자적 연산 기반 동기화

단순 타입의 플래그나 카운터에 대해서는 뮤텍스 대신 원자적 연산(atomic operation)을 사용하여 락 없는(lock-free) 동기화를 수행할 수 있다.

class AsyncDetector : public BT::StatefulActionNode {
public:
    BT::NodeStatus onStart() override {
        detection_count_.store(0, std::memory_order_relaxed);
        is_processing_.store(true, std::memory_order_release);
        
        worker_ = std::thread([this]() {
            int count = runDetection();
            detection_count_.store(count, std::memory_order_release);
            is_processing_.store(false, std::memory_order_release);
        });
        worker_.detach();
        return BT::NodeStatus::RUNNING;
    }

    BT::NodeStatus onRunning() override {
        if (!is_processing_.load(std::memory_order_acquire)) {
            int count = detection_count_.load(std::memory_order_acquire);
            setOutput("count", count);
            return (count > 0) 
                ? BT::NodeStatus::SUCCESS 
                : BT::NodeStatus::FAILURE;
        }
        return BT::NodeStatus::RUNNING;
    }

private:
    std::atomic<bool> is_processing_{false};
    std::atomic<int> detection_count_{0};
    std::thread worker_;
};

5. 메모리 순서(Memory Ordering)

원자적 연산에서 메모리 순서는 스레드 간 데이터 가시성을 제어한다.

메모리 순서보장성능사용 시점
memory_order_relaxed원자성만 보장최고독립적 카운터
memory_order_acquire이전 release의 가시성 보장높음데이터 읽기 측
memory_order_release이전 쓰기의 가시성 보장높음데이터 쓰기 측
memory_order_seq_cst전역 순서 보장보통복잡한 동기화

Tick 메커니즘에서의 일반적 패턴은 작업 스레드에서 release로 결과를 기록하고, Tick 스레드에서 acquire로 결과를 읽는 것이다. 이에 의해 결과 데이터의 가시성이 보장된다.

6. 교착 상태 방지

6.1 락 순서 규약

복수의 뮤텍스를 사용하는 경우, 모든 스레드에서 동일한 순서로 락을 획득해야 교착 상태가 방지된다.

// 위험: 순서 불일치로 교착 상태 가능
// 스레드 A: lock(mutex_a) → lock(mutex_b)
// 스레드 B: lock(mutex_b) → lock(mutex_a)

// 안전: std::scoped_lock 사용
void safeOperation() {
    std::scoped_lock lock(mutex_a_, mutex_b_);
    // 두 뮤텍스를 교착 상태 없이 동시에 획득
}

6.2 락 범위 최소화

뮤텍스의 보유 시간을 최소화하여 다른 스레드의 대기 시간을 줄이고 교착 상태 가능성을 낮춘다.

BT::NodeStatus onRunning() override {
    // 데이터 복사만 락 내에서 수행
    geometry_msgs::msg::Pose pose_copy;
    {
        std::lock_guard<std::mutex> lock(mutex_);
        pose_copy = current_pose_;
    }
    // 복사본으로 계산 수행 (락 외부)
    return processPosition(pose_copy);
}

7. Tick 스레드에서의 동기화 비용

동기화는 Tick 실행 시간에 직접적인 영향을 미친다. 뮤텍스 획득에 소요되는 시간은 경쟁 여부에 따라 크게 달라진다.

T_{lock} = \begin{cases} T_{uncontended} \approx 20\text{ns} & \text{(경쟁 없음)} \\ T_{contended} \gg T_{uncontended} & \text{(경쟁 존재)} \end{cases}

경쟁 없는 뮤텍스 획득은 나노초 수준으로 Tick 예산에 미미한 영향을 미치지만, 경쟁이 존재하면 Tick 스레드가 대기 상태에 진입하여 Tick 실행 시간이 크게 증가할 수 있다. 이를 방지하기 위해 try_lock을 사용한 비차단 획득 시도가 유효하다.

BT::NodeStatus onRunning() override {
    std::unique_lock<std::mutex> lock(mutex_, std::try_to_lock);
    if (lock.owns_lock()) {
        // 락 획득 성공: 데이터 읽기
        auto data = shared_data_;
        lock.unlock();
        return processData(data);
    }
    // 락 획득 실패: 다음 Tick에서 재시도
    return BT::NodeStatus::RUNNING;
}

8. 동기화 설계 지침

  1. 단일 스레드 모델 우선: 가능하면 단일 스레드 실행 모델을 유지하여 동기화 자체를 회피한다.
  2. 원자적 연산 우선: 단순 플래그나 단일 값에는 뮤텍스 대신 원자적 변수를 사용한다.
  3. 락 범위 최소화: 뮤텍스 보유 시간을 최소화하여 경쟁을 줄인다.
  4. Tick 스레드 차단 금지: Tick 스레드에서 차단 대기를 수행하지 않는다.
  5. 일관된 락 순서: 복수의 뮤텍스 사용 시 전역적으로 일관된 획득 순서를 정의한다.

참고 문헌

  • Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
  • Faconti, D. (2022). BehaviorTree.CPP documentation and API reference. https://www.behaviortree.dev/
  • Williams, A. (2019). C++ Concurrency in Action (2nd ed.). Manning Publications.