Repeat 데코레이터의 동작 (Operation of the Repeat Decorator)

Repeat 데코레이터의 동작 (Operation of the Repeat Decorator)

1. 개요

Repeat 데코레이터는 자식 노드를 지정된 횟수만큼 반복 실행하는 실행 제어 데코레이터이다. 자식이 SUCCESS를 반환할 때마다 반복 카운터를 증가시키고, 지정된 횟수에 도달하면 전체가 SUCCESS를 반환한다. 자식이 중간에 FAILURE를 반환하면 반복이 즉시 중단되고 FAILURE를 반환한다.

2. 동작 규칙

2.1 상태 전이 규칙

자식 반환카운터 상태Repeat 결과
SUCCESS카운터 < 최대 횟수RUNNING (다음 반복)
SUCCESS카운터 = 최대 횟수SUCCESS (반복 완료)
FAILURE임의FAILURE (반복 중단)
RUNNING임의RUNNING (자식 실행 중)

2.2 수학적 표현

반복 횟수를 N, 현재 반복 카운터를 k (0 \leq k \leq N)라 하면:

f_{\text{Repeat}}(s, k) = \begin{cases} \text{RUNNING} & \text{if } s = \text{SUCCESS} \wedge k < N \\ \text{SUCCESS} & \text{if } s = \text{SUCCESS} \wedge k = N \\ \text{FAILURE} & \text{if } s = \text{FAILURE} \\ \text{RUNNING} & \text{if } s = \text{RUNNING} \end{cases}

BehaviorTree.CPP 구현 구조

class RepeatNode : public BT::DecoratorNode
{
public:
    RepeatNode(const std::string& name,
               const BT::NodeConfiguration& config)
        : DecoratorNode(name, config),
          num_cycles_(0),
          repeat_count_(0)
    {
        getInput("num_cycles", num_cycles_);
    }

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<int>("num_cycles", -1,
                "반복 횟수 (-1: 무한 반복)")
        };
    }

private:
    BT::NodeStatus tick() override
    {
        setStatus(BT::NodeStatus::RUNNING);
        auto child_status = child_node_->executeTick();

        switch (child_status)
        {
        case BT::NodeStatus::SUCCESS:
            ++repeat_count_;
            if (num_cycles_ > 0 && repeat_count_ >= num_cycles_)
            {
                repeat_count_ = 0;
                return BT::NodeStatus::SUCCESS;
            }
            return BT::NodeStatus::RUNNING;

        case BT::NodeStatus::FAILURE:
            repeat_count_ = 0;
            return BT::NodeStatus::FAILURE;

        case BT::NodeStatus::RUNNING:
            return BT::NodeStatus::RUNNING;

        default:
            throw BT::LogicError("Invalid status");
        }
    }

    void halt() override
    {
        repeat_count_ = 0;
        DecoratorNode::halt();
    }

    int num_cycles_;
    int repeat_count_;
};

XML에서의 사용

고정 횟수 반복

<Repeat num_cycles="5">
    <Action ID="PatrolWaypoint"/>
</Repeat>

순찰 웨이포인트를 5회 반복 방문한다.

무한 반복

<Repeat num_cycles="-1">
    <Sequence>
        <Action ID="MoveToWaypoint"/>
        <Action ID="PerformInspection"/>
    </Sequence>
</Repeat>

num_cycles-1로 설정하면 무한히 반복한다. 반드시 Timeout이나 외부 조건에 의한 종료 메커니즘과 함께 사용하여야 한다.

블랙보드를 통한 동적 횟수 지정

<Repeat num_cycles="{patrol_count}">
    <Action ID="PatrolWaypoint"/>
</Repeat>

블랙보드의 patrol_count 값에 따라 반복 횟수가 동적으로 결정된다.

시간적 동작 흐름 (num_cycles=3)

Tick 1: Child 시작 → RUNNING
Tick 2: Child 완료 → SUCCESS, count=1 → Repeat=RUNNING
Tick 3: Child 재시작 → RUNNING
Tick 4: Child 완료 → SUCCESS, count=2 → Repeat=RUNNING
Tick 5: Child 재시작 → RUNNING
Tick 6: Child 완료 → SUCCESS, count=3 → Repeat=SUCCESS

halt() 시 카운터 초기화

Repeat 데코레이터가 halt되면 반복 카운터를 0으로 리셋하여, 다음 실행에서 처음부터 반복을 시작한다.

설계 시 고려 사항

반복 중 FAILURE의 의미

자식이 FAILURE를 반환하면 반복이 즉시 중단된다. 이는 반복 행동 중 오류가 발생한 것으로 해석되며, 반복의 정상 완료와 구분된다. 반복 중 실패를 허용하려면 자식을 ForceSuccess로 감싼다.

무한 반복의 안전성

무한 반복은 행동 트리의 tick 루프를 영원히 점유하므로, Timeout이나 ReactiveSequence 기반의 외부 조건 감시와 반드시 결합하여야 한다.

참고 문헌

  • Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
  • BehaviorTree.CPP 공식 문서. https://www.behaviortree.dev/

버전날짜변경 사항
v0.12026-04-04초안 작성