1295.90 성능 고려 사항
1. Parallel 및 Reactive 노드의 성능 특성
Parallel 노드와 Reactive 노드(ReactiveSequence, ReactiveFallback)는 일반 Sequence/Fallback에 비해 본질적으로 더 많은 연산을 수행한다. 일반 Sequence는 자식을 순차적으로 평가하되 이미 완료된 자식을 건너뛰므로, 매 Tick에서 하나의 RUNNING 자식만 Tick하면 된다. 반면 Parallel 노드는 매 Tick에서 모든 자식을 Tick하고, Reactive 노드는 매 Tick에서 처음부터 재평가를 수행한다. 이러한 구조적 차이가 성능에 미치는 영향을 정량적으로 이해하여야 한다.
2. Tick 시간 복잡도 분석
2.1 Parallel 노드의 Tick 시간
Parallel 노드의 단일 Tick 소요 시간 T_{\text{parallel}}은 모든 자식의 Tick 소요 시간의 합이다.
T_{\text{parallel}} = T_{\text{overhead}} + \sum_{i=1}^{N} T_{\text{child}_i}
여기서 T_{\text{overhead}}는 Parallel 노드 자체의 정책 평가, 상태 관리 등의 오버헤드이고, T_{\text{child}_i}는 i번째 자식의 Tick 소요 시간이다. N은 자식 수이다.
단일 스레드에서 실행되므로 자식의 Tick은 순차적으로 수행되며, 전체 시간은 개별 자식 시간의 합산이다.
Reactive 노드의 Tick 시간
ReactiveSequence의 단일 Tick 소요 시간은 재평가되는 자식의 수에 의존한다.
T_{\text{reactive\_seq}} = T_{\text{overhead}} + \sum_{i=1}^{k} T_{\text{child}_i}
여기서 k는 현재 Tick에서 평가되는 자식의 수이다. 첫 번째 자식이 FAILURE를 반환하면 k = 1이고, 모든 자식이 SUCCESS이거나 마지막 자식이 RUNNING이면 k = N이다.
2.2 일반 Sequence와의 비교
일반 Sequence(메모리 있는 Sequence)의 Tick 시간은 현재 활성 자식의 Tick 시간만을 포함한다.
T_{\text{sequence}} = T_{\text{overhead}} + T_{\text{active\_child}}
따라서 ReactiveSequence는 일반 Sequence에 비해 최대 N배의 Tick 시간을 소요할 수 있다.
| 노드 유형 | 매 Tick 평가 자식 수 | 최악 Tick 시간 |
|---|---|---|
| Sequence | 1 (활성 자식만) | T_{\text{overhead}} + T_{\text{max\_child}} |
| ReactiveSequence | 1 ~ N (처음부터 재평가) | T_{\text{overhead}} + \sum T_{\text{child}_i} |
| Parallel | N (모든 자식) | T_{\text{overhead}} + \sum T_{\text{child}_i} |
Tick 주기와 실시간 제약
로봇 시스템에서 행동 트리의 Tick 주기는 제어 루프의 주기와 맞추어야 한다. 일반적인 Tick 주기는 다음과 같다.
| 응용 분야 | Tick 주기 | Tick 시간 예산 |
|---|---|---|
| 산업용 매니퓰레이터 | 1~10 ms | < 1 ms |
| 이동 로봇 항법 | 10~100 ms | < 10 ms |
| 드론 비행 제어 | 5~20 ms | < 5 ms |
| 서비스 로봇 | 50~200 ms | < 50 ms |
Parallel 노드의 Tick 시간이 예산을 초과하면 제어 루프의 주기가 유지되지 않아, 로봇의 반응성이 저하되거나 안전 감시의 지연이 발생한다.
성능 병목의 원인
자식 노드의 Tick 비용
Parallel 노드의 성능 병목은 대부분 자식 노드의 Tick 비용에 기인한다. 조건 노드가 블랙보드에서 값을 읽는 것은 마이크로초 단위의 비용이지만, 행동 노드가 ROS2 서비스를 호출하거나 센서 데이터를 처리하면 밀리초 단위의 비용이 발생한다.
// 경량 조건 노드: ~1 us
BT::NodeStatus IsLocalized::tick()
{
auto localized = getInput<bool>("is_localized");
return localized.value() ? BT::NodeStatus::SUCCESS
: BT::NodeStatus::FAILURE;
}
// 중량 행동 노드: ~500 us ~ 수 ms
BT::NodeStatus ComputePath::tick()
{
// 경로 계획 알고리즘 실행
auto path = planner_.computePath(start, goal);
setOutput("path", path);
return BT::NodeStatus::SUCCESS;
}
블랙보드 접근 비용
블랙보드의 getInput()과 setOutput() 호출은 타입 변환과 문자열 검색을 포함하므로, 빈번한 호출은 누적 비용을 발생시킨다. Parallel 노드의 모든 자식이 매 Tick에서 블랙보드에 접근하면, 블랙보드 접근 횟수는 O(N \cdot P)가 된다. 여기서 P는 자식당 포트 수이다.
Halt 비용
Parallel 노드가 정책을 충족하여 haltChildren()을 호출할 때, 모든 자식에 대해 halt()가 순차적으로 호출된다. 자식의 halt() 구현이 ROS2 액션의 취소, 하드웨어 정지 명령 등을 포함하면 Halt 비용이 상당할 수 있다.
성능 최적화 전략
조건 노드의 경량화
Reactive 노드에서 매 Tick마다 재평가되는 조건 노드는 가능한 한 경량으로 구현하여야 한다. 조건 노드는 블랙보드에서 미리 계산된 값을 읽는 것으로 한정하고, 무거운 연산은 별도의 비동기 프로세스에서 수행하여 블랙보드에 결과를 기록하도록 설계한다.
// 권장: 블랙보드 값만 읽는 경량 조건
BT::NodeStatus IsBatteryLow::tick()
{
double level = getInput<double>("battery_level").value();
double threshold = getInput<double>("threshold").value();
return (level < threshold) ? BT::NodeStatus::SUCCESS
: BT::NodeStatus::FAILURE;
}
// 비권장: 조건 내에서 무거운 연산 수행
BT::NodeStatus IsPathBlocked::tick()
{
auto costmap = getCostmap(); // 비용 맵 복사: ~100 us
auto path = getInput<Path>("path").value();
return checkCollision(costmap, path) ? BT::NodeStatus::SUCCESS
: BT::NodeStatus::FAILURE;
}
이미 완료된 자식의 재Tick 회피
Parallel 노드에서 이미 SUCCESS 또는 FAILURE를 반환한 자식의 재Tick을 회피하면 불필요한 연산을 제거할 수 있다.
// 최적화된 Parallel tick
for (size_t i = 0; i < childrenCount(); i++)
{
auto current_status = children_nodes_[i]->status();
if (current_status == BT::NodeStatus::SUCCESS ||
current_status == BT::NodeStatus::FAILURE)
{
// 이미 완료된 자식은 건너뛰기
statuses[i] = current_status;
continue;
}
statuses[i] = children_nodes_[i]->executeTick();
}
BehaviorTree.CPP 4.x의 ParallelAll 노드는 이 최적화를 기본으로 적용한다.
조기 종료의 활용
정책 충족이 불가능한 경우를 조기에 감지하면, 남은 자식의 Tick을 생략할 수 있다. 예를 들어, SUCCESS_ALL 정책에서 하나의 자식이 FAILURE를 반환하면 나머지 자식을 Tick하지 않고 즉시 FAILURE를 반환한다.
Tick 주기의 분리
모든 자식을 동일한 Tick 주기로 실행할 필요가 없는 경우, 자식별로 다른 Tick 주기를 적용할 수 있다. 안전 감시 조건은 매 Tick마다, 환경 데이터 수집은 10 Tick마다 실행하는 방식이다.
BT::NodeStatus tick() override
{
for (size_t i = 0; i < childrenCount(); i++)
{
// 자식별 Tick 주기 적용
if (tick_count_ % tick_divisors_[i] != 0)
{
statuses[i] = children_nodes_[i]->status();
continue;
}
statuses[i] = children_nodes_[i]->executeTick();
}
tick_count_++;
// ... 정책 평가
}
성능 측정 방법
Tick 시간 측정
auto start = std::chrono::steady_clock::now();
auto status = tree.tickOnce();
auto elapsed = std::chrono::duration_cast<
std::chrono::microseconds>(
std::chrono::steady_clock::now() - start);
tick_times.push_back(elapsed);
통계 보고
void printTickStatistics(
const std::vector<std::chrono::microseconds>& times)
{
auto sum = std::accumulate(times.begin(), times.end(),
std::chrono::microseconds{0});
auto avg = sum / times.size();
auto max_it = std::max_element(times.begin(), times.end());
auto min_it = std::min_element(times.begin(), times.end());
std::cout << "Tick statistics:" << std::endl;
std::cout << " Average: " << avg.count() << " us" << std::endl;
std::cout << " Max: " << max_it->count() << " us" << std::endl;
std::cout << " Min: " << min_it->count() << " us" << std::endl;
std::cout << " Count: " << times.size() << std::endl;
}
실시간 시스템에서는 평균값보다 최악값(worst case)이 중요하다. Tick 시간의 최악값이 Tick 주기 예산을 초과하지 않는지를 확인하여야 한다.