이벤트 기반 캐싱의 구현 (Event-Based Caching Implementation)

이벤트 기반 캐싱의 구현 (Event-Based Caching Implementation)

1. 개요

이벤트 기반 캐싱은 외부 이벤트(토픽 메시지 수신, 파라미터 변경, 서비스 응답 수신 등)가 발생할 때에만 조건을 재평가하고, 이벤트가 발생하지 않는 동안에는 이전에 캐싱된 결과를 반환하는 캐싱 전략이다. 시간 기반 캐싱이 주기적으로 재평가하는 것과 달리, 이벤트 기반 캐싱은 데이터가 실제로 변경된 시점에서만 평가를 수행하므로 가장 효율적인 캐싱 전략이다.

2. 이벤트 기반 캐싱의 동작 원리

2.1 상태 전이

[초기] --이벤트--> [평가 수행, 캐시 갱신] --tick--> [캐시 반환]
                          ^                         |
                          |--- 이벤트 발생 시 ------+
  1. 구독 콜백에서 이벤트(새 메시지 수신)를 감지하면 조건을 재평가하고 캐시를 갱신한다.
  2. tick() 메서드는 캐시된 결과를 즉시 반환한다.
  3. 이벤트가 발생하지 않는 동안 tick()은 이전 결과를 계속 반환한다.

2.2 시간 기반 캐싱과의 비교

특성시간 기반 캐싱이벤트 기반 캐싱
재평가 시점유효 기간 만료 시이벤트 발생 시
불필요한 재평가발생 가능없음
반응 지연최대 유효 기간없음 (이벤트 즉시 반영)
구현 복잡도낮음중간~높음
적합한 데이터 소스주기적 데이터비주기적/이벤트형 데이터

3. 구현

3.1 토픽 메시지 이벤트 기반 캐싱

template <typename MessageT>
class EventCachedCondition : public BT::ConditionNode
{
public:
    EventCachedCondition(const std::string& name,
                         const BT::NodeConfiguration& config,
                         rclcpp::Node::SharedPtr node)
        : BT::ConditionNode(name, config),
          node_(node),
          has_cache_(false),
          new_data_available_(false)
    {
        std::string topic_name;
        getInput("topic_name", 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_);
                latest_message_ = msg;
                new_data_available_ = true;
            });
    }

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<std::string>("topic_name", "토픽 이름")
        };
    }

    BT::NodeStatus tick() override
    {
        std::lock_guard<std::mutex> lock(mutex_);

        if (new_data_available_)
        {
            cached_result_ = evaluateCondition(latest_message_);
            has_cache_ = true;
            new_data_available_ = false;
        }

        if (has_cache_)
        {
            return cached_result_;
        }
        return BT::NodeStatus::FAILURE;
    }

protected:
    virtual BT::NodeStatus evaluateCondition(
        const typename MessageT::SharedPtr& msg) = 0;

    rclcpp::Node::SharedPtr node_;

private:
    typename rclcpp::Subscription<MessageT>::SharedPtr subscription_;
    typename MessageT::SharedPtr latest_message_;
    std::mutex mutex_;
    bool has_cache_;
    bool new_data_available_;
    BT::NodeStatus cached_result_;
};

이 구현의 핵심 특성은 다음과 같다.

  1. 구독 콜백은 새 메시지를 저장하고 new_data_available_ 플래그를 설정한다.
  2. tick() 메서드는 새 데이터가 있을 때만 evaluateCondition()을 호출한다.
  3. 새 데이터가 없으면 이전 캐시 결과를 즉시 반환한다.
  4. 콜백과 tick 사이의 스레드 안전성은 뮤텍스로 보장한다.

3.2 파라미터 이벤트 기반 캐싱

ROS2 파라미터 변경 이벤트를 감지하여 캐시를 갱신하는 패턴이다.

