Retry 데코레이터의 동작 (Operation of the Retry Decorator)
1. 개요
Retry 데코���이터는 자식 노드가 FAILURE를 반환할 때, 지정된 최대 횟수까지 자식을 재실행하는 실행 제어 데코레이터이다. 네트워크 지연, 센서 일시적 오류, 일시적 장애물 등에 의한 간헐적 실패를 자동으로 복구하는 데 활용된다. Repeat 데코레이터가 SUCCESS 시 반복하는 것과 대조적으로, Retry는 FAILURE 시 재시도한다.
2. 동작 규칙
2.1 상태 전이 규칙
| 자식 반환 | 재시도 카운터 상태 | Retry 결과 |
|---|---|---|
| SUCCESS | 임의 | SUCCESS (재시도 종료) |
| FAILURE (k < N) | k \leftarrow k + 1 | RUNNING (재시도) |
| FAILURE (k \geq N) | 리셋 | FAILURE (재시도 소진) |
| RUNNING | 변화 없음 | RUNNING (자식 실행 중) |
여기서 k는 현재 시도 횟수, N은 최대 시도 횟수(num_attempts)이다.
2.2 수학적 표현
f_{\text{Retry}}(s, k, N) = \begin{cases} \text{SUCCESS} & \text{if } s = \text{SUCCESS} \\ \text{RUNNING} & \text{if } s = \text{FAILURE} \wedge k < N \\ \text{FAILURE} & \text{if } s = \text{FAILURE} \wedge k \geq N \\ \text{RUNNING} & \text{if } s = \text{RUNNING} \end{cases}
Repeat와의 비교
| 특성 | Repeat | Retry |
|---|---|---|
| 반복 트리거 | 자식 SUCCESS | 자식 FAILURE |
| 종료 조건 (성공) | N회 SUCCESS 완료 | 자식 SUCCESS (1회) |
| 종료 조건 (실패) | 자식 FAILURE | N회 FAILURE 소진 |
| 용도 | 행동의 반복 실행 | 실패한 행동의 재시도 |
BehaviorTree.CPP 구현 구조
class RetryNode : public BT::DecoratorNode
{
BT::NodeStatus tick() override
{
setStatus(BT::NodeStatus::RUNNING);
auto child_status = child_node_->executeTick();
switch (child_status)
{
case BT::NodeStatus::SUCCESS:
try_count_ = 0;
return BT::NodeStatus::SUCCESS;
case BT::NodeStatus::FAILURE:
++try_count_;
if (try_count_ >= max_attempts_)
{
try_count_ = 0;
return BT::NodeStatus::FAILURE;
}
return BT::NodeStatus::RUNNING;
case BT::NodeStatus::RUNNING:
return BT::NodeStatus::RUNNING;
default:
throw BT::LogicError("Invalid status");
}
}
void halt() override
{
try_count_ = 0;
DecoratorNode::halt();
}
int try_count_ = 0;
int max_attempts_ = 1;
};
XML에서의 사용
<RetryNode num_attempts="3">
<Action ID="ConnectToSensor"/>
</RetryNode>
센서 연결에 실패하면 최대 3회 재시도한다.
시간적 동작 흐름 (num_attempts=3)
Tick 1: Child 시작 → RUNNING
Tick 2: Child 완료 → FAILURE, try=1 → Retry=RUNNING
Tick 3: Child 재시작 → RUNNING
Tick 4: Child 완료 → FAILURE, try=2 → Retry=RUNNING
Tick 5: Child 재시작 → RUNNING
Tick 6: Child 완료 → FAILURE, try=3 → Retry=FAILURE (재시도 소진)
또는 중간에 성공하는 경우:
Tick 1: Child → FAILURE, try=1 → Retry=RUNNING
Tick 2: Child → FAILURE, try=2 ��� Retry=RUNNING
Tick 3: Child → SUCCESS, try 리셋 → Retry=SUCCESS
활용 사례
네트워크 연결 재시도
<RetryNode num_attempts="5">
<Action ID="ConnectToServer"/>
</RetryNode>
파지 행동 재시도
<RetryNode num_attempts="3">
<Sequence>
<Action ID="MoveToGraspPose"/>
<Action ID="CloseGripper"/>
<Condition ID="IsObjectGrasped"/>
</Sequence>
</RetryNode>
Retry + Delay (재시도 간 대기)
<RetryNode num_attempts="5">
<Delay delay_msec="2000">
<Action ID="DownloadMap"/>
</Delay>
</RetryNode>
각 재시도 사이에 2초 대기한다.
Retry + Timeout (전체 시간 제한)
<Timeout msec="30000">
<RetryNode num_attempts="10">
<Action ID="EstablishLink"/>
</RetryNode>
</Timeout>
30초 이내에 최대 10회 재시도한다.
설계 시 고려 사항
재시도 횟수의 합리적 설정
과도한 재시도 횟수는 영구적 오류에 대해 불필요한 시간 소모를 초래한다. 간헐적 오류의 빈도와 심각도를 고려하여 적절한 횟수를 설정하여야 한다.
재시도 간 상태 변화
자식이 FAILURE를 반환한 후 재시도할 때, 환경이나 시스템 상태가 변화하여 재시도가 성공할 가능성이 있어야 의미가 있다. 동일한 조건에서 반복적으로 실패하는 경우, 재시도보다는 복구 행동을 수행하는 것이 효과적이다.
halt 시 카운터 초기화
Retry가 halt되면 재시도 카운터를 리셋하여, 다음 실행에서 처음부터 시작하도록 한다.
참고 문헌
- Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
- BehaviorTree.CPP 공식 문서. https://www.behaviortree.dev/
| 버전 | 날짜 | 변경 사항 |
|---|---|---|
| v0.1 | 2026-04-04 | 초안 작성 |