1294.85 BehaviorTree.CPP의 FallbackNode 클래스
1. FallbackNode 클래스의 개요
BehaviorTree.CPP v4에서 FallbackNode 클래스는 FallbackWithMemory(StatefulFallback) 동작을 구현하는 제어 노드이다. SequenceNode와 대칭적 구조를 가지며, current_child_idx_ 멤버 변수를 통해 마지막 RUNNING 자식의 위치를 기억한다. XML에서 <Fallback> 태그로 선언된다(Faconti, 2022).
2. 클래스 선언
namespace BT {
class FallbackNode : public ControlNode {
public:
FallbackNode(const std::string& name,
const NodeConfig& config);
virtual ~FallbackNode() override = default;
static PortsList providedPorts() { return {}; }
virtual void halt() override;
private:
size_t current_child_idx_;
bool all_skipped_;
virtual BT::NodeStatus tick() override;
};
} // namespace BT
3. tick() 메서드의 상세 분석
3.1 전체 구현
NodeStatus FallbackNode::tick() {
const size_t children_count = children_nodes_.size();
if (status() == NodeStatus::IDLE) {
all_skipped_ = true;
}
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:
all_skipped_ = false;
current_child_idx_++;
break;
case NodeStatus::SKIPPED:
current_child_idx_++;
break;
}
}
current_child_idx_ = 0;
return all_skipped_ ? NodeStatus::SKIPPED : NodeStatus::FAILURE;
}
3.2 SequenceNode와의 대칭적 관계
FallbackNode::tick()은 SequenceNode::tick()과 SUCCESS와 FAILURE의 역할만 정확히 교환된 구조이다:
| 자식 반환 상태 | SequenceNode | FallbackNode |
|---|---|---|
| SUCCESS | 다음 자식으로 진행 | 즉시 SUCCESS 반환 (조기 종료) |
| FAILURE | 즉시 FAILURE 반환 (조기 종료) | 다음 자식으로 진행 |
| RUNNING | 인덱스 유지, RUNNING 반환 | 인덱스 유지, RUNNING 반환 |
| 전체 순회 완료 | SUCCESS 반환 | FAILURE 반환 |
3.3 동작 분석
-
메모리 기반 재진입:
current_child_idx_가 이전 Tick에서 RUNNING이었던 자식의 인덱스를 유지하므로, 이전에 FAILURE를 반환한 자식은 건너뛴다. -
SUCCESS의 조기 종료: 자식이 SUCCESS를 반환하면 즉시 전체 Fallback이 SUCCESS를 반환한다. 이는 “하나라도 성공하면 충분하다“는 OR 의미론의 구현이다.
-
FAILURE의 진행: 자식이 FAILURE를 반환하면 인덱스를 증가시키고 다음 대안을 시도한다.
-
전체 FAILURE: 모든 자식이 FAILURE를 반환하면 인덱스를 0으로 초기화하고 FAILURE를 반환한다.
4. halt() 메서드
void FallbackNode::halt() {
current_child_idx_ = 0;
ControlNode::halt();
}
SequenceNode::halt()와 동일한 구조이다. current_child_idx_를 0으로 초기화하고, 부모 클래스의 halt()를 호출하여 모든 RUNNING 자식을 Halt한다.
5. 메모리 메커니즘의 동작
5.1 비동기 대안에서의 메모리 활용
Tick 1: Alt1→F, Alt2→R (idx=1, Alt2 진행 중)
Tick 2: Alt2→R (idx=1, Alt1 건너뜀)
Tick 3: Alt2→F, Alt3→R (idx=2, Alt3으로 전환)
Tick 4: Alt3→S → SUCCESS (idx=0 초기화)
Alt1이 FAILURE를 반환한 후 Alt2가 RUNNING 상태에서 여러 Tick 동안 진행된다. 이 동안 Alt1은 재평가되지 않으며, current_child_idx_에 의해 건너뛴다.
5.2 SUCCESS에 의한 인덱스 초기화
어떤 자식이든 SUCCESS를 반환하면 current_child_idx_가 0으로 초기화되고, resetChildren()에 의해 모든 자식이 IDLE로 설정된다. 다음 Tick에서는 첫 번째 자식부터 다시 시작한다.
6. XML에서의 사용
<BehaviorTree ID="NavigationWithRecovery">
<Fallback name="nav_fallback">
<Action ID="NavigateToPose"/>
<Sequence>
<Action ID="ClearCostmap"/>
<Action ID="NavigateToPose"/>
</Sequence>
<Action ID="SafeStop"/>
</Fallback>
</BehaviorTree>
<Fallback> 태그는 BehaviorTree.CPP에 기본 등록되어 있으며, name 속성으로 디버깅용 식별자를 지정할 수 있다.
7. 사용 시 주의 사항
-
메모리의 의미: FallbackNode는 FAILURE를 반환한 자식을 건너뛰므로, 이전에 실패한 대안이 이후 가용해지더라도 감지하지 못한다. 동적 조건 변화를 감시해야 하는 경우 ReactiveFallback을 사용해야 한다.
-
FAILURE 후 전체 재시작: 모든 자식이 FAILURE를 반환하면 인덱스가 0으로 초기화된다. 상위 트리에서 다시 Tick되면 첫 번째 자식부터 재시도한다.
-
v3에서 v4로의 변경: BehaviorTree.CPP v3에서
FallbackStar로 불리던 것이 v4에서FallbackNode로 명칭이 변경되었다(Faconti, 2022).
참고 문헌
- 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/