1294.49 ReactiveFallback의 실행 알고리즘

1. 알고리즘의 개요

ReactiveFallback의 실행 알고리즘은 매 Tick에서 항상 첫 번째 자식(인덱스 0)부터 순차적으로 평가를 시작하며, 내부에 재진입 인덱스를 유지하지 않는다. ReactiveSequence 알고리즘의 대칭적 쌍대로서, SUCCESS와 FAILURE의 역할이 교환된 구조를 가진다(Colledanchise & Ogren, 2018).

2. 알고리즘의 단계별 절차

2.1 단계 1: 초기화

Tick이 수신되면, 반복 인덱스 i를 0으로 설정한다.

i ← 0

2.2 단계 2: 자식 순차 평가

인덱스 i의 자식에 대해 executeTick()을 호출한다.

status ← children[i].executeTick()

2.3 단계 3: 반환 상태에 따른 처리

경우 1: FAILURE 반환

현재 자식이 FAILURE를 반환하면, 인덱스를 증가시키고 다음 자식의 평가로 진행한다.

if status == FAILURE:
    i ← i + 1
    if i == N:
        return FAILURE
    else:
        단계 2로 이동

경우 2: SUCCESS 반환

현재 자식이 SUCCESS를 반환하면, 이후에 RUNNING 상태인 자식이 있을 경우 해당 자식을 Halt하고, ReactiveFallback 전체가 SUCCESS를 반환한다.

if status == SUCCESS:
    resetChildren()
    return SUCCESS

경우 3: RUNNING 반환

현재 자식이 RUNNING을 반환하면, 이후의 모든 자식을 Halt하고 RUNNING을 반환한다.

if status == RUNNING:
    haltChildrenAfter(i)
    return RUNNING

3. 알고리즘의 형식적 기술

\text{ReactiveFallback.tick}() = \begin{cases} \text{FAILURE} & \text{if } \forall i \in [0, N): c_i = \text{FAILURE} \\ \text{SUCCESS} & \text{if } \exists k: c_k = \text{SUCCESS} \land \forall j < k: c_j = \text{FAILURE} \\ \text{RUNNING} & \text{if } \exists k: c_k = \text{RUNNING} \land \forall j < k: c_j = \text{FAILURE} \end{cases}

이 형식적 정의는 ReactiveSequence의 정의에서 SUCCESS와 FAILURE가 교환된 대칭 구조이다.

4. ReactiveSequence 알고리즘과의 대칭적 대응

알고리즘 요소ReactiveSequenceReactiveFallback
시작 인덱스항상 0항상 0
계속 진행 조건SUCCESSFAILURE
조기 종료 (종료)FAILURESUCCESS
전체 완료 반환모든 자식 SUCCESS → SUCCESS모든 자식 FAILURE → FAILURE
RUNNING 처리Halt 후속, RUNNING 반환Halt 후속, RUNNING 반환

5. 실행 추적 예시

5.1 정상 실행: 대안 순차 탐색

자식: [CondA, CondB, AsyncAct]

Tick 1:
  i=0: CondA.executeTick() → FAILURE
  i=1: CondB.executeTick() → FAILURE
  i=2: AsyncAct.executeTick() → RUNNING
  haltChildrenAfter(2): (더 이상 자식 없음)
  → return RUNNING

5.2 우선순위 전환: 앞쪽 조건 성공

Tick 2:
  i=0: CondA.executeTick() → SUCCESS    (재평가에서 변화 감지)
  resetChildren():
    children[2](AsyncAct): RUNNING → halt()
  → return SUCCESS

5.3 대안 변경: RUNNING 자식의 이동

자식: [CondA, AsyncAct1, AsyncAct2]

Tick 1:
  i=0: CondA → FAILURE
  i=1: AsyncAct1 → RUNNING
  haltChildrenAfter(1):
    children[2](AsyncAct2): IDLE → 건너뜀
  → return RUNNING

Tick 2 (AsyncAct1 실패):
  i=0: CondA → FAILURE
  i=1: AsyncAct1 → FAILURE
  i=2: AsyncAct2 → RUNNING
  → return RUNNING

5.4 모든 대안 소진

Tick 3:
  i=0: CondA → FAILURE
  i=1: AsyncAct1 → FAILURE
  i=2: AsyncAct2 → FAILURE
  resetChildren()
  → return FAILURE

6. 알고리즘의 시간 복잡도

6.1 최선의 경우

첫 번째 자식이 SUCCESS를 반환하면, 1개의 노드만 평가된다.

T_{best} = O(1)

최악의 경우

모든 자식이 FAILURE를 반환하거나 마지막 자식이 RUNNING을 반환하면, N개의 노드가 평가된다.

T_{worst} = O(N)

6.2 RUNNING 지속 시의 총 비용

비동기 액션이 인덱스 k에 위치하고 M Tick 동안 RUNNING을 유지하는 경우:

T_{total} = (k + 1) \times M

BehaviorTree.CPP v4에서의 알고리즘 구현

BehaviorTree.CPP v4에서 ReactiveFallback의 tick() 메서드는 다음과 같이 구현된다(Faconti, 2022).

NodeStatus ReactiveFallback::tick()
{
    bool all_skipped = true;
    for (size_t i = 0; i < childrenCount(); i++)
    {
        TreeNode* child = children_nodes_[i];
        const NodeStatus child_status = child->executeTick();

        switch (child_status)
        {
            case NodeStatus::RUNNING:
                for (size_t j = i + 1; j < childrenCount(); j++)
                {
                    haltChild(j);
                }
                return NodeStatus::RUNNING;

            case NodeStatus::SUCCESS:
                resetChildren();
                return NodeStatus::SUCCESS;

            case NodeStatus::FAILURE:
                all_skipped = false;
                break;

            case NodeStatus::SKIPPED:
                break;

            case NodeStatus::IDLE:
                throw LogicError("Child node returned IDLE");
        }
    }
    resetChildren();
    return all_skipped ? NodeStatus::SKIPPED : NodeStatus::FAILURE;
}

이 구현에서 RUNNING 자식이 발견되면 해당 인덱스 이후의 모든 자식에 대해 haltChild()를 호출한다.

알고리즘의 불변 조건

  1. 단일 RUNNING 자식: 매 Tick 종료 시, 최대 하나의 자식만 RUNNING 상태를 유지한다.
  2. 순차적 평가 보장: 인덱스 i의 자식은 인덱스 0부터 i-1까지의 모든 자식이 FAILURE를 반환한 후에만 평가된다.
  3. Halt 완전성: SUCCESS 반환 시, 모든 RUNNING 자식이 Halt된다.
  4. 우선순위 유효성: RUNNING 상태가 유지되는 동안, 모든 앞쪽 대안이 매 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/