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

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

1. 개요

RunOnce 데코레이터는 자식 노드를 최초 한 번만 실행하고, 이후의 tick에서는 자식을 다시 실행하지 않고 이전 결과를 캐싱하여 반환하는 실행 제어 데코레이터이다. 시스템 초기화, 일회성 설정, 센서 캘리브레이션 등 한 번만 수행하면 되는 행동에 적합하다.

2. 동작 규칙

2.1 상태 전이

상태동작RunOnce 반환
최초 tick (자식 미실행)자식을 tick자식의 반환 상태
이후 tick (자식 실행 완료)자식을 tick하지 않음캐싱된 이전 결과
자식이 RUNNING 중자식을 계속 tickRUNNING

2.2 수학적 표현

f_{\text{RunOnce}}(t) = \begin{cases} \text{child.tick()} & \text{if } t = t_{\text{first}} \text{ or } s_{\text{prev}} = \text{RUNNING} \\ s_{\text{cached}} & \text{otherwise} \end{cases}

구현

class RunOnceNode : public BT::DecoratorNode
{
    BT::NodeStatus tick() override
    {
        if (already_completed_)
        {
            return cached_status_;
        }

        setStatus(BT::NodeStatus::RUNNING);
        auto child_status = child_node_->executeTick();

        if (child_status != BT::NodeStatus::RUNNING)
        {
            already_completed_ = true;
            cached_status_ = child_status;
        }

        return child_status;
    }

    void halt() override
    {
        // RunOnce의 halt 정책에 따라 리셋 여부 결정
        // 기본: 리셋하지 않음 (한 번 실행된 것은 유지)
        DecoratorNode::halt();
    }

    bool already_completed_ = false;
    BT::NodeStatus cached_status_ = BT::NodeStatus::IDLE;
};

XML에서의 사용

<RunOnce>
    <Action ID="InitializeHardware"/>
</RunOnce>

시간적 동작 흐름

동기 자식의 경우

Tick 1: 최초 tick → 자식 tick → SUCCESS → RunOnce=SUCCESS (캐싱)
Tick 2: 캐시 사용 → RunOnce=SUCCESS (자식 미실행)
Tick 3: 캐시 사용 → RunOnce=SUCCESS (자식 미실행)
...

비동기 자식의 경우

Tick 1: 자식 tick → RUNNING → RunOnce=RUNNING
Tick 2: 자식 tick → RUNNING → RunOnce=RUNNING
Tick 3: 자식 tick → SUCCESS → RunOnce=SUCCESS (캐싱)
Tick 4: 캐시 사용 → RunOnce=SUCCESS (자식 미실행)
...

자식이 RUNNING 동안에는 계속 tick한다. 자식이 최종 결과(SUCCESS 또는 FAILURE)를 반환하면 캐싱하고, 이후에는 캐싱된 결과를 반환한다.

활용 사례

시스템 초기화

<Sequence>
    <RunOnce>
        <Action ID="InitializeSensors"/>
    </RunOnce>
    <RunOnce>
        <Action ID="LoadCalibrationData"/>
    </RunOnce>
    <SubTree ID="MainMission"/>
</Sequence>

센서 초기화와 캘리브레이션 데이터 로딩을 최초 한 번만 수행하고, 이후에는 바로 메인 임무를 수행한다.

일회성 알림

<Sequence>
    <RunOnce>
        <Action ID="AnnounceStartup"/>
    </RunOnce>
    <Action ID="StartOperation"/>
</Sequence>

ReactiveSequence 내에서의 RunOnce

<ReactiveSequence>
    <Condition ID="IsSystemActive"/>
    <RunOnce>
        <Action ID="PerformInitialSetup"/>
    </RunOnce>
    <Action ID="MainTask"/>
</ReactiveSequence>

ReactiveSequence에서 매 tick마다 조건이 재평가되더라도, RunOnce에 의해 초기 설정은 한 번만 수행된다.

설계 시 고려 사항

halt 시의 리셋 정책

RunOnce가 halt될 때, 캐싱된 결과를 리셋할지 유지할지는 설계 정책에 따라 다르다. BehaviorTree.CPP에서는 halt 시 리셋하는 것이 기본이나, 구현에 따라 다를 수 있다.

정책halt 시 동작재실행 여부
리셋캐시 초기화다음 tick에서 자식 재실행
유지캐시 유지자식 재실행하지 않음

자식 FAILURE의 캐싱

자식이 FAILURE를 반환한 경우에도 캐싱되므로, 이후 tick에서 항상 FAILURE가 반환된다. 초기화가 실패한 경우 재시도가 필요하다면 Retry를 내부에 배치한다.

<RunOnce>
    <RetryNode num_attempts="3">
        <Action ID="InitializeSensor"/>
    </RetryNode>
</RunOnce>

참고 문헌

  • 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초안 작성