1293.87 조건 노드의 캐싱 기법
1. 조건 노드 캐싱의 동기
조건 노드(Condition Node)는 행동 트리에서 환경 상태를 평가하여 SUCCESS 또는 FAILURE를 즉시 반환하는 리프 노드이다. Reactive 제어 노드 하에서 조건 노드는 매 Tick마다 반복적으로 평가되며, 이 평가 비용이 Tick 실행 시간의 상당 부분을 차지할 수 있다. 특히, 조건 평가가 센서 데이터 접근, 수학적 연산, 또는 외부 서비스 조회를 포함하는 경우 비용이 크다(Faconti, 2022).
캐싱(caching)이란, 조건 노드의 평가 결과를 일시적으로 저장하고, 이후의 Tick에서 조건의 입력이 변하지 않았다면 저장된 결과를 재사용하는 기법이다. 이를 통해 불필요한 중복 연산을 제거하고 Tick 실행 시간을 단축한다.
2. 캐싱 전략의 유형
2.1 시간 기반 캐싱 (Time-Based Caching)
일정 시간 동안 캐싱된 결과를 유지하고, 해당 시간이 경과한 후에만 재평가를 수행한다. 조건의 변화 빈도가 예측 가능한 경우에 적합하다.
class TimeBasedCachedCondition : public BT::ConditionNode {
public:
TimeBasedCachedCondition(const std::string& name,
const BT::NodeConfig& config,
std::chrono::milliseconds cache_duration)
: BT::ConditionNode(name, config),
cache_duration_(cache_duration) {}
BT::NodeStatus tick() override {
auto now = std::chrono::steady_clock::now();
if (cache_valid_ && (now - last_eval_time_) < cache_duration_) {
return cached_result_;
}
cached_result_ = evaluate();
last_eval_time_ = now;
cache_valid_ = true;
return cached_result_;
}
private:
virtual BT::NodeStatus evaluate() = 0;
std::chrono::milliseconds cache_duration_;
std::chrono::steady_clock::time_point last_eval_time_;
BT::NodeStatus cached_result_{BT::NodeStatus::FAILURE};
bool cache_valid_{false};
};
2.2 Tick 횟수 기반 캐싱 (Tick-Count Caching)
지정된 Tick 횟수 동안 캐싱된 결과를 유지한다. 시간이 아닌 Tick 주기 단위로 캐시 유효성을 관리하므로, Tick 주기가 가변적인 환경에서도 일관된 동작을 보장한다.
class TickCountCachedCondition : public BT::ConditionNode {
public:
TickCountCachedCondition(const std::string& name,
const BT::NodeConfig& config,
int cache_ticks)
: BT::ConditionNode(name, config),
cache_interval_(cache_ticks) {}
BT::NodeStatus tick() override {
ticks_since_eval_++;
if (cache_valid_ && ticks_since_eval_ < cache_interval_) {
return cached_result_;
}
cached_result_ = evaluate();
ticks_since_eval_ = 0;
cache_valid_ = true;
return cached_result_;
}
private:
virtual BT::NodeStatus evaluate() = 0;
int cache_interval_;
int ticks_since_eval_{0};
BT::NodeStatus cached_result_{BT::NodeStatus::FAILURE};
bool cache_valid_{false};
};
2.3 입력 변화 기반 캐싱 (Input-Change Caching)
조건 노드의 입력 포트 값이 변경된 경우에만 재평가를 수행한다. 이 방식은 시간이나 Tick 횟수와 무관하게 입력 데이터의 실제 변화에 기반하므로, 가장 정밀한 캐싱 전략이다.
class InputChangeCachedCondition : public BT::ConditionNode {
public:
BT::NodeStatus tick() override {
double current_value;
getInput("sensor_value", current_value);
// 입력 값이 유의미하게 변경된 경우에만 재평가
if (cache_valid_ && std::abs(current_value - last_input_value_) < epsilon_) {
return cached_result_;
}
last_input_value_ = current_value;
cached_result_ = evaluateWithValue(current_value);
cache_valid_ = true;
return cached_result_;
}
private:
virtual BT::NodeStatus evaluateWithValue(double value) = 0;
double last_input_value_{0.0};
double epsilon_{1e-6};
BT::NodeStatus cached_result_{BT::NodeStatus::FAILURE};
bool cache_valid_{false};
};
2.4 블랙보드 시퀀스 번호 기반 캐싱
BehaviorTree.CPP v4의 블랙보드 항목은 갱신 시 시퀀스 번호가 증가한다. 이 시퀀스 번호를 감시하여 입력 포트의 변경 여부를 효율적으로 판단할 수 있다.
BT::NodeStatus tick() override {
auto entry = config().blackboard->getEntry("target_position");
if (entry && entry->sequence_id != last_sequence_id_) {
last_sequence_id_ = entry->sequence_id;
cached_result_ = evaluate();
}
return cached_result_;
}
3. 캐싱 데코레이터 패턴
조건 노드 자체를 수정하지 않고, 데코레이터를 통해 캐싱 기능을 외부에서 부여하는 패턴이다. 이 방식은 기존 조건 노드의 코드를 변경하지 않으면서 캐싱을 적용할 수 있다는 장점이 있다.
class CacheDecorator : public BT::DecoratorNode {
public:
CacheDecorator(const std::string& name,
const BT::NodeConfig& config)
: BT::DecoratorNode(name, config) {
getInput("cache_duration_ms", cache_duration_ms_);
}
BT::NodeStatus tick() override {
auto now = std::chrono::steady_clock::now();
auto elapsed = std::chrono::duration_cast<std::chrono::milliseconds>(
now - last_eval_).count();
if (cache_valid_ && elapsed < cache_duration_ms_) {
return cached_result_;
}
cached_result_ = child_node_->executeTick();
last_eval_ = now;
cache_valid_ = true;
return cached_result_;
}
static BT::PortsList providedPorts() {
return {BT::InputPort<int>("cache_duration_ms", 100,
"Cache duration in milliseconds")};
}
private:
int cache_duration_ms_{100};
std::chrono::steady_clock::time_point last_eval_;
BT::NodeStatus cached_result_{BT::NodeStatus::FAILURE};
bool cache_valid_{false};
};
XML에서의 사용:
<ReactiveSequence>
<!-- 500ms 동안 캐싱 -->
<Cache cache_duration_ms="500">
<Condition ID="IsPathClear"/>
</Cache>
<Action ID="NavigateToGoal"/>
</ReactiveSequence>
4. 캐시 무효화 전략
캐싱된 결과가 더 이상 유효하지 않은 상황을 정확히 감지하여 캐시를 무효화(invalidation)해야 한다. 잘못된 캐시 유지는 트리의 논리적 오류를 유발한다.
4.1 명시적 무효화
외부 이벤트(센서 고장, 모드 전환 등)에 의해 캐시를 명시적으로 무효화한다.
void invalidateCache() {
cache_valid_ = false;
}
4.2 Halt 시 무효화
노드에 Halt가 호출되면 캐시를 무효화하여, 재시작 시 정확한 상태를 반영하도록 한다.
void halt() override {
cache_valid_ = false;
BT::ConditionNode::halt();
}
4.3 의존 키 변화 시 무효화
블랙보드에서 조건이 의존하는 모든 키를 감시하고, 하나라도 변경되면 캐시를 무효화한다.
5. 캐싱 기법의 비교
| 캐싱 전략 | 재평가 조건 | 정밀도 | 구현 복잡도 | 적합한 상황 |
|---|---|---|---|---|
| 시간 기반 | 지정 시간 경과 | 낮음 | 낮음 | 변화 빈도가 예측 가능한 조건 |
| Tick 횟수 기반 | 지정 Tick 경과 | 낮음 | 낮음 | 가변 Tick 주기 환경 |
| 입력 변화 기반 | 입력 값 변경 | 높음 | 중간 | 수치 기반 조건 |
| 시퀀스 번호 기반 | 블랙보드 갱신 | 높음 | 낮음 | 블랙보드 의존 조건 |
| 데코레이터 패턴 | 설정에 따름 | 설정에 따름 | 낮음 | 기존 노드 수정 불가 시 |
6. 캐싱의 안전성 제약
캐싱은 조건의 재평가 빈도를 줄이므로, 조건 변화의 감지가 지연된다. 이 지연이 로봇의 안전에 영향을 미칠 수 있는 조건에는 캐싱을 적용해서는 안 된다. 구체적으로, 다음의 조건 유형은 캐싱 대상에서 제외해야 한다(Colledanchise & Ogren, 2018).
- 비상 정지 조건: 장애물 감지, 충돌 임박 판정
- 안전 임계값 조건: 배터리 잔량, 온도 과열, 통신 연결 상태
- 빠르게 변하는 환경 조건: 동적 장애물의 위치, 실시간 센서 값
캐싱의 적용 여부와 캐시 지속 시간은 조건의 변화 속도와 안전 요구 수준을 종합적으로 고려하여 결정해야 한다.
참고 문헌
- 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/