1293.24 노드의 Running에서 Failure로의 전이

1. RUNNING에서 FAILURE 전이의 의미

RUNNING에서 FAILURE로의 전이는 행동 트리(Behavior Tree) 노드가 수행하던 비동기 작업이 실패로 종결되었음을 나타내는 상태 변화이다. 이 전이는 노드가 RUNNING 상태에서 후속 Tick을 수신하여 작업의 상태를 확인한 결과, 작업이 더 이상 성공적으로 완료될 수 없다고 판단한 시점에서 발생한다(Colledanchise & Ogren, 2018).

FAILURE는 작업의 비정상적 종결을 의미하는 것이 아니라, 해당 노드가 목표로 하는 결과를 달성하지 못하였음을 정상적으로 보고하는 것이다. 행동 트리에서 FAILURE는 예외(exception)가 아닌 예상된 흐름의 일부이며, 부모 노드의 제어 로직에 의해 대안적 행동으로 전환되는 기점이 된다.

2. FAILURE 전이의 발생 원인

비동기 노드에서 RUNNING → FAILURE 전이를 유발하는 원인은 다양하다.

2.1 작업 자체의 실패

외부 시스템이 수행하던 작업이 실패한 경우이다. ROS2 액션 서버가 ABORTED 상태를 반환하거나, 네비게이션 경로가 차단되어 목표에 도달할 수 없는 경우가 이에 해당한다.

BT::NodeStatus onRunning() override {
    auto status = goal_handle_->get_status();
    
    if (status == action_msgs::msg::GoalStatus::STATUS_ABORTED) {
        auto result = action_client_->get_result();
        RCLCPP_WARN(logger_, "Action aborted: %s", 
                    result.error_message.c_str());
        return BT::NodeStatus::FAILURE;
    }
    
    if (status == action_msgs::msg::GoalStatus::STATUS_CANCELED) {
        return BT::NodeStatus::FAILURE;
    }
    
    if (status == action_msgs::msg::GoalStatus::STATUS_EXECUTING) {
        return BT::NodeStatus::RUNNING;
    }
    
    return BT::NodeStatus::FAILURE;
}

2.2 타임아웃 초과

작업이 허용된 시간 내에 완료되지 못한 경우이다. 노드가 자체적으로 타임아웃을 관리하거나, 데코레이터 노드에 의해 외부에서 시간 제한이 적용될 수 있다.

BT::NodeStatus onRunning() override {
    auto elapsed = std::chrono::steady_clock::now() - start_time_;
    if (elapsed > timeout_duration_) {
        RCLCPP_WARN(logger_, "Action timed out after %.1f seconds",
            std::chrono::duration<double>(elapsed).count());
        cancel_action();
        return BT::NodeStatus::FAILURE;
    }
    
    if (is_action_complete()) {
        return BT::NodeStatus::SUCCESS;
    }
    
    return BT::NodeStatus::RUNNING;
}

2.3 전제 조건의 위반

작업 수행 중에 전제 조건(precondition)이 더 이상 충족되지 않게 된 경우이다. 예를 들어, 물체 파지 작업 중 대상 물체가 시야에서 사라지거나, 배터리 잔량이 임계값 이하로 감소하는 경우가 해당한다. 이러한 전제 조건의 검증은 일반적으로 ReactiveSequence의 조건 노드에 의해 수행되며, 조건 노드가 FAILURE를 반환하면 ReactiveSequence가 액션 노드를 Halt하는 방식으로 동작한다. 그러나 액션 노드 자체적으로 내부 전제 조건을 검증하여 FAILURE를 반환하는 것도 가능하다.

2.4 통신 장애

ROS2 통신의 장애로 인해 액션 서버와의 연결이 끊기거나, 서비스 응답이 수신되지 않는 경우이다.

3. FAILURE 전이 시 수행되는 처리

3.1 작업 취소 요청

