1293.36 ReactiveFallback의 조건 재평가 메커니즘

1. 조건 재평가의 의의

ReactiveFallback에서 조건 재평가(condition re-evaluation)란, 매 Tick마다 이전에 FAILURE를 반환한 자식 노드들을 다시 Tick하여, 상위 우선순위 대안의 사용 가능 여부를 지속적으로 확인하는 메커니즘이다. WithMemory Fallback에서는 한 번 FAILURE를 반환한 자식이 이후 Tick에서 건너뛰어지므로, 해당 대안이 다시 사용 가능해지더라도 이를 감지할 수 없다. ReactiveFallback의 조건 재평가는 이러한 한계를 극복하여, 우선순위가 높은 대안이 복구되면 즉시 전환하는 적응적 행동을 가능하게 한다(Colledanchise & Ogren, 2018).

2. 조건 재평가의 동작 원리

ReactiveFallback에서 조건 재평가는 다음과 같은 흐름으로 수행된다.

function ReactiveFallback.tick():
    for i = 0 to children.size() - 1:
        child_status = children[i].tick()   // 매 Tick마다 인덱스 0부터 재평가
        
        if child_status == SUCCESS:
            haltRunningChildren()
            return SUCCESS                  // 대안 확보 시 즉시 반환
        
        if child_status == RUNNING:
            haltChildrenAfter(i + 1)
            return RUNNING
    
    return FAILURE

이 알고리즘에서 인덱스 0부터 시작하는 반복문이 매 Tick마다 동일하게 실행된다는 점이 핵심이다. WithMemory Fallback이 기억된 인덱스에서 재개하는 것과 달리, ReactiveFallback은 항상 첫 번째 자식부터 순차적으로 Tick한다. 이로 인해 이전 Tick에서 FAILURE를 반환한 상위 자식이 현재 Tick에서 SUCCESS를 반환할 수 있으며, 이 경우 하위에서 RUNNING 중이던 자식은 Halt된다.

3. 조건 노드 기반의 우선순위 선택 패턴

ReactiveFallback에서 조건 재평가가 가장 효과적으로 활용되는 패턴은, 앞쪽에 조건 노드를 배치하고 뒤쪽에 기본 액션을 배치하는 구조이다. 조건 노드는 동기적으로 SUCCESS 또는 FAILURE를 즉시 반환하므로, 매 Tick마다 경량으로 재평가된다.

<ReactiveFallback>
    <IsGPSAvailable/>           <!-- 조건: GPS 사용 가능? -->
    <IsVisualOdometryValid/>    <!-- 조건: 시각 주행 거리 측정 유효? -->
    <UseIMUDeadReckoning/>      <!-- 액션: IMU 기반 추측 항법 (최후 수단) -->
</ReactiveFallback>

이 구조에서 각 Tick의 실행 흐름은 다음과 같다.

3.1 GPS 사용 가능 시

Tick N:
  IsGPSAvailable.tick() → SUCCESS
  → ReactiveFallback 반환: SUCCESS
  (나머지 자식은 Tick되지 않음)

3.2 GPS 불가, 시각 주행 거리 측정 유효 시

Tick N:
  IsGPSAvailable.tick() → FAILURE
  IsVisualOdometryValid.tick() → SUCCESS
  → ReactiveFallback 반환: SUCCESS
  (UseIMUDeadReckoning은 Tick되지 않음)

3.3 GPS 불가, 시각 주행 거리 측정 불가 시

Tick N:
  IsGPSAvailable.tick() → FAILURE
  IsVisualOdometryValid.tick() → FAILURE
  UseIMUDeadReckoning.tick() → RUNNING
  → ReactiveFallback 반환: RUNNING

4. 조건 변화에 의한 우선순위 전환 과정

ReactiveFallback의 조건 재평가가 우선순위 전환을 유발하는 구체적 과정을 분석한다.

ReactiveFallback
├── TryPrimaryStrategy    (비동기 액션)
├── TrySecondaryStrategy  (비동기 액션)
└── TryFallbackStrategy   (비동기 액션)
TickTryPrimaryTrySecondaryTryFallbackReactiveFallback비고
1FAILURERUNNING(Tick 안 됨)RUNNING보조 전략 시도
2FAILURERUNNING(Tick 안 됨)RUNNING보조 전략 진행
3SUCCESSHalt(Tick 안 됨)SUCCESS주 전략 복구
4FAILURERUNNING (재시작)(Tick 안 됨)RUNNING주 전략 재실패

