1293.58 비동기 노드의 별도 스레드 실행

1. 별도 스레드 실행의 필요성

행동 트리의 Tick은 통상적으로 단일 스레드에서 동기적으로 실행된다. 장시간 수행되는 작업(네비게이션, 매니퓰레이션, 복잡한 계산 등)을 Tick 스레드 내에서 직접 실행하면, 해당 작업이 완료될 때까지 전체 트리의 Tick이 차단(blocking)된다. 이는 Tick 주기 위반, 시스템 응답성 저하, 조건 재평가 지연을 유발한다. 별도 스레드 실행은 이러한 차단을 방지하기 위해 실제 작업을 Tick 스레드와 분리된 스레드에서 수행하는 설계 방식이다(Faconti, 2022).

2. BehaviorTree.CPP의 스레드 실행 모델

BehaviorTree.CPP v4에서 비동기 노드의 스레드 실행은 두 가지 모델로 구분된다.

2.1 StatefulActionNode 모델

StatefulActionNode는 노드 자체가 별도 스레드를 생성하지 않는다. 대신 외부 시스템(ROS2 액션 서버, 외부 프로세스 등)에 작업을 위임하고, onRunning()에서 결과를 비차단 방식으로 확인한다. 스레드 관리는 외부 시스템이 담당한다.

class NavigateAction : public BT::StatefulActionNode {
public:
    BT::NodeStatus onStart() override {
        // 외부 시스템에 작업 위임 (스레드 생성 없음)
        auto goal = NavigateToPose::Goal();
        getInput("goal", goal.pose);
        future_handle_ = action_client_->async_send_goal(goal);
        return BT::NodeStatus::RUNNING;
    }

    BT::NodeStatus onRunning() override {
        // 비차단 상태 확인 (Tick 스레드에서 실행)
        if (future_handle_.wait_for(std::chrono::milliseconds(0)) 
            == std::future_status::ready) {
            auto result = future_handle_.get();
            return result.code == rclcpp_action::ResultCode::SUCCEEDED
                ? BT::NodeStatus::SUCCESS
                : BT::NodeStatus::FAILURE;
        }
        return BT::NodeStatus::RUNNING;
    }

    void onHalted() override {
        action_client_->async_cancel_goal(goal_handle_);
    }
};

2.2 ThreadedAction 모델

ThreadedAction(BehaviorTree.CPP v3의 AsyncActionNode)은 라이브러리가 자동으로 별도 스레드를 생성하여 tick() 메서드를 실행한다. tick() 내에서 차단 연산을 수행하더라도 Tick 스레드가 차단되지 않는다.

class HeavyComputation : public BT::ThreadedAction {
public:
    BT::NodeStatus tick() override {
        // 이 코드는 별도 스레드에서 실행된다
        auto result = performExpensiveCalculation();  // 차단 연산
        
        if (result.valid()) {
            setOutput("result", result.value());
            return BT::NodeStatus::SUCCESS;
        }
        return BT::NodeStatus::FAILURE;
    }
    
    void halt() override {
        // 스레드 중단 요청
        should_cancel_ = true;
        ThreadedAction::halt();  // 스레드 조인 대기
    }
    
private:
    std::atomic<bool> should_cancel_{false};
};

3. ThreadedAction의 내부 스레드 관리

ThreadedAction의 내부 메커니즘은 다음과 같이 동작한다.

첫 Tick:
  1. 라이브러리가 std::thread 생성
  2. 별도 스레드에서 tick() 실행 시작
  3. Tick 스레드에 즉시 RUNNING 반환

후속 Tick:
  1. 스레드 완료 여부 확인
  2. 미완료 시 RUNNING 반환
  3. 완료 시 tick()의 반환값(SUCCESS/FAILURE) 반환

Halt:
  1. halt() 호출
  2. 스레드 조인(join) 대기
  3. 노드 상태 IDLE로 전이

라이브러리가 스레드의 생명주기를 자동으로 관리하므로, 개발자는 tick() 내에서 순차적 로직만을 작성하면 된다.

