Tick 단위 캐싱의 구현 (Per-Tick Caching Implementation)

Tick 단위 캐싱의 구현 (Per-Tick Caching Implementation)

1. 개요

Tick 단위 캐싱은 단일 tick 주기 내에서 동일한 조건 노드가 복수 회 평가되는 경우, 첫 번째 평가 결과를 해당 tick 동안 캐싱하여 재사용하는 최적화 전략이다. 행동 트리에서 동일한 조건이 서로 다른 분기에서 참조되거나, 서브트리의 재사용으로 인해 동일 조건이 중복 평가되는 상황에서 유용하다.

2. Tick 단위 캐싱이 필요한 상황

2.1 동일 조건의 중복 참조

<Fallback>
    <Sequence>
        <Condition ID="IsBatteryAbove" min_percentage="0.3"/>
        <Action ID="FullSpeedNavigation"/>
    </Sequence>
    <Sequence>
        <Condition ID="IsBatteryAbove" min_percentage="0.1"/>
        <Action ID="EconomyNavigation"/>
    </Sequence>
</Fallback>

위 구조에서 IsBatteryAbove가 서로 다른 임계값으로 두 번 평가되므로, 동일한 배터리 메시지를 두 번 처리한다. 동일 tick 내에서 배터리 토픽의 값은 변화하지 않으므로, 메시지 수신은 한 번만 수행하면 충분하다.

2.2 서브트리 재사용

동일한 안전 점검 서브트리가 여러 분기에서 재사용되는 경우에도 중복 평가가 발생한다.

3. 구현

3.1 Tick ID 기반 캐싱

BehaviorTree.CPP에서 각 tick은 고유한 시퀀스 번호를 가진다. 이를 활용하여 동일 tick 내의 중복 평가를 방지한다.

class PerTickCachedCondition : public BT::ConditionNode
{
public:
    PerTickCachedCondition(const std::string& name,
                           const BT::NodeConfiguration& config)
        : BT::ConditionNode(name, config),
          last_tick_count_(0),
          has_cache_(false)
    {}

    BT::NodeStatus tick() override
    {
        // 현재 tick 카운트 확인
        auto tick_count = config().blackboard->get<uint16_t>(
            "__tick_count");

        if (has_cache_ && tick_count == last_tick_count_)
        {
            return cached_result_;
        }

        cached_result_ = evaluateCondition();
        last_tick_count_ = tick_count;
        has_cache_ = true;

        return cached_result_;
    }

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

private:
    uint16_t last_tick_count_;
    bool has_cache_;
    BT::NodeStatus cached_result_;
};

3.2 시간 기반 Tick 캐싱

tick 카운트에 접근할 수 없는 경우, tick 주기보다 짧은 캐시 유효 기간을 설정하여 사실상의 tick 단위 캐싱을 구현한다.

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

    BT::NodeStatus tick() override
    {
        if (has_cache_)
        {
            double elapsed =
                (node_->get_clock()->now() - cache_time_).seconds();
            // tick 주기(예: 10ms)보다 짧은 유효 기간
            if (elapsed < 0.005)
            {
                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_;
};

캐시 유효 기간을 tick 주기의 절반(예: 5ms)으로 설정하면, 동일 tick 내에서는 캐시가 유효하고 다음 tick에서는 만료된다.

3.3 공유 캐시 패턴

동일한 토픽 데이터를 참조하는 복수의 조건 노드가 있는 경우, 토픽 메시지의 캐싱을 공유 객체에서 수행한다.

template <typename MessageT>
class SharedMessageCache
{
public:
    SharedMessageCache(rclcpp::Node::SharedPtr node,
                       const std::string& topic_name)
    {
        subscription_ = node->create_subscription<MessageT>(
            topic_name,
            rclcpp::QoS(1),
            [this](const%20typename%20MessageT::SharedPtr%20msg) {
                std::lock_guard<std::mutex> lock(mutex_);
                cached_message_ = msg;
            });
    }

    typename MessageT::SharedPtr getMessage() const
    {
        std::lock_guard<std::mutex> lock(mutex_);
        return cached_message_;
    }

private:
    typename rclcpp::Subscription<MessageT>::SharedPtr subscription_;
    typename MessageT::SharedPtr cached_message_;
    mutable std::mutex mutex_;
};

복수의 조건 노드가 동일한 SharedMessageCache 인스턴스를 참조하면, 토픽 구독은 한 번만 이루어지고 모든 조건 노드가 동일한 메시지를 공유한다.

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

4.1 중복 평가가 발생하는 구조

<ReactiveSequence>
    <!-- 이 조건들이 매 tick마다 모두 재평가됨 -->
    <Condition ID="IsBatteryOk_Cached"/>
    <Condition ID="IsSensorOk_Cached"/>
    <Fallback>
        <Sequence>
            <Condition ID="IsBatteryOk_Cached"/>  <!-- 중복 -->
            <Action ID="HighPowerMode"/>
        </Sequence>
        <Action ID="LowPowerMode"/>
    </Fallback>
</ReactiveSequence>

5. 설계 시 고려 사항

5.1 캐싱과 조건 변화의 일관성

Tick 단위 캐싱은 단일 tick 내에서 조건의 결과가 일관되도록 보장한다. 이는 동일 tick에서 동일 조건이 서로 다른 결과를 반환하여 행동 트리의 논리적 일관성이 깨지는 것을 방지한다.

5.2 캐싱 오버헤드

캐싱 자체에도 약간의 오버헤드(tick 카운트 비교, 시간 확인)가 존재한다. 조건 평가의 원래 비용이 캐싱 오버헤드보다 작은 경우에는 캐싱이 오히려 성능을 저하시킬 수 있다. 블랙보드 값 비교와 같이 매우 가벼운 조건에는 캐싱이 불필요하다.

5.3 BehaviorTree.CPP의 내장 캐싱

BehaviorTree.CPP 4.x에서는 pre_conditionpost_condition 스크립트를 통해 조건 평가의 일부 최적화가 가능하다. 라이브러리의 내장 기능을 먼저 검토하고, 부족한 부분에 대해서만 사용자 정의 캐싱을 구현하는 것이 바람직하다.

6. 참고 문헌

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