Tick 3에서 TryPrimaryStrategy가 SUCCESS를 반환하면, RUNNING 중이던 TrySecondaryStrategy에 Halt가 호출되고 ReactiveFallback은 SUCCESS를 반환한다. Tick 4에서 TryPrimaryStrategy가 다시 FAILURE를 반환하면, TrySecondaryStrategy는 IDLE 상태에서 새로 시작된다.

5. 조건 재평가와 블랙보드의 연동

ReactiveFallback의 조건 노드는 블랙보드에서 데이터를 읽어 평가를 수행하는 것이 일반적이다. 외부 시스템(ROS2 토픽 구독자, 센서 드라이버 등)이 블랙보드의 값을 갱신하면, 다음 Tick에서 조건 노드가 변경된 값을 반영한 판정을 반환한다.

class IsLocalizationReliable : public BT::ConditionNode {
public:
    IsLocalizationReliable(const std::string& name, 
                           const BT::NodeConfig& config)
        : BT::ConditionNode(name, config) {}

    static BT::PortsList providedPorts() {
        return { BT::InputPort<double>("covariance_trace"),
                 BT::InputPort<double>("threshold") };
    }

    BT::NodeStatus tick() override {
        double cov_trace, threshold;
        getInput("covariance_trace", cov_trace);
        getInput("threshold", threshold);
        return (cov_trace < threshold) 
            ? BT::NodeStatus::SUCCESS 
            : BT::NodeStatus::FAILURE;
    }
};

이 조건 노드를 ReactiveFallback에서 사용하면, 위치 추정의 공분산이 임계값을 초과하여 신뢰할 수 없는 경우 FAILURE를 반환하고, 공분산이 회복되면 다음 Tick에서 SUCCESS를 반환하여 해당 위치 추정 방법으로 즉시 전환한다.

<ReactiveFallback>
    <Sequence>
        <IsLocalizationReliable source="AMCL" 
            covariance_trace="{amcl_cov}" threshold="0.5"/>
        <UseAMCLPose/>
    </Sequence>
    <Sequence>
        <IsLocalizationReliable source="EKF" 
            covariance_trace="{ekf_cov}" threshold="1.0"/>
        <UseEKFPose/>
    </Sequence>
    <UseLastKnownPose/>
</ReactiveFallback>

6. 조건 재평가의 비용과 최적화

ReactiveFallback에서 매 Tick마다 수행되는 조건 재평가의 비용은 현재 활성 자식 인덱스까지의 조건 평가 비용의 합이다.

T_{re\_eval} = \sum_{i=0}^{j-1} T_{cond_i} + T_{child_j}

여기서 j는 SUCCESS 또는 RUNNING을 반환한 최초의 자식 인덱스이며, T_{cond_i}는 FAILURE를 반환한 앞선 자식의 평가 시간, T_{child_j}는 활성 자식의 Tick 시간이다.

6.1 최적화 전략

  1. 경량 조건 노드 사용: 블랙보드 값 비교, 플래그 확인 등 O(1) 연산으로 조건 노드를 구현하여 재평가 비용을 최소화한다.
  2. 고비용 판정의 비동기 분리: 복잡한 연산(확률적 추론, 기하학적 계산 등)은 별도의 주기적 프로세스에서 수행하고, 그 결과를 블랙보드에 캐시하여 조건 노드는 캐시된 값만 참조하도록 한다.
  3. 자식 순서 최적화: 성공 확률이 높은 자식을 앞에 배치하여, 뒤쪽 자식의 평가를 생략할 수 있는 기회를 극대화한다.

7. ReactiveSequence의 조건 재평가와의 비교

ReactiveSequence와 ReactiveFallback 모두 매 Tick마다 조건을 재평가하지만, 그 목적과 효과가 상이하다.

