1296.87 동기 액션 노드의 Halt 처리

1. 개요

동기 액션 노드(SyncActionNode)는 단일 tick 내에서 SUCCESS 또는 FAILURE를 즉시 반환하며, RUNNING 상태를 반환하지 않는다. 따라서 동기 액션 노드는 행동 트리의 관점에서 항상 완료된 상태에 있으므로, 외부에서 halt가 호출되는 상황이 구조적으로 발생하지 않는다.

그러나 BehaviorTree.CPP 프레임워크에서 SyncActionNodeTreeNode를 상속하므로 halt() 가상 메서드를 보유하며, 특정 조건에서 halt가 호출될 수 있다. 본 절에서는 동기 액션 노드에서의 halt 처리 특성과 고려 사항을 기술한다.

2. SyncActionNode의 Halt 특성

2.1 RUNNING 미반환 원칙과 Halt

SyncActionNodetick() 메서드는 RUNNING을 반환하지 않으므로, 노드가 실행 중인 상태에서 halt가 호출되는 정상적인 경우는 존재하지 않는다. tick()이 호출되면 즉시 SUCCESS 또는 FAILURE 중 하나를 반환하고, 노드의 상태는 즉시 IDLE로 전환된다.

2.2 트리 전체 중지 시의 Halt

행동 트리 전체를 중지(Tree::haltTree())할 때, 프레임워크는 모든 노드에 대해 halt를 호출한다. 이 경우 동기 노드도 halt 대상에 포함되지만, 동기 노드는 이미 실행이 완료된 상태이므로 실질적인 중단 동작은 필요하지 않다.

2.3 기본 halt() 구현

SyncActionNode는 기본 halt() 구현을 상속하며, 이는 노드의 상태를 IDLE로 설정하는 것 이외의 동작을 수행하지 않는다.

// BehaviorTree.CPP 내부 (간략화)
void TreeNode::halt()
{
    setStatus(NodeStatus::IDLE);
}

3. 동기 노드에서 Halt가 문제되는 경우

3.1 장시간 실행 tick()

SyncActionNodetick() 메서드가 장시간 블로킹되는 경우, 그 동안 다른 노드의 halt 처리가 지연된다. 동기 노드의 tick()은 즉시 반환되어야 하며, 장시간 소요되는 작업은 StatefulActionNode 또는 ThreadedAction으로 구현해야 한다.

// 잘못된 설계: 동기 노드에서의 블로킹
BT::NodeStatus tick() override
{
    // 서비스 응답을 동기적으로 대기 (수 초 소요 가능)
    auto result = service_client_->call(request);
    // 이 시간 동안 다른 노드의 halt 불가
    return result ? BT::NodeStatus::SUCCESS
                  : BT::NodeStatus::FAILURE;
}
// 올바른 설계: 즉시 반환
BT::NodeStatus tick() override
{
    // 비동기 요청 전송
    auto future = service_client_->async_send_request(
        request);

    // 즉시 완료 여부 확인
    if (future.wait_for(std::chrono::milliseconds(0))
        == std::future_status::ready)
    {
        auto result = future.get();
        return result->success
            ? BT::NodeStatus::SUCCESS
            : BT::NodeStatus::FAILURE;
    }

    // 즉시 완료되지 않으면 FAILURE 반환
    // (또는 StatefulActionNode로 전환)
    return BT::NodeStatus::FAILURE;
}

3.2 부작용이 있는 동기 노드

tick()에서 부작용(ROS2 토픽 발행, 파일 쓰기, 하드웨어 명령 전송 등)을 수행하는 동기 노드는, tick()이 호출된 시점에서 이미 부작용이 발생한 상태이다. 이후 halt가 호출되더라도 이미 발생한 부작용을 되돌리는 것은 동기 노드의 범위를 벗어난다.

부작용의 취소가 필요한 경우, 보상 동작을 별도의 노드로 구현하고 행동 트리에서 명시적으로 호출하는 것이 올바른 설계이다.

<Sequence>
    <SendCommand command="START_MOTOR" />
    <SomeTask />
    <!-- SomeTask 실패 시 보상 동작으로 모터 정지 -->
</Sequence>

4. 동기 노드의 halt 커스터마이징

대부분의 동기 노드에서는 기본 halt 구현으로 충분하다. 그러나 동기 노드가 내부적으로 캐시, 발행자 객체, 또는 기타 장기 자원을 보유하는 경우, halt를 재정의하여 이러한 자원을 정리할 수 있다.

class CachedSyncAction : public BT::SyncActionNode
{
public:
    BT::NodeStatus tick() override
    {
        // 캐시 활용
        if (!publisher_)
        {
            publisher_ =
                node_->create_publisher<std_msgs::msg::String>(
                    topic_, rclcpp::QoS(10));
        }
        // ...
        return BT::NodeStatus::SUCCESS;
    }

    void halt() override
    {
        publisher_.reset();  // 자원 해제
        BT::SyncActionNode::halt();  // 기본 구현 호출
    }

private:
    rclcpp::Publisher<std_msgs::msg::String>::SharedPtr
        publisher_;
};

5. SyncActionNode와 StatefulActionNode의 Halt 비교

특성SyncActionNodeStatefulActionNode
Halt 호출 빈도극히 드묾빈번
Halt 구현 필요성대부분 불필요필수
자원 정리선택적필수
안전 전환해당 없음필수
진행 중 작업 취소해당 없음필수

6. 설계 지침

  1. SyncActionNodetick() 메서드는 수 밀리초 이내에 반환되어야 한다.
  2. tick() 실행 시간이 수십 밀리초를 초과하는 경우, StatefulActionNode로 전환하여 비동기 처리한다.
  3. 대부분의 동기 노드에서는 halt를 재정의할 필요가 없다.
  4. 동기 노드가 장기 자원(발행자, 구독자, 캐시 등)을 보유하는 경우에만 halt를 재정의하여 자원을 정리한다.
  5. halt 재정의 시 반드시 기반 클래스의 halt()를 호출하여 노드 상태를 IDLE로 설정한다.

7. 참고 문헌

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

버전: 2026-04-04