1296.89 ThreadedAction의 Halt 시 스레드 종료 처리

1. 개요

ThreadedAction 노드는 tick() 메서드를 별도의 스레드에서 실행하여, 블로킹 연산이 행동 트리의 메인 tick 루프를 차단하지 않도록 한다. Halt 시에는 실행 중인 스레드를 안전하게 종료해야 하며, 이 과정에서 스레드 안전성, 자원 정리, 교착 상태 방지 등의 복잡한 동시성 문제를 처리해야 한다.

2. ThreadedAction의 스레드 생명주기

2.1 스레드 시작

ThreadedAction이 처음 tick되면 프레임워크가 별도의 스레드를 생성하여 tick() 메서드를 실행한다. 메인 스레드에는 RUNNING이 반환된다.

[메인 스레드]                     [작업 스레드]
     │                                │
     ├── executeTick() 호출            │
     │   ├── 스레드 생성 ──────────────┤
     │   └── RUNNING 반환              ├── tick() 실행
     │                                 │
     ├── 다음 tick                      │   (블로킹 작업)
     │   └── 스레드 상태 확인            │
     │       └── RUNNING 반환           │
     │                                 ├── tick() 완료
     ├── 다음 tick                      │   (결과 저장)
     │   └── 스레드 완료 확인            │
     │       └── SUCCESS/FAILURE       │

2.2 스레드 종료

tick() 메서드가 반환되면 스레드는 자연스럽게 종료된다. 그러나 halt가 호출되면 아직 실행 중인 스레드를 강제로 종료해야 하는 상황이 발생한다.

3. Halt 시 스레드 종료 메커니즘

3.1 BehaviorTree.CPP의 기본 halt 동작

BehaviorTree.CPP의 ThreadedAction 기본 구현에서, halt는 내부 중단 플래그를 설정하고 스레드의 완료를 대기한다.

// BehaviorTree.CPP 내부 (간략화)
void ThreadedAction::halt()
{
    halt_requested_.store(true);

    if (thread_.joinable())
    {
        thread_.join();
    }

    setStatus(NodeStatus::IDLE);
}

thread_.join()은 스레드가 종료될 때까지 블로킹하므로, tick() 내부에서 중단 플래그를 주기적으로 확인하지 않으면 halt가 무기한 블로킹될 수 있다.

3.2 중단 플래그 확인 패턴

tick() 메서드 내부에서 isHaltRequested()를 주기적으로 확인하여, halt 요청 시 조기에 반환한다.

BT::NodeStatus tick() override
{
    // 장시간 루프
    while (!isComplete())
    {
        // 중단 플래그 확인
        if (isHaltRequested())
        {
            RCLCPP_INFO(node_->get_logger(),
                "Halt 요청 감지, 스레드 종료");
            cleanup();
            return BT::NodeStatus::FAILURE;
        }

        // 작업 수행
        performStep();

        // 짧은 대기 (CPU 부하 방지)
        std::this_thread::sleep_for(
            std::chrono::milliseconds(10));
    }

    return BT::NodeStatus::SUCCESS;
}

3.3 블로킹 호출의 중단 가능성

외부 라이브러리의 블로킹 함수(소켓 읽기, 파일 입출력, 동기 서비스 호출 등)를 사용하는 경우, 해당 함수가 반환되기 전에는 중단 플래그를 확인할 수 없다. 이 문제를 해결하는 방법은 다음과 같다.

타임아웃 기반 블로킹:

BT::NodeStatus tick() override
{
    while (!isComplete())
    {
        if (isHaltRequested())
            return BT::NodeStatus::FAILURE;

        // 짧은 타임아웃으로 블로킹 호출
        auto result = waitForData(
            std::chrono::milliseconds(100));

        if (result.has_value())
        {
            processData(result.value());
        }
        // 타임아웃 시 루프 반복 → 중단 플래그 재확인
    }
    return BT::NodeStatus::SUCCESS;
}

조건 변수 활용:

