1293.88 Tick 실행 경로의 최적화
1. Tick 실행 경로의 개념
Tick 실행 경로(Tick execution path)란, 단일 Tick에서 루트 노드로부터 시작하여 실제로 방문되는 노드들의 순서화된 집합을 의미한다. 행동 트리의 깊이 우선, 왼쪽에서 오른쪽 전파 규칙에 의해, 매 Tick의 실행 경로는 트리의 구조와 각 노드의 현재 상태에 의해 결정된다. Tick 실행 경로의 최적화란, 동일한 논리적 결과를 산출하면서 방문 노드의 수와 각 노드의 실행 비용을 최소화하는 기법이다(Colledanchise & Ogren, 2018).
2. 실행 경로 분석
2.1 최선 경로와 최악 경로
트리의 구조에 따라 Tick당 방문 노드 수의 최솟값과 최댓값이 결정된다.
Fallback
/ | \
C₁ C₂ A₁
최선 경로: Root → Fallback → C₁(SUCCESS) → 방문 3개
최악 경로: Root → Fallback → C₁(FAIL) → C₂(FAIL) → A₁ → 방문 5개
Fallback 노드에서 첫 번째 자식이 SUCCESS를 반환하면 나머지 자식은 방문되지 않는다. 반면, 모든 조건이 FAILURE를 반환하면 마지막 자식까지 방문해야 한다. 이러한 경로 길이의 변동은 Tick 실행 시간의 변동성을 야기한다.
2.2 평균 경로 길이의 추정
실행 로그로부터 Tick당 평균 방문 노드 수를 계측하여, 트리의 전형적인 실행 경로 길이를 파악한다.
class PathLengthMonitor : public BT::StatusChangeLogger {
public:
void callback(BT::Duration timestamp,
const BT::TreeNode& node,
BT::NodeStatus prev_status,
BT::NodeStatus status) override {
if (prev_status == BT::NodeStatus::IDLE) {
current_tick_visits_++;
}
}
void onTickCompleted() {
total_visits_ += current_tick_visits_;
tick_count_++;
max_visits_ = std::max(max_visits_, current_tick_visits_);
current_tick_visits_ = 0;
}
double averagePathLength() const {
return static_cast<double>(total_visits_) / tick_count_;
}
void flush() override {}
private:
int current_tick_visits_{0};
long total_visits_{0};
int tick_count_{0};
int max_visits_{0};
};
3. 트리 구조 재배치에 의한 경로 최적화
3.1 조건 노드의 전방 배치
Sequence 노드에서 FAILURE를 반환할 가능성이 높은 조건 노드를 앞쪽에 배치하면, 조기 종료에 의해 후속 노드의 불필요한 방문을 방지할 수 있다. Fallback 노드에서는 SUCCESS를 반환할 가능성이 높은 노드를 앞쪽에 배치한다.
<!-- 최적화 전: 비용 큰 조건이 앞에 위치 -->
<Sequence>
<Condition ID="IsPathClear"/> <!-- 비용 높음, 성공률 95% -->
<Condition ID="IsBatteryAbove20"/> <!-- 비용 낮음, 성공률 80% -->
<Action ID="Navigate"/>
</Sequence>
<!-- 최적화 후: 실패 가능성 높은 조건을 앞으로 -->
<Sequence>
<Condition ID="IsBatteryAbove20"/> <!-- 비용 낮음, 실패 시 조기 종료 -->
<Condition ID="IsPathClear"/> <!-- 실패율 낮으므로 뒤에 배치 -->
<Action ID="Navigate"/>
</Sequence>
최적 배치는 각 조건의 실패 확률(p_f)과 평가 비용(c)을 고려하여 결정한다. Sequence에서는 p_f / c가 큰 조건을 앞에, Fallback에서는 성공 확률 대비 비용이 유리한 노드를 앞에 배치하는 것이 일반적 원칙이다.
3.2 빈번한 분기의 상위 배치
Fallback 노드에서 가장 빈번하게 성공하는 분기를 첫 번째 자식으로 배치하면, 대부분의 Tick에서 짧은 경로로 실행이 완료된다.
<!-- 로봇이 80%의 시간을 정상 네비게이션에 사용한다면 -->
<Fallback>
<!-- 가장 빈번한 시나리오를 첫 번째로 -->
<Sequence>
<Condition ID="IsNavigating"/>
<Action ID="ContinueNavigation"/>
</Sequence>
<!-- 덜 빈번한 시나리오 -->
<Sequence>
<Condition ID="IsRecovering"/>
<Action ID="ExecuteRecovery"/>
</Sequence>
<!-- 가장 드문 시나리오 -->
<Action ID="RequestHelp"/>
</Fallback>
4. 트리 깊이 최소화
트리의 깊이가 깊을수록 루트에서 리프까지의 경로가 길어지고, 각 Tick에서 방문해야 하는 내부 노드의 수가 증가한다. 트리의 논리를 변경하지 않으면서 깊이를 줄이는 구조적 리팩토링을 적용할 수 있다.
4.1 불필요한 중첩 제거
단일 자식만을 가진 제어 노드나, 논리적으로 무의미한 중첩을 제거한다.
<!-- 최적화 전: 불필요한 Sequence 중첩 -->
<Sequence>
<Sequence>
<Condition ID="CondA"/>
<Action ID="ActionA"/>
</Sequence>
</Sequence>
<!-- 최적화 후: 단일 Sequence로 평탄화 -->
<Sequence>
<Condition ID="CondA"/>
<Action ID="ActionA"/>
</Sequence>
4.2 동일 유형 제어 노드의 병합
연속된 동일 유형의 제어 노드는 하나의 노드로 병합할 수 있다. Sequence 안에 Sequence가 있고 중간에 다른 노드가 없다면, 내부 Sequence의 자식을 외부 Sequence에 직접 포함시킬 수 있다.
<!-- 최적화 전 -->
<Sequence>
<Condition ID="CondA"/>
<Sequence>
<Condition ID="CondB"/>
<Action ID="ActionB"/>
</Sequence>
</Sequence>
<!-- 최적화 후 (WithMemory 동작이 동일한 경우에만) -->
<Sequence>
<Condition ID="CondA"/>
<Condition ID="CondB"/>
<Action ID="ActionB"/>
</Sequence>
단, 이 병합은 내부 Sequence와 외부 Sequence의 WithMemory 설정이 동일할 때에만 의미론적으로 동등하다.
5. 서브트리 호출 비용의 최적화
서브트리는 모듈화와 재사용성을 위한 핵심 메커니즘이지만, 서브트리 호출 시 블랙보드 포트 매핑과 트리 전환에 따른 오버헤드가 발생한다. 빈번하게 호출되는 서브트리의 경우, 포트 매핑의 수를 최소화하거나 _autoremap을 활용하여 매핑 비용을 절감할 수 있다.
<!-- 포트 매핑 최소화 -->
<SubTree ID="SimpleCheck" _autoremap="true"/>
6. 실행 경로 최적화와 유지보수성의 균형
트리 구조의 최적화는 성능을 향상시키지만, 과도한 최적화는 트리의 가독성과 유지보수성을 저하시킬 수 있다. 깊이 있는 중첩이 논리적 그룹화를 명확히 표현하는 경우, 성능상의 이점이 미미하다면 구조적 명료성을 우선해야 한다. 최적화는 프로파일링을 통해 병목으로 확인된 경로에 집중하고, 가독성과 성능 사이의 적절한 균형을 유지해야 한다(Faconti, 2022).
참고 문헌
- 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/