1294.43 FallbackWithMemory의 실행 알고리즘

1. 알고리즘의 개요

FallbackWithMemory의 실행 알고리즘은 current_child_idx에 기억된 인덱스부터 자식을 순차적으로 평가하여, 첫 번째로 SUCCESS 또는 RUNNING을 반환하는 자식을 찾는 과정이다. 이 알고리즘은 SequenceWithMemory 알고리즘의 대칭적 쌍대(dual)이며, SUCCESS와 FAILURE의 역할이 교환된 구조를 가진다(Colledanchise & Ogren, 2018).

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

2.1 단계 1: 시작 인덱스 결정

Tick이 수신되면, current_child_idx에 기억된 값을 시작 인덱스로 사용한다.

i ← current_child_idx

최초 Tick이거나 이전 Tick에서 SUCCESS/전체FAILURE로 종료된 경우, current_child_idx는 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:
        current_child_idx ← 0
        return FAILURE        // 모든 대안 소진
    else:
        단계 2로 이동

경우 2: SUCCESS 반환

현재 자식이 SUCCESS를 반환하면, 대안 탐색이 완료되었으므로 인덱스를 초기화하고 SUCCESS를 반환한다.

if status == SUCCESS:
    haltChildren()
    current_child_idx ← 0
    return SUCCESS

경우 3: RUNNING 반환

현재 자식이 RUNNING을 반환하면, 인덱스를 기억하고 RUNNING을 반환한다.

if status == RUNNING:
    current_child_idx ← i
    return RUNNING

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

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

여기서 \text{idx} = \text{current\_child\_idx}이다.

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

알고리즘 요소SequenceWithMemoryFallbackWithMemory
시작 인덱스current_child_idxcurrent_child_idx
다음 자식 진행SUCCESS 시FAILURE 시
즉시 반환 (성공)해당 없음SUCCESS 시
즉시 반환 (실패)FAILURE 시해당 없음
전체 완료 반환모든 자식 SUCCESS → SUCCESS모든 자식 FAILURE → FAILURE
인덱스 기억RUNNING 시RUNNING 시
인덱스 초기화FAILURE 또는 전체 SUCCESSSUCCESS 또는 전체 FAILURE

5. 실행 추적 예시

5.1 예시 1: 정상적인 대안 탐색

children: [ActA, ActB, ActC]

Tick 1:
  current_child_idx = 0
  i=0: ActA → FAILURE
  i=1: ActB → SUCCESS
  haltChildren()
  current_child_idx ← 0
  → SUCCESS

5.2 예시 2: 비동기 대안의 진행

children: [ActA, AsyncActB, ActC]

Tick 1:
  current_child_idx = 0
  i=0: ActA → FAILURE
  i=1: AsyncActB → RUNNING
  current_child_idx ← 1
  → RUNNING

Tick 2:
  current_child_idx = 1
  i=1: AsyncActB → RUNNING    (ActA 건너뜀)
  → RUNNING

Tick 3:
  current_child_idx = 1
  i=1: AsyncActB → SUCCESS    (ActA 건너뜀)
  haltChildren()
  current_child_idx ← 0
  → SUCCESS

5.3 예시 3: 대안 순차 이동

children: [AsyncActA, AsyncActB, ActC]

Tick 1:
  i=0: AsyncActA → RUNNING
  current_child_idx ← 0
  → RUNNING

Tick 2:
  i=0: AsyncActA → FAILURE
  i=1: AsyncActB → RUNNING
  current_child_idx ← 1
  → RUNNING

Tick 3:
  i=1: AsyncActB → FAILURE    (AsyncActA 건너뜀)
  i=2: ActC → SUCCESS
  current_child_idx ← 0
  → SUCCESS

5.4 예시 4: 모든 대안 소진

children: [ActA, AsyncActB, ActC]

Tick 1:
  i=0: ActA → FAILURE
  i=1: AsyncActB → RUNNING
  current_child_idx ← 1
  → RUNNING

Tick 2:
  i=1: AsyncActB → FAILURE
  i=2: ActC → FAILURE
  current_child_idx ← 0
  → FAILURE

6. BehaviorTree.CPP v4에서의 구현

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

NodeStatus FallbackNode::tick()
{
    const size_t children_count = childrenCount();

    if (status() == NodeStatus::IDLE)
    {
        skipped_count_ = 0;
    }

    setStatus(NodeStatus::RUNNING);

    while (current_child_idx_ < children_count)
    {
        TreeNode* current_child = children_nodes_[current_child_idx_];
        const NodeStatus child_status = current_child->executeTick();

        switch (child_status)
        {
            case NodeStatus::RUNNING:
                return NodeStatus::RUNNING;

            case NodeStatus::SUCCESS:
                resetChildren();
                current_child_idx_ = 0;
                return NodeStatus::SUCCESS;

            case NodeStatus::FAILURE:
                current_child_idx_++;
                break;

            case NodeStatus::SKIPPED:
                current_child_idx_++;
                skipped_count_++;
                break;

            case NodeStatus::IDLE:
                throw LogicError("Child returned IDLE");
        }
    }

    current_child_idx_ = 0;
    resetChildren();

    if (skipped_count_ == children_count)
        return NodeStatus::SKIPPED;

    return NodeStatus::FAILURE;
}

이 구현에서 while 루프가 current_child_idx_부터 시작하므로, 이전 Tick에서 기억된 인덱스 이전의 자식은 자동으로 건너뛰어진다.

7. 알고리즘의 불변 조건

  1. 단일 RUNNING 자식: 매 Tick 종료 시, 최대 하나의 자식만 RUNNING 상태이다.
  2. 단조 증가 진행: 단일 평가 주기 내에서 current_child_idx는 증가만 한다 (감소 없음).
  3. 초기화 보장: SUCCESS, 전체 FAILURE, Halt 후에는 반드시 current_child_idx가 0으로 초기화된다.
  4. 건너뛰기 일관성: 건너뛰어진 자식은 해당 평가 주기 내에서 executeTick()이 호출되지 않는다.

참고 문헌

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