1293.86 불필요한 노드 Tick 방지
1. 불필요한 노드 Tick의 정의
불필요한 노드 Tick이란, Tick 전파 과정에서 특정 노드가 방문되어 tick() 함수가 호출되지만, 그 실행 결과가 트리의 최종 출력이나 로봇의 동작에 영향을 미치지 않는 경우를 의미한다. 이러한 불필요한 방문은 CPU 시간을 소비하고 Tick 실행 시간을 증가시키며, 특히 대규모 트리에서 심각한 성능 저하를 유발할 수 있다(Colledanchise & Ogren, 2018).
2. 불필요한 Tick이 발생하는 상황
2.1 이미 확정된 결과의 재평가
WithMemory 모드가 아닌 Sequence 노드에서, 이전 Tick에서 SUCCESS를 반환한 조건 노드가 매 Tick마다 다시 평가되는 경우가 있다. 이 조건이 변하지 않는 정적 조건이라면, 매번 재평가하는 것은 낭비이다.
ReactiveSequence:
├── IsMapLoaded ← 한 번 로드되면 항상 SUCCESS
├── IsBatteryAbove20 ← 동적 조건, 재평가 필요
└── NavigateToGoal ← RUNNING 상태
위 예에서 IsMapLoaded는 맵이 로드된 이후 항상 SUCCESS를 반환하므로, 매 Tick마다 재평가할 필요가 없다. 그러나 ReactiveSequence의 의미론에 의해 모든 자식이 매 Tick마다 재평가된다.
2.2 비활성 분기의 방문
Fallback 노드에서 첫 번째 자식이 SUCCESS를 반환하면, 나머지 자식은 평가되지 않는다. 이는 조기 종료(short-circuit) 메커니즘에 의해 자연스럽게 방지된다. 그러나 트리 구조가 복잡해지면, 논리적으로 도달할 수 없는 분기가 존재할 수 있으며, 이러한 분기의 존재 자체가 트리 설계의 비효율을 나타낸다.
2.3 IDLE 상태 노드의 불필요한 초기화
WithoutMemory 모드에서 Sequence가 재시작될 때, 이전에 IDLE로 복귀한 모든 자식 노드가 처음부터 다시 Tick된다. 이미 완료된 작업을 다시 수행하는 것이 논리적으로 불필요한 경우, 이는 중복 실행에 해당한다.
3. WithMemory를 통한 재방문 방지
WithMemory 모드의 Sequence 및 Fallback 노드는 이전 Tick에서 확정된 자식의 결과를 기억하고, RUNNING 상태의 자식부터 재개한다. 이를 통해 이미 SUCCESS를 반환한 자식의 불필요한 재평가를 방지한다.
// BehaviorTree.CPP v4에서의 WithMemory Sequence 동작
// XML: <Sequence> (기본이 WithMemory)
// 자식 A → SUCCESS (Tick 1에서 완료)
// 자식 B → RUNNING (Tick 1에서 시작)
//
// Tick 2: 자식 A를 건너뛰고 자식 B부터 재개
WithMemory와 Reactive 모드의 선택은 성능과 안전성 사이의 트레이드오프이다.
| 모드 | 재평가 범위 | 성능 | 조건 변화 감지 |
|---|---|---|---|
| WithMemory | RUNNING 자식부터 | 높음 | 불가 |
| Reactive | 첫 자식부터 | 낮음 | 가능 |
4. 조건 노드의 선택적 평가
4.1 정적 조건과 동적 조건의 분리
조건 노드를 변화 빈도에 따라 분류하고, 정적 조건은 결과를 캐싱하여 재평가를 방지한다.
class CachedCondition : public BT::ConditionNode {
public:
CachedCondition(const std::string& name, const BT::NodeConfig& config)
: BT::ConditionNode(name, config) {}
BT::NodeStatus tick() override {
// 결과가 확정되면 이후 Tick에서 재평가하지 않음
if (result_finalized_) {
return cached_result_;
}
cached_result_ = evaluateCondition();
// 한 번 결정되면 변하지 않는 조건인 경우
if (isStaticCondition()) {
result_finalized_ = true;
}
return cached_result_;
}
private:
virtual BT::NodeStatus evaluateCondition() = 0;
virtual bool isStaticCondition() const { return false; }
BT::NodeStatus cached_result_{BT::NodeStatus::IDLE};
bool result_finalized_{false};
};
4.2 변화 감지 기반 평가
블랙보드의 값이 실제로 변경된 경우에만 조건을 재평가하는 방식이다. 블랙보드의 타임스탬프 또는 시퀀스 번호를 활용하여 값의 변경 여부를 판단한다.
BT::NodeStatus tick() override {
auto entry = config().blackboard->getEntry("sensor_data");
// 시퀀스 번호를 통해 값 변경 여부 확인
auto current_seq = entry->sequence_id;
if (current_seq == last_seq_) {
return cached_result_; // 값이 변하지 않았으면 캐시 반환
}
last_seq_ = current_seq;
cached_result_ = evaluateCondition();
return cached_result_;
}
5. 서브트리 수준의 Tick 방지
5.1 비활성 서브트리의 건너뛰기
트리의 특정 분기가 현재 실행 컨텍스트에서 활성화되지 않을 조건이라면, 해당 분기 전체를 건너뛸 수 있다. 이를 위해 게이트(gate) 역할의 조건 노드를 서브트리 앞에 배치한다.
<Sequence>
<!-- 게이트 조건: 실내 환경일 때만 하위 트리 실행 -->
<Condition ID="IsIndoorEnvironment"/>
<SubTree ID="IndoorNavigationTree"/>
</Sequence>
게이트 조건이 FAILURE를 반환하면 Sequence의 조기 종료에 의해 서브트리 전체가 Tick되지 않는다.
5.2 Switch 노드를 통한 선택적 분기 실행
BehaviorTree.CPP v4의 Switch 노드는 조건 값에 따라 하나의 자식만을 선택적으로 Tick한다. 이는 다수의 Fallback 분기 중 하나만 활성화되는 경우, Fallback의 순차적 평가보다 효율적이다.
<Switch3 variable="{operation_mode}"
case_1="patrol" case_2="charge" case_3="manual">
<SubTree ID="PatrolBehavior"/>
<SubTree ID="ChargeBehavior"/>
<SubTree ID="ManualControlBehavior"/>
<AlwaysFailure/> <!-- 기본 분기 -->
</Switch3>
6. 데코레이터를 활용한 Tick 제어
6.1 SkipUnlessUpdated 데코레이터
자식 노드의 입력 포트가 갱신된 경우에만 자식을 Tick하고, 그렇지 않으면 이전 결과를 반환하는 데코레이터이다.
class SkipUnlessUpdated : public BT::DecoratorNode {
public:
BT::NodeStatus tick() override {
if (inputPortUpdated()) {
return child_node_->executeTick();
}
return last_result_;
}
private:
bool inputPortUpdated() const;
BT::NodeStatus last_result_{BT::NodeStatus::FAILURE};
};
6.2 Throttle 데코레이터
자식 노드의 Tick 빈도를 제한하는 데코레이터이다. 최소 간격을 설정하여 해당 간격 내에서는 이전 결과를 반환한다.
class Throttle : public BT::DecoratorNode {
public:
BT::NodeStatus tick() override {
auto now = std::chrono::steady_clock::now();
auto elapsed = std::chrono::duration_cast<std::chrono::milliseconds>(
now - last_tick_time_).count();
if (elapsed >= min_interval_ms_) {
last_tick_time_ = now;
last_result_ = child_node_->executeTick();
}
return last_result_;
}
private:
int min_interval_ms_{100};
std::chrono::steady_clock::time_point last_tick_time_;
BT::NodeStatus last_result_{BT::NodeStatus::FAILURE};
};
7. 불필요한 Tick 방지의 안전성 고려
불필요한 Tick을 방지하는 모든 기법은, 해당 노드의 재평가가 정말로 불필요한지에 대한 정확한 판단을 전제로 한다. 잘못된 판단에 의해 필요한 조건 재평가가 생략되면, 환경 변화에 대한 트리의 반응성이 저하되고 안전 위험이 발생할 수 있다. 따라서 안전 관련 조건(배터리 수준, 장애물 감지, 비상 정지 등)은 항상 매 Tick마다 평가해야 하며, 최적화 대상에서 제외해야 한다(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/