비동기 작업이 외부 시스템에서 진행 중인 경우, FAILURE 반환 전에 해당 작업의 취소를 요청해야 한다. ROS2 액션 클라이언트의 cancel_goal() 호출이 대표적이다. 취소 요청 없이 FAILURE를 반환하면, 외부 시스템에서 작업이 계속 진행되어 자원이 낭비되거나 예기치 않은 동작이 발생할 수 있다.

3.2 오류 정보의 기록

FAILURE의 원인을 블랙보드에 기록하여 후속 노드(예: 복구 행동 노드)가 적절한 대응을 결정할 수 있도록 한다.

BT::NodeStatus onRunning() override {
    if (is_action_aborted()) {
        setOutput("error_code", get_error_code());
        setOutput("error_message", get_error_message());
        return BT::NodeStatus::FAILURE;
    }
    // ...
}

3.3 자원 해제

RUNNING 상태에서 사용하던 자원을 적절히 해제한다. SUCCESS 전이와 마찬가지로 타이머, 버퍼, 연결 등의 자원이 해제되어야 하며, 특히 FAILURE 경로에서의 자원 해제가 누락되지 않도록 주의해야 한다.

4. FAILURE 전이가 부모 노드에 미치는 영향

자식 노드의 FAILURE 반환은 부모 노드의 유형에 따라 상이한 후속 동작을 유발한다.

부모 노드 유형자식 FAILURE 시 부모의 동작
Sequence나머지 자식 건너뛰고 즉시 FAILURE 반환
Fallback다음 자식으로 Tick 전파 (대안 시도)
Parallel실패 카운트 증가, 임계값 도달 시 FAILURE
ReactiveSequence즉시 FAILURE 반환, RUNNING 자식 Halt
ReactiveFallback다음 자식으로 Tick 전파 (대안 시도)

Fallback 노드에서의 FAILURE는 현재 대안이 작동하지 않으므로 다음 대안을 시도하라는 신호이다. 이 메커니즘을 통해 행동 트리는 복수의 전략을 순차적으로 시도하는 견고한 의사 결정을 구현한다. Sequence 노드에서의 FAILURE는 전체 순차 계획의 실패를 의미하며, 상위 Fallback 노드에 의한 대안적 계획으로의 전환을 유발할 수 있다.

5. FAILURE의 전파와 복구

RUNNING → FAILURE 전이는 행동 트리의 복구(recovery) 메커니즘과 밀접하게 연관된다. 하위 노드의 FAILURE가 상위 Fallback 노드까지 전파되면, Fallback 노드는 다음 자식(복구 행동)에 Tick을 전파하여 실패 상황에 대한 대응을 시도한다.

Root (Sequence)
├── ReactiveSequence
│   ├── CheckBattery          → SUCCESS
│   └── NavigateToGoal        → FAILURE (경로 차단)
└── [이 노드는 도달하지 않음]

→ Root가 FAILURE 반환
→ 상위 Fallback이 존재하면 복구 시도

이러한 계층적 실패 전파와 복구 메커니즘은 행동 트리의 핵심적인 강점 중 하나이며, 복잡한 로봇 임무에서 예상치 못한 상황에 대한 견고한 대응을 가능하게 한다.

6. FAILURE와 예외의 구분

행동 트리에서 FAILURE는 예외(exception)와 구별되어야 한다. FAILURE는 노드가 정상적인 평가 과정을 통해 목표를 달성하지 못하였음을 보고하는 정상적 결과이다. 반면, C++ 예외는 프로그래밍 오류, 메모리 부족, 잘못된 입력 등 예상하지 못한 비정상적 상황을 나타낸다.

BehaviorTree.CPP에서 tick() 메서드 내에서 발생한 C++ 예외는 프레임워크에 의해 포착되어 해당 노드를 FAILURE 상태로 전환시킨다. 그러나 이는 설계된 FAILURE 처리가 아니므로, 예외 발생 시 자원 정리가 불완전할 수 있다. 따라서 예상 가능한 실패 상황은 반드시 명시적인 FAILURE 반환으로 처리하고, C++ 예외는 진정한 프로그래밍 오류에 대해서만 사용해야 한다.


참고 문헌

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