1294.39 FallbackWithMemory (StatefulFallback)의 개념

1. FallbackWithMemory의 정의

FallbackWithMemory는 Fallback 노드의 변형으로, 이전 Tick에서 RUNNING을 반환한 자식의 인덱스를 기억하고, 다음 Tick에서 해당 인덱스부터 평가를 재개하는 제어 흐름 노드이다. 이전 Tick에서 FAILURE를 반환한 자식들은 건너뛰어지며, 이를 통해 이미 실패가 확인된 대안을 불필요하게 재시도하는 것을 방지한다(Colledanchise & Ogren, 2018).

“WithMemory“라는 수식어는 노드가 Tick 간에 상태(메모리)를 유지한다는 것을 의미하며, 이는 SequenceWithMemory에서의 메모리 개념과 동일하다.

2. 메모리 메커니즘

2.1 current_child_idx 상태 변수

FallbackWithMemory는 내부에 current_child_idx 상태 변수를 유지한다. 이 변수는 다음 Tick에서 평가를 시작할 자식의 인덱스를 기억한다.

초기 상태: current_child_idx = 0

상태 전이 규칙:
  자식이 RUNNING 반환 → current_child_idx ← 해당 인덱스 (유지)
  자식이 SUCCESS 반환 → current_child_idx ← 0 (초기화)
  모든 자식 FAILURE    → current_child_idx ← 0 (초기화)
  Halt 호출            → current_child_idx ← 0 (초기화)

2.2 메모리의 생성과 소멸

이벤트current_child_idx 변화의미
초기 상태0첫 자식부터 평가
자식 k가 RUNNINGkk번째 대안 시도 중
어떤 자식이 SUCCESS0대안 탐색 완료, 초기화
모든 자식 FAILURE0모든 대안 소진, 초기화
외부 Halt0강제 초기화

3. SequenceWithMemory와의 대칭적 관계

FallbackWithMemory와 SequenceWithMemory는 동일한 메모리 메커니즘을 가지며, SUCCESS와 FAILURE의 역할만 교환된다.

특성SequenceWithMemoryFallbackWithMemory
건너뛰는 자식의 상태이전에 SUCCESS인 자식이전에 FAILURE인 자식
진행 조건SUCCESS (다음 단계로)FAILURE (다음 대안으로)
종료 조건FAILURE (전체 실패)SUCCESS (대안 성공)
인덱스 초기화 조건FAILURE 또는 전체 SUCCESSSUCCESS 또는 전체 FAILURE

4. 동작 예시

4.1 기본 동작 흐름

children: [ActA, AsyncActB, ActC]

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

Tick 2: (인덱스 1부터 재개)
  i=1: AsyncActB → RUNNING    (ActA 건너뜀)
  → RUNNING

Tick 3: (인덱스 1부터 재개)
  i=1: AsyncActB → SUCCESS    (ActA 건너뜀)
  current_child_idx ← 0
  → SUCCESS

Tick 2와 3에서 ActA는 이전 Tick에서 FAILURE를 반환했으므로 건너뛰어진다.

4.2 FAILURE 전파 후 다음 대안 시도

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

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

AsyncActB가 FAILURE를 반환하면, 다음 대안인 ActC로 자동 진행한다.

4.3 모든 대안 소진

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

5. ReactiveFallback과의 비교

동일한 트리에서 FallbackWithMemory와 ReactiveFallback의 동작 차이를 비교한다.

<Fallback변형>
    <Condition ID="IsPrimaryPathClear"/>
    <Action ID="UseDetourPath"/>
</Fallback변형>

5.1 FallbackWithMemory의 동작

Tick 1: IsPrimaryPathClear→F, UseDetourPath→R (idx=1)
Tick 2: UseDetourPath→R                       (조건 건너뜀)
Tick 3: UseDetourPath→R                       (주 경로 정리됐지만 감지 못함)
Tick 4: UseDetourPath→S                       (우회 완료)
        → SUCCESS

주 경로가 Tick 3에서 정리되었지만, FallbackWithMemory는 이를 감지하지 못하고 우회 경로를 계속 사용한다.

5.2 ReactiveFallback의 동작

Tick 1: IsPrimaryPathClear→F, UseDetourPath→R
Tick 2: IsPrimaryPathClear→F, UseDetourPath→R
Tick 3: IsPrimaryPathClear→S                  (주 경로 정리 감지)
        UseDetourPath→Halt                    (우회 중단)
        → SUCCESS

ReactiveFallback에서는 주 경로가 정리되는 즉시 우회를 중단하고 SUCCESS를 반환한다.

6. BehaviorTree.CPP v4에서의 FallbackWithMemory

BehaviorTree.CPP v4에서 <Fallback> XML 태그는 기본적으로 WithMemory 동작을 수행한다. 별도의 FallbackWithMemory 태그는 존재하지 않으며, <Fallback>이 곧 FallbackWithMemory이다(Faconti, 2022).

<!-- BehaviorTree.CPP v4 -->
<Fallback>                   <!-- WithMemory 동작 (기본) -->
    <Action ID="TryMethodA"/>
    <Action ID="TryMethodB"/>
    <Action ID="TryMethodC"/>
</Fallback>

<ReactiveFallback>           <!-- 매 Tick 재평가 동작 -->
    <Condition ID="CondA"/>
    <Action ID="ActB"/>
</ReactiveFallback>

이 설계는 Sequence에서 <Sequence>가 기본적으로 WithMemory 동작을 수행하는 것과 일관적이다.

7. FallbackWithMemory의 적용 시나리오

7.1 비용이 높은 대안의 재시도 방지

대안의 실행 비용이 높은 경우, 이미 실패한 대안을 매 Tick마다 재시도하는 것은 비효율적이다.

<Fallback>
    <Action ID="ExpensiveDiagnostic"/>     <!-- 비용 높은 진단 -->
    <Action ID="ExpensiveRecalibration"/>  <!-- 비용 높은 재보정 -->
    <Action ID="ManualIntervention"/>      <!-- 수동 개입 요청 -->
</Fallback>

ExpensiveDiagnostic이 실패한 후 매 Tick마다 재실행하면 불필요한 자원 소모가 발생한다. WithMemory를 사용하면 실패한 진단을 건너뛰고 다음 대안으로 직접 진행한다.

7.2 순차적 복구 단계

복구 절차가 단계적으로 진행되어야 하며, 이전 단계를 반복할 필요가 없는 경우에 적합하다.

<Fallback>
    <Action ID="SoftReset"/>
    <Action ID="HardReset"/>
    <Action ID="FactoryReset"/>
</Fallback>

SoftReset이 실패하면 HardReset을 시도하고, 그것도 실패하면 FactoryReset을 시도한다. SoftReset을 매번 재시도하는 것은 의미가 없다.


참고 문헌

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