조건 노드의 캐싱 전략 (Condition Node Caching Strategies)

조건 노드의 캐싱 전략 (Condition Node Caching Strategies)

1. 개요

조건 노드의 캐싱 전략은 반복적인 조건 평가의 계산 비용을 줄이기 위해, 이전 평가 결과를 일정 기간 재사용하는 최적화 기법이다. ReactiveSequenceReactiveFallback 내부에 배치된 조건 노드는 매 tick마다 재평가되므로, 계산 비용이 높은 조건(서비스 호출, 복잡한 센서 데이터 처리 등)에 캐싱을 적용하면 시스템 성능을 개선할 수 있다.

2. 캐싱의 필요성

2.1 반복 평가의 비용

행동 트리의 tick 주기가 10~100Hz인 경우, ReactiveSequence 내부의 조건 노드는 초당 10~100회 평가된다. 조건 평가에 서비스 호출이나 복잡한 계산이 포함되면, 이 빈도의 반복 평가는 불필요한 계산 부하를 유발한다.

2.2 캐싱의 타당성 조건

캐싱이 유효하려면 조건의 결과가 캐시 유효 기간 내에 변화하지 않아야 한다. 빠르게 변화하는 조건(예: 장애물 감지)은 캐싱에 적합하지 않으며, 느리게 변화하는 조건(예: 배터리 잔량, GPS 상태)이 캐싱에 적합하다.

조건 유형변화 빈도캐싱 적합성권장 캐시 유효 기간
장애물 감지매우 높음부적합캐싱 하지 않음
센서 수신 여부중간보통0.1~0.5초
배터리 잔량낮음적합1~5초
서비스 가용성매우 낮음매우 적합5~30초
파라미터 값매우 낮음매우 적합1~10초

3. 캐싱 전략의 유형

3.1 Tick 단위 캐싱

동일 tick 내에서 복수 회 호출되는 조건의 결과를 단일 tick 동안 캐싱한다. Parallel 노드의 자식이나, 서브트리에서 동일 조건이 중복 참조되는 경우에 유용하다.

3.2 시간 기반 캐싱

조건 평가 결과를 지정된 시간 동안 캐싱하고, 유효 기간이 경과하면 다시 평가한다. 가장 일반적인 캐싱 전략이다.

3.3 이벤트 기반 캐싱

외부 이벤트(토픽 메시지 수신, 파라미터 변경 등)가 발생할 때에만 캐시를 갱신하고, 이벤트가 발생하지 않는 동안은 캐시된 결과를 사용한다. 가장 효율적이지만 구현 복잡도가 높다.

4. 시간 기반 캐싱의 일반 구현

class CachedCondition : public BT::ConditionNode
{
public:
    CachedCondition(const std::string& name,
                    const BT::NodeConfiguration& config,
                    rclcpp::Node::SharedPtr node)
        : BT::ConditionNode(name, config),
          node_(node),
          has_cache_(false)
    {}

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<double>("cache_duration_sec", 1.0,
                "캐시 유효 기간 (초)")
        };
    }

    BT::NodeStatus tick() override
    {
        double cache_duration;
        getInput("cache_duration_sec", cache_duration);

        if (has_cache_)
        {
            double elapsed =
                (node_->get_clock()->now() - cache_time_).seconds();
            if (elapsed < cache_duration)
            {
                return cached_result_;
            }
        }

        // 캐시 만료 또는 초기 평가: 실제 조건 평가 수행
        cached_result_ = evaluateCondition();
        cache_time_ = node_->get_clock()->now();
        has_cache_ = true;

        return cached_result_;
    }

protected:
    virtual BT::NodeStatus evaluateCondition() = 0;

    rclcpp::Node::SharedPtr node_;

private:
    bool has_cache_;
    BT::NodeStatus cached_result_;
    rclcpp::Time cache_time_;
};

파생 클래스에서 evaluateCondition() 메서드를 구현하면, 시간 기반 캐싱이 자동으로 적용된다.

5. XML 행동 트리에서의 활용

5.1 서비스 기반 조건의 캐싱

<ReactiveSequence>
    <Condition ID="IsPathValid_Cached"
               service_name="/is_path_valid"
               cache_duration_sec="2.0"/>
    <Action ID="FollowPath"/>
</ReactiveSequence>

경로 유효성 확인은 서비스 호출을 수반하므로, 2초 동안 결과를 캐싱하여 서비스 호출 빈도를 제한한다.

6. 설계 시 고려 사항

6.1 캐시 유효 기간과 반응성의 균형

캐시 유효 기간이 길수록 계산 부하가 감소하나, 조건 변화에 대한 반응이 지연된다. 안전 관련 조건에는 짧은 캐시 유효 기간을 적용하거나 캐싱을 적용하지 않아야 하며, 성능 관련 조건에는 긴 유효 기간을 적용할 수 있다.

6.2 캐시 무효화

캐시된 결과가 더 이상 유효하지 않은 상황(센서 장애, 환경 급변 등)에서 캐시를 강제로 무효화하는 메커니즘이 필요할 수 있다. 블랙보드를 통한 무효화 신호나, 특정 이벤트에 의한 캐시 리셋을 구현할 수 있다.

6.3 순수 함수 원칙과의 관계

캐싱은 내부 상태(캐시된 결과, 캐시 시각)를 유지하므로 순수 함수 원칙과 완전히 부합하지 않는다. 그러나 캐싱은 성능 최적화를 위한 투명한 메커니즘으로, 외부에서 관찰되는 조건 노드의 의미론을 변경하지 않는다(캐시 유효 기간 내에서는 동일한 결과를 반환).

7. 참고 문헌

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