횟수 제한 데코레이터 구현 (Execution Count Limiter Decorator Implementation)
1. 개요
횟수 제한 데코레이터는 자식 노드의 총 실행 횟수에 상한을 부여하여, 지정된 횟수를 초과하면 자식을 tick하지 않고 FAILURE를 반환하는 커스텀 데코레이터이다. 복구 행동의 과도한 반복 방지, 자원 소모 제한, 안전 행동의 실행 횟수 제어 등에 활용된다.
2. Retry 및 Repeat와의 차이
| 데코레이터 | 카운터 증가 시점 | 종료 조건 | 리셋 시점 |
|---|---|---|---|
| Retry | 자식 FAILURE 시 | SUCCESS 또는 카운터 도달 | SUCCESS, 카운터 도달, halt |
| Repeat | 자식 SUCCESS 시 | FAILURE 또는 카운터 도달 | FAILURE, 카운터 도달, halt |
| 횟수 제한 | 매 tick 시 | 카운터 도달 | halt |
횟수 제한 데코레이터��� ��식의 반환 상태와 관계없이 매 실행마다 카운터를 증가시킨다.
3. 전체 구현
class ExecutionCountLimiter : public BT::DecoratorNode
{
public:
ExecutionCountLimiter(const std::string& name,
const BT::NodeConfiguration& config)
: DecoratorNode(name, config), execution_count_(0)
{}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<int>("max_executions", 10,
"최대 실행 횟수"),
BT::OutputPort<int>("current_count",
"현재 실행 횟수")
};
}
private:
BT::NodeStatus tick() override
{
setStatus(BT::NodeStatus::RUNNING);
int max_exec;
getInput("max_executions", max_exec);
if (execution_count_ >= max_exec)
{
return BT::NodeStatus::FAILURE;
}
++execution_count_;
setOutput("current_count", execution_count_);
return child_node_->executeTick();
}
void halt() override
{
execution_count_ = 0;
DecoratorNode::halt();
}
int execution_count_;
};
4. XML에서의 사용
<ExecutionCountLimiter max_executions="5"
current_count="{recovery_count}">
<Action ID="PerformRecovery"/>
</ExecutionCountLimiter>
복구 행동을 최대 5회까지만 실행한다. current_count를 통해 현재 실행 횟수를 다른 노드에서 참조할 수 있다.
5. 활용 사례
5.1 복구 횟수 제한
<Fallback>
<Action ID="NormalNavigation"/>
<ExecutionCountLimiter max_executions="3">
<Action ID="SpinRecovery"/>
</ExecutionCountLimiter>
<Action ID="RequestHelp"/>
</Fallback>
회전 복구를 최대 3회까지만 시도하고, 초과하면 도움을 요청한다.
6. 참고 문헌
- BehaviorTree.CPP 공식 문서. https://www.behaviortree.dev/
| 버전 | 날짜 | 변경 사항 |
|---|---|---|
| v0.1 | 2026-04-05 | 초안 작성 |