class EventCachedParameterCondition : public BT::ConditionNode
{
public:
    EventCachedParameterCondition(const std::string& name,
                                  const BT::NodeConfiguration& config,
                                  rclcpp::Node::SharedPtr node)
        : BT::ConditionNode(name, config),
          node_(node),
          cached_result_(BT::NodeStatus::FAILURE),
          needs_update_(true)
    {
        std::string param_name;
        getInput("param_name", param_name);

        // 초기값 평가
        if (node_->has_parameter(param_name))
        {
            cached_result_ = evaluateParameter(
                node_->get_parameter(param_name));
            needs_update_ = false;
        }

        // 파라미터 변경 이벤트 구독
        param_handler_ =
            std::make_shared<rclcpp::ParameterEventHandler>(node_);
        cb_handle_ = param_handler_->add_parameter_callback(
            param_name,
            [this](const%20rclcpp::Parameter&%20param) {
                std::lock_guard<std::mutex> lock(mutex_);
                cached_result_ = evaluateParameter(param);
                needs_update_ = false;
            });
    }

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<std::string>("param_name", "파라미터 이름"),
            BT::InputPort<std::string>("expected_value", "기대 값")
        };
    }

    BT::NodeStatus tick() override
    {
        std::lock_guard<std::mutex> lock(mutex_);
        return cached_result_;
    }

private:
    BT::NodeStatus evaluateParameter(
        const rclcpp::Parameter& param)
    {
        std::string expected;
        getInput("expected_value", expected);
        return (param.value_to_string() == expected)
                   ? BT::NodeStatus::SUCCESS
                   : BT::NodeStatus::FAILURE;
    }

    rclcpp::Node::SharedPtr node_;
    std::shared_ptr<rclcpp::ParameterEventHandler> param_handler_;
    std::shared_ptr<rclcpp::ParameterCallbackHandle> cb_handle_;
    std::mutex mutex_;
    BT::NodeStatus cached_result_;
    bool needs_update_;
};

이 구현에서 tick() 메서드는 단순히 캐시된 결과를 반환할 뿐이며, 조건 평가는 오직 파라미터 변경 콜백에서만 수행된다. 따라서 tick의 계산 비용은 뮤텍스 잠금과 변수 반환에 해당하는 최소 수준이다.

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

<ReactiveSequence>
    <Condition ID="IsBatteryOk_EventCached"
               topic_name="/battery_state"/>
    <Condition ID="IsParamMode_EventCached"
               param_name="operation_mode"
               expected_value="autonomous"/>
    <Action ID="AutonomousMission"/>
</ReactiveSequence>

5. 이벤트 기반 캐싱과 타임아웃의 결합

이벤트 기반 캐싱에 타임아웃을 추가하여, 이벤트가 장시간 발생하지 않는 경우(데이터 소스 장애)를 감지한다.

BT::NodeStatus tick() override
{
    std::lock_guard<std::mutex> lock(mutex_);

    if (new_data_available_)
    {
        cached_result_ = evaluateCondition(latest_message_);
        cache_time_ = node_->get_clock()->now();
        has_cache_ = true;
        new_data_available_ = false;
    }

    if (!has_cache_)
    {
        return BT::NodeStatus::FAILURE;
    }

    double timeout;
    getInput("stale_timeout_sec", timeout);
    double elapsed =
        (node_->get_clock()->now() - cache_time_).seconds();

    if (elapsed > timeout)
    {
        return BT::NodeStatus::FAILURE;  // 캐시가 오래됨
    }

    return cached_result_;
}

6. 설계 시 고려 사항

6.1 초기 상태 처리

이벤트 기반 캐싱에서 노드가 생성된 직후 아직 이벤트가 발생하지 않은 경우, 캐시가 비어 있으므로 FAILURE를 반환한다. 이는 시스템 초기화 단계에서 일시적으로 모든 조건이 FAILURE를 반환하는 상황을 초래할 수 있다.

6.2 콜백 실행 스레드

ROS2의 콜백은 실행기(executor)에 의해 별도의 스레드에서 실행될 수 있다. 콜백에서의 조건 평가와 tick 스레드에서의 캐시 접근이 동시에 발생하지 않도록 뮤텍스를 통한 동기화가 필수적이다.

6.3 콜백 내 평가의 부하

콜백 함수 내에서 복잡한 조건 평가를 수행하면 콜백 큐의 처리 지연을 유발할 수 있다. 평가 로직이 복잡한 경우, 콜백에서는 메시지만 저장하고 tick()에서 평가를 수행하는 것이 적절하다.

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