1293.28 Sequence 노드의 자식 재진입 규칙
1. 재진입 규칙의 필요성
Sequence 노드에서 자식 노드가 RUNNING을 반환하면, 다음 Tick에서 해당 자식에 다시 Tick을 전달하여 작업의 완료 여부를 확인해야 한다. 이때 핵심적인 설계 결정은 RUNNING을 반환한 자식에 도달하기까지의 이전 자식들을 다시 평가할 것인지의 여부이다. 이 결정이 Sequence 노드의 자식 재진입 규칙(child re-entry rule)이며, 메모리(Memory) 속성에 의해 결정된다(Colledanchise & Ogren, 2018).
2. WithMemory 모드의 재진입 규칙
WithMemory 모드의 Sequence 노드는 이전 Tick에서 SUCCESS를 반환한 자식의 다음 인덱스를 기억하고, 후속 Tick에서는 기억된 인덱스의 자식부터 실행을 재개한다. 이미 SUCCESS를 반환한 자식은 재평가하지 않는다.
2.1 동작 과정
Tick 1: Sequence[Memory]
→ Child_0.tick() → SUCCESS (인덱스 기억: 1)
→ Child_1.tick() → SUCCESS (인덱스 기억: 2)
→ Child_2.tick() → RUNNING (인덱스 기억: 2)
반환: RUNNING
Tick 2: Sequence[Memory]
→ Child_2.tick() → RUNNING (Child_0, Child_1 건너뜀)
반환: RUNNING
Tick 3: Sequence[Memory]
→ Child_2.tick() → SUCCESS
→ Child_3.tick() → SUCCESS
반환: SUCCESS (인덱스 리셋: 0)
2.2 인덱스 리셋 조건
WithMemory 모드에서 기억된 인덱스는 다음 조건에서 0으로 리셋된다.
- Sequence가 SUCCESS를 반환할 때 (모든 자식 완료)
- Sequence가 FAILURE를 반환할 때 (자식 중 하나가 실패)
- Sequence에 Halt가 호출될 때 (외부에 의한 중단)
// 개념적 구현
NodeStatus SequenceWithMemory::tick() {
while (current_idx_ < children_.size()) {
auto status = children_[current_idx_]->executeTick();
if (status == NodeStatus::RUNNING) {
return NodeStatus::RUNNING;
// current_idx_ 유지
}
if (status == NodeStatus::FAILURE) {
haltChildren();
current_idx_ = 0; // 리셋
return NodeStatus::FAILURE;
}
current_idx_++; // SUCCESS: 다음으로
}
current_idx_ = 0; // 리셋
return NodeStatus::SUCCESS;
}
void SequenceWithMemory::halt() {
current_idx_ = 0; // 리셋
ControlNode::halt();
}
2.3 WithMemory 모드의 이점과 제약
이점:
- 이미 완료된 자식의 불필요한 재실행을 방지하여 Tick 실행 시간을 절약한다.
- 부수 효과(side effect)를 가지는 액션 노드가 중복 실행되는 것을 방지한다.
- 장시간 소요되는 작업 중에 매 Tick마다 이전 단계를 재검증하지 않아도 된다.
제약:
- 이전 자식의 조건이 변화하더라도 이를 감지하지 못한다. 예를 들어, 첫 번째 자식인 조건 노드가 SUCCESS를 반환한 후 환경이 변화하여 해당 조건이 더 이상 충족되지 않더라도, WithMemory 모드에서는 이 변화를 인지하지 못한다.
3. WithoutMemory (Reactive) 모드의 재진입 규칙
WithoutMemory 모드, 즉 ReactiveSequence 노드는 매 Tick마다 첫 번째 자식부터 모든 자식을 재평가한다. RUNNING 중인 자식에 도달하면 해당 자식을 재진입시킨다.
3.1 동작 과정
Tick 1: ReactiveSequence
→ Child_0.tick() → SUCCESS
→ Child_1.tick() → RUNNING
반환: RUNNING
Tick 2: ReactiveSequence
→ Child_0.tick() → SUCCESS (재평가)
→ Child_1.tick() → RUNNING (재진입)
반환: RUNNING
Tick 3: ReactiveSequence
→ Child_0.tick() → FAILURE (재평가, 조건 변화)
→ Child_1에 Halt 호출 (RUNNING 중인 자식 중단)
반환: FAILURE
3.2 Reactive 모드에서의 Halt 유발
ReactiveSequence에서 이전 자식이 재평가 시 FAILURE를 반환하면, 현재 RUNNING 중인 자식에 Halt가 호출되어 비동기 작업이 중단된다. 이는 전제 조건이 더 이상 충족되지 않는 상황에서 불필요한 작업을 즉시 중단하는 안전 메커니즘이다.
3.3 Reactive 모드의 이점과 제약
이점:
- 조건 변화에 대한 즉각적인 반응이 가능하다.
- 전제 조건이 위반되면 진행 중인 작업을 즉시 중단하여 안전성을 보장한다.
제약:
- 매 Tick마다 이전 자식을 재평가하므로 Tick 실행 시간이 증가한다.
- 조건 노드가 비용이 높은 연산을 수행하는 경우 성능에 영향을 미친다.
- SUCCESS를 반환한 액션 노드가 재실행되면 부수 효과가 중복 발생할 수 있으므로, ReactiveSequence의 자식 중 액션 노드는 하나만 배치하는 것이 일반적이다.
4. 두 모드의 비교
| 특성 | WithMemory | WithoutMemory (Reactive) |
|---|---|---|
| 이전 자식 재평가 | 하지 않음 | 매 Tick마다 수행 |
| 조건 변화 감지 | 불가 | 즉시 감지 |
| Tick 실행 비용 | 낮음 | 높음 |
| 전형적 사용 패턴 | 순차적 작업 수행 | 조건 유지 + 액션 실행 |
| 부수 효과 안전성 | 안전 (재실행 없음) | 주의 필요 (조건만 재평가 권장) |
5. 전형적 사용 패턴의 비교
5.1 WithMemory 패턴: 단계적 작업 수행
<Sequence>
<OpenGripper/> <!-- 한 번만 실행 -->
<MoveToObject/> <!-- 한 번만 실행 -->
<CloseGripper/> <!-- 한 번만 실행 -->
<MoveToDestination/> <!-- 한 번만 실행 -->
</Sequence>
각 단계가 한 번 성공하면 다음 단계로 진행하고, 이전 단계를 반복하지 않는다.
5.2 Reactive 패턴: 조건 감시 + 액션 수행
<ReactiveSequence>
<IsBatteryAbove threshold="10"/> <!-- 매 Tick 재평가 -->
<IsPathClear/> <!-- 매 Tick 재평가 -->
<NavigateToGoal goal="{target}"/> <!-- RUNNING 유지 -->
</ReactiveSequence>
네비게이션 진행 중에도 매 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/