4. 두 모델의 비교

특성StatefulActionNodeThreadedAction
스레드 생성 주체외부 시스템 또는 개발자라이브러리 자동
Tick 메서드onStart(), onRunning(), onHalted()tick(), halt()
차단 연산 허용불가 (Tick 스레드 차단)가능 (별도 스레드)
스레드 안전성 책임개발자 (외부 통신)개발자 (공유 데이터)
ROS2 통합 적합성높음 (액션 클라이언트 패턴)제한적 (콜백 컨텍스트 문제)
블랙보드 접근Tick 스레드에서 안전별도 스레드에서 경쟁 조건 가능
Halt 응답성즉시 (외부 취소 요청)스레드 조인 대기 필요

5. 별도 스레드 실행의 위험 요소

5.1 블랙보드 경쟁 조건

ThreadedActiontick()이 별도 스레드에서 실행되면, 블랙보드에 대한 읽기/쓰기가 Tick 스레드와 동시에 발생할 수 있다. 이는 데이터 경쟁(data race) 조건을 유발한다.

Tick 스레드:     블랙보드["pose"] 읽기
작업 스레드:     블랙보드["pose"] 쓰기    ← 동시 접근, 경쟁 조건

이를 방지하기 위해 블랙보드 접근에 뮤텍스(mutex)를 사용하거나, 작업 스레드에서의 블랙보드 직접 접근을 회피하고 onStart()에서 입력을 복사하고 tick() 완료 후 출력을 설정하는 방식을 채택해야 한다.

5.2 Halt 시 스레드 종료 지연

ThreadedAction에서 halt() 호출 시, 실행 중인 스레드가 즉시 종료되지 않을 수 있다. tick() 내의 차단 연산이 취소 불가능한 경우, 스레드 조인이 지연되어 Halt 응답성이 저하된다.

BT::NodeStatus tick() override {
    // 취소 불가능한 차단 연산: Halt 지연 유발
    auto result = blockingFileIO();  // 수 초 소요 가능
    return BT::NodeStatus::SUCCESS;
}

이를 방지하기 위해 차단 연산을 분할하고 주기적으로 취소 플래그를 확인하는 패턴이 필요하다.

BT::NodeStatus tick() override {
    for (int i = 0; i < total_chunks; ++i) {
        if (isHaltRequested()) {
            return BT::NodeStatus::FAILURE;
        }
        processChunk(i);
    }
    return BT::NodeStatus::SUCCESS;
}

6. StatefulActionNode 모델의 권장 이유

BehaviorTree.CPP v4에서는 StatefulActionNode를 비동기 작업의 기본 구현 방식으로 권장한다(Faconti, 2022). 이 모델의 이점은 다음과 같다.

  1. Tick 스레드 단일성 유지: 모든 노드 로직이 Tick 스레드에서 실행되므로, 블랙보드 접근에 대한 스레드 안전성이 보장된다.
  2. Halt 즉시 응답: 외부 작업의 취소 요청만 전송하면 되므로, 스레드 조인 대기가 불필요하다.
  3. ROS2 통합 자연성: ROS2 액션 클라이언트의 비동기 목표 전송 및 상태 확인 패턴과 자연스럽게 일치한다.
  4. 자원 관리 단순성: 라이브러리에 의한 스레드 생성/소멸 오버헤드가 없다.

7. 스레드 실행과 Tick 실행 시간의 관계

별도 스레드 실행은 Tick 실행 시간에서 실제 작업 시간을 분리한다.

T_{tick\_async} = T_{status\_check} \quad \text{(별도 스레드 모델)}

T_{tick\_sync} = T_{computation} \quad \text{(동기 실행 모델)}

별도 스레드 모델에서 Tick 실행 시간은 상태 확인 비용(T_{status\_check})에만 비례하며, 이는 통상적으로 마이크로초 단위이다. 동기 실행 모델에서 Tick 실행 시간은 전체 계산 비용(T_{computation})에 비례하여 Tick 예산을 초과할 수 있다.


참고 문헌

  • 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/