특성ReactiveSequence 재평가ReactiveFallback 재평가
재평가 대상이전에 SUCCESS를 반환한 조건이전에 FAILURE를 반환한 자식
재평가 목적전제 조건의 지속적 충족 확인상위 우선순위 대안의 복구 확인
위반 시 효과액션 즉시 중단 (FAILURE)하위 대안 Halt, 상위 대안 선택 (SUCCESS)
안전성 관점전제 조건 위반 감지최적 대안 복귀
논리적 의미“모든 조건이 여전히 유효한가?”“더 좋은 대안이 사용 가능한가?”

8. 조건 재평가에 의한 진동 문제와 해결

ReactiveFallback에서 조건의 반환 상태가 빈번하게 변동하면, 우선순위 전환이 반복적으로 발생하여 어떤 대안도 완료되지 못하는 진동(oscillation) 문제가 발생할 수 있다.

Tick 1: Child_0(SUCCESS) → ReactiveFallback: SUCCESS
Tick 2: Child_0(FAILURE), Child_1(RUNNING) → RUNNING
Tick 3: Child_0(SUCCESS), Child_1(Halt) → SUCCESS
Tick 4: Child_0(FAILURE), Child_1(RUNNING, 재시작) → RUNNING
...  (무한 반복)

8.1 히스테리시스를 통한 해결

조건 노드에 히스테리시스(hysteresis)를 적용하여, SUCCESS에서 FAILURE로의 전환과 FAILURE에서 SUCCESS로의 전환에 서로 다른 임계값을 사용한다.

class IsSignalStrong : public BT::ConditionNode {
public:
    BT::NodeStatus tick() override {
        double signal;
        getInput("signal_strength", signal);
        
        if (was_success_) {
            // SUCCESS → FAILURE 전환: 낮은 임계값
            was_success_ = (signal > low_threshold_);
        } else {
            // FAILURE → SUCCESS 전환: 높은 임계값
            was_success_ = (signal > high_threshold_);
        }
        
        return was_success_ 
            ? BT::NodeStatus::SUCCESS 
            : BT::NodeStatus::FAILURE;
    }

private:
    bool was_success_ = false;
    double low_threshold_ = 0.3;
    double high_threshold_ = 0.7;
};

이 히스테리시스 패턴에서 신호 강도가 0.7을 초과해야 SUCCESS로 전환되고, 0.3 미만으로 하락해야 FAILURE로 전환된다. 두 임계값 사이의 불감대(dead band)가 빈번한 상태 진동을 억제한다.

8.2 최소 유지 시간을 통한 해결

대안이 최소한의 실행 시간을 확보할 수 있도록, 조건 상태의 전환에 최소 유지 시간(minimum hold time)을 부여하는 방법도 사용된다.

BT::NodeStatus tick() override {
    bool condition_met = evaluateCondition();
    auto now = std::chrono::steady_clock::now();
    
    if (condition_met != last_result_) {
        if (now - last_change_time_ < min_hold_duration_) {
            return last_result_ 
                ? BT::NodeStatus::SUCCESS 
                : BT::NodeStatus::FAILURE;
        }
        last_result_ = condition_met;
        last_change_time_ = now;
    }
    
    return last_result_ 
        ? BT::NodeStatus::SUCCESS 
        : BT::NodeStatus::FAILURE;
}

이 패턴에서 조건의 실제 상태가 변화하더라도, 최소 유지 시간이 경과하기 전에는 이전 상태를 유지하여 불필요한 우선순위 전환을 방지한다.

9. 로봇공학에서의 적용 사례

ReactiveFallback의 조건 재평가는 다음과 같은 로봇공학 시나리오에서 활용된다.

시나리오우선 대안하위 대안재평가 효과
위치 추정AMCL (고정밀)추측 항법AMCL 복구 시 즉시 전환
통신5G 링크위성 링크5G 복구 시 즉시 전환
센서 융합LiDAR + 카메라LiDAR만카메라 복구 시 즉시 전환
경로 선택최단 경로우회 경로최단 경로 해제 시 즉시 전환

이러한 시나리오에서 ReactiveFallback의 조건 재평가는 시스템이 항상 사용 가능한 최선의 대안을 선택하도록 보장하며, 일시적 장애로부터의 자동 복구를 가능하게 한다.


참고 문헌

  • 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/