BT::NodeStatus tick() override
{
    std::unique_lock<std::mutex> lock(mutex_);

    while (!data_ready_ && !isHaltRequested())
    {
        // 100ms 간격으로 조건 재확인
        cv_.wait_for(lock,
            std::chrono::milliseconds(100));
    }

    if (isHaltRequested())
    {
        return BT::NodeStatus::FAILURE;
    }

    return processData()
        ? BT::NodeStatus::SUCCESS
        : BT::NodeStatus::FAILURE;
}

4. 교착 상태 방지

4.1 Halt와 tick()의 교착

halt가 thread_.join()으로 스레드 완료를 대기하고, tick() 내부에서 메인 스레드가 보유한 뮤텍스를 요청하면 교착 상태가 발생한다.

[메인 스레드]                [작업 스레드]
     │                           │
     ├── halt() 호출              │
     │   ├── mutex_ 보유           │
     │   ├── thread_.join() 대기   │
     │   │   (블로킹)              ├── tick() 실행
     │   │                        │   ├── mutex_ 요청
     │   │                        │   │   (블로킹)
     │   │                        │   │   ← 교착 상태

이를 방지하려면, halt에서 뮤텍스를 보유한 채로 thread_.join()을 호출하지 않도록 해야 한다.

void halt() override
{
    halt_requested_.store(true);

    // 뮤텍스 없이 스레드 완료 대기
    if (thread_.joinable())
    {
        thread_.join();
    }

    // 스레드 종료 후 정리
    {
        std::lock_guard<std::mutex> lock(mutex_);
        resetState();
    }
}

5. 스레드 풀 활용

매 실행마다 스레드를 생성하고 소멸하는 것은 오버헤드가 크다. 스레드 풀(thread pool)을 활용하면 스레드 생성 비용을 줄이고 자원 관리를 단순화할 수 있다.

// 스레드 풀에 작업 제출
auto future = thread_pool_.submit(
    [this]() -> BT::NodeStatus
    {
        return tick();
    });

BehaviorTree.CPP 4.x 버전에서는 내장 스레드 풀을 지원하며, TreeExecutionServer를 통해 스레드 관리를 자동화한다.

6. 스레드 안전 자원 접근

6.1 atomic 변수

작업 스레드와 메인 스레드 간에 공유되는 플래그 변수는 std::atomic을 사용하여 원자적 접근을 보장한다.

std::atomic<bool> halt_requested_{false};
std::atomic<bool> task_completed_{false};
std::atomic<bool> task_succeeded_{false};

6.2 공유 데이터 보호

결과 데이터 등 복합 자료 구조의 공유는 뮤텍스를 통해 보호한다.

std::mutex result_mutex_;
ResultData result_data_;

// 작업 스레드에서 결과 저장
{
    std::lock_guard<std::mutex> lock(result_mutex_);
    result_data_ = computeResult();
}
task_completed_.store(true);

// 메인 스레드에서 결과 읽기
if (task_completed_.load())
{
    std::lock_guard<std::mutex> lock(result_mutex_);
    setOutput("result", result_data_);
}

7. 설계 지침

  1. tick() 내부에서 isHaltRequested()를 최소 100ms 간격으로 확인한다.
  2. 블로킹 호출은 짧은 타임아웃과 함께 사용하여 중단 가능성을 확보한다.
  3. halt에서 뮤텍스를 보유한 채로 join()을 호출하지 않는다.
  4. 공유 데이터 접근에 std::atomic 또는 std::mutex를 사용한다.
  5. 장시간 블로킹이 불가피한 경우, StatefulActionNode로의 전환을 고려한다.

8. 참고 문헌

  • Colledanchise, M. and Ögren, P., “Behavior Trees in Robotics and AI: An Introduction,” CRC Press, 2018.
  • Faconti, D. and Contributors, “BehaviorTree.CPP: A C++ library to build Behavior Trees,” GitHub Repository, https://github.com/BehaviorTree/BehaviorTree.CPP.
  • Williams, A., “C++ Concurrency in Action,” 2nd ed., Manning Publications, 2019.
  • Stroustrup, B., “The C++ Programming Language,” 4th ed., Addison-Wesley, 2013.

버전: 2026-04-04