1293.39 Running 상태의 메모리 (Memory) 개념

1. 메모리 개념의 정의

행동 트리(Behavior Tree)에서 메모리(Memory)란, 제어 노드가 이전 Tick에서 자식 노드의 반환 상태를 기억하고, 후속 Tick에서 이 기억에 기반하여 Tick 전파의 시작 지점을 결정하는 메커니즘이다. 구체적으로, 메모리를 가진 제어 노드(WithMemory)는 자식이 RUNNING을 반환한 경우 해당 자식의 인덱스를 기억하고, 다음 Tick에서 이전에 완료된 자식을 건너뛰어 RUNNING 중인 자식부터 Tick을 재개한다(Colledanchise & Ogren, 2018).

2. 메모리의 필요성

행동 트리의 실행 모델에서 제어 노드는 매 Tick마다 자식 노드에 Tick을 전파해야 한다. 자식 노드가 비동기적으로 동작하여 RUNNING을 반환하면, 다음 Tick에서 해당 자식의 작업 완료 여부를 확인하기 위해 다시 Tick을 전파해야 한다. 이때 두 가지 설계 선택이 가능하다.

  1. 메모리 없음(WithoutMemory): 매 Tick마다 첫 번째 자식부터 모든 자식을 재평가한다.
  2. 메모리 있음(WithMemory): 이전에 완료된 자식을 건너뛰고 RUNNING 중인 자식부터 재개한다.

메모리의 유무는 제어 노드의 동작 특성을 근본적으로 변경하며, 동일한 트리 구조에서도 전혀 다른 실행 흐름을 생성한다.

3. 메모리의 내부 구현

메모리는 제어 노드 내부에 유지되는 인덱스 변수로 구현된다. 이 변수는 다음 Tick에서 Tick 전파를 시작해야 하는 자식의 인덱스를 저장한다.

class SequenceWithMemory : public BT::ControlNode {
private:
    size_t current_child_index_ = 0;  // 메모리: 재개 인덱스

public:
    BT::NodeStatus tick() override {
        // current_child_index_부터 시작 (이전 완료 자식 건너뜀)
        while (current_child_index_ < children_count()) {
            auto status = children_[current_child_index_]->executeTick();
            
            if (status == BT::NodeStatus::RUNNING) {
                return BT::NodeStatus::RUNNING;
            }
            if (status == BT::NodeStatus::FAILURE) {
                current_child_index_ = 0;  // 리셋
                return BT::NodeStatus::FAILURE;
            }
            // SUCCESS: 다음 자식으로 진행
            current_child_index_++;
        }
        current_child_index_ = 0;  // 리셋
        return BT::NodeStatus::SUCCESS;
    }
    
    void halt() override {
        current_child_index_ = 0;  // 리셋
        ControlNode::halt();
    }
};

4. 메모리 인덱스의 생명 주기

메모리 인덱스는 다음과 같은 생명 주기를 가진다.

4.1 초기화

제어 노드가 생성되거나 Halt될 때, 메모리 인덱스는 0으로 초기화된다.

4.2 갱신

자식이 완료 상태(SUCCESS 또는 FAILURE)를 반환할 때, 메모리 인덱스가 갱신된다.

  • Sequence: 자식이 SUCCESS를 반환하면 인덱스가 증가한다.
  • Fallback: 자식이 FAILURE를 반환하면 인덱스가 증가한다.

4.3 유지

자식이 RUNNING을 반환하면, 메모리 인덱스는 현재 값을 유지한다. 다음 Tick에서 이 인덱스부터 Tick 전파가 재개된다.

4.4 리셋

제어 노드가 최종 상태(SUCCESS 또는 FAILURE)를 반환하거나 Halt될 때, 메모리 인덱스는 0으로 리셋된다.

메모리 인덱스 생명 주기:

생성/Halt → [0] → 자식 0 완료 → [1] → 자식 1 RUNNING → [1] 유지
                                                          ↓
                                  다음 Tick: 자식 1부터 재개 → [1]
                                                          ↓
                                  자식 1 완료 → [2] → ... → 완료/실패 → [0] 리셋

5. Sequence에서의 메모리 동작

WithMemory Sequence에서 메모리는 이미 SUCCESS를 반환한 자식의 재실행을 방지한다.

Tick 1: Sequence[Memory]
  index=0 → Child_0.tick() → SUCCESS
  index=1 → Child_1.tick() → SUCCESS
  index=2 → Child_2.tick() → RUNNING
  메모리 유지: index=2
  반환: RUNNING

Tick 2: Sequence[Memory]
  index=2 → Child_2.tick() → RUNNING   (Child_0, Child_1 건너뜀)
  메모리 유지: index=2
  반환: RUNNING

Tick 3: Sequence[Memory]
  index=2 → Child_2.tick() → SUCCESS   (Child_0, Child_1 건너뜀)
  메모리 리셋: index=0
  반환: SUCCESS

이 동작에서 Child_0과 Child_1은 Tick 1에서 SUCCESS를 반환한 후, 후속 Tick에서 재Tick되지 않는다. 이는 이미 성공적으로 완료된 단계를 불필요하게 반복하지 않는 효율적인 실행을 가능하게 한다.

6. Fallback에서의 메모리 동작

WithMemory Fallback에서 메모리는 이미 FAILURE를 반환한 자식의 재시도를 방지한다.

Tick 1: Fallback[Memory]
  index=0 → Child_0.tick() → FAILURE
  index=1 → Child_1.tick() → RUNNING
  메모리 유지: index=1
  반환: RUNNING

Tick 2: Fallback[Memory]
  index=1 → Child_1.tick() → RUNNING   (Child_0 건너뜀)
  메모리 유지: index=1
  반환: RUNNING

Tick 3: Fallback[Memory]
  index=1 → Child_1.tick() → SUCCESS   (Child_0 건너뜀)
  메모리 리셋: index=0
  반환: SUCCESS

7. 메모리가 없는 경우의 동작

메모리가 없는 제어 노드(WithoutMemory, Reactive)는 매 Tick마다 인덱스 0부터 모든 자식을 재평가한다. 이는 메모리 인덱스 변수가 존재하지 않거나, 매 Tick의 시작 시 0으로 리셋되는 것과 동등하다.

Tick 1: ReactiveSequence (메모리 없음)
  → Child_0.tick() → SUCCESS
  → Child_1.tick() → SUCCESS
  → Child_2.tick() → RUNNING
  반환: RUNNING

Tick 2: ReactiveSequence (메모리 없음)
  → Child_0.tick() → SUCCESS  (재평가)
  → Child_1.tick() → SUCCESS  (재평가)
  → Child_2.tick() → RUNNING
  반환: RUNNING

8. 메모리의 의미론적 해석

메모리의 유무는 제어 노드의 의미론(semantics)을 근본적으로 변경한다.

제어 노드WithMemory 의미WithoutMemory 의미
Sequence“단계적 작업 수행: 완료된 단계는 재실행하지 않음”“모든 조건이 지속적으로 충족되어야 함”
Fallback“순차적 대안 시도: 실패한 대안은 재시도하지 않음”“우선순위 기반 선택: 상위 대안 복구 시 즉시 전환”

WithMemory는 작업의 진행(progression)을 모델링하고, WithoutMemory는 조건의 감시(monitoring)를 모델링한다.

9. 메모리와 노드 상태의 관계

메모리는 제어 노드 수준에서 관리되며, 개별 자식 노드의 내부 상태와는 독립적이다. 그러나 두 개념은 밀접하게 상호작용한다.

  • 메모리 인덱스 갱신 시: 완료된 자식의 상태는 IDLE로 리셋되지 않는다. 자식은 자신의 마지막 반환 상태를 유지하며, 제어 노드가 메모리 인덱스를 통해 해당 자식을 건너뛴다.
  • 메모리 리셋 시: 제어 노드의 Halt가 호출되면 메모리 인덱스가 리셋되고, 모든 자식에 Halt가 전파되어 IDLE 상태로 리셋된다.

10. BehaviorTree.CPP에서의 메모리 표현

BehaviorTree.CPP v4에서 메모리의 유무는 XML 태그명으로 구분된다(Faconti, 2022).

<!-- WithMemory -->
<Sequence>...</Sequence>
<Fallback>...</Fallback>

<!-- WithoutMemory (Reactive) -->
<ReactiveSequence>...</ReactiveSequence>
<ReactiveFallback>...</ReactiveFallback>

BehaviorTree.CPP v3에서는 SequenceStar, FallbackStar라는 접미사로 WithMemory를 표현하였으나, v4에서는 기본 SequenceFallback이 WithMemory로 동작하며, WithoutMemory 변형에 Reactive 접두사를 사용한다.

11. 메모리의 설계 지침

11.1 WithMemory를 선택해야 하는 경우

  • 자식 노드가 순차적 단계를 나타내며, 이전 단계의 재실행이 불필요하거나 비효율적인 경우
  • 자식 노드의 실행에 부수 효과(side effect)가 있어 재실행이 부적절한 경우
  • 이전 자식의 반환 상태가 시간이 지나도 변하지 않는 경우

11.2 WithoutMemory를 선택해야 하는 경우

  • 전제 조건의 지속적 충족을 감시해야 하는 경우
  • 우선순위가 높은 대안이 복구되면 즉시 전환해야 하는 경우
  • 환경의 동적 변화에 실시간으로 반응해야 하는 경우

참고 문헌

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