1295.91 Parallel 자식 수 증가에 따른 Tick 시간 영향

1295.91 Parallel 자식 수 증가에 따른 Tick 시간 영향

1. 선형 증가 모델

Parallel 노드의 Tick 시간은 자식 수 N에 대해 선형적으로 증가한다. 이는 단일 스레드에서 모든 자식을 순차적으로 Tick하는 구조에 기인한다.

T_{\text{tick}}(N) = T_{\text{overhead}} + \sum_{i=1}^{N} T_{\text{child}_i}

자식의 Tick 비용이 동일하다고 가정하면(T_{\text{child}_i} = T_c) 다음과 같이 단순화된다.

T_{\text{tick}}(N) = T_{\text{overhead}} + N \cdot T_c

T_{\text{overhead}}는 정책 평가, 상태 집계 등의 비용으로, 자식 수에 대해 O(N)이다. 따라서 전체 Tick 시간은 O(N)이다.

2. 실측 데이터를 통한 검증

자식 수를 변화시키면서 Parallel 노드의 Tick 시간을 측정하는 벤치마크를 구성한다.

void benchmarkParallelTickTime(BT::BehaviorTreeFactory& factory)
{
    std::vector<int> child_counts = {2, 4, 8, 16, 32, 64};

    for (int n : child_counts)
    {
        auto tree = createParallelTree(factory, n);

        // 워밍업
        for (int i = 0; i < 10; i++)
            tree->tickOnce();

        // 측정
        std::vector<double> times;
        for (int i = 0; i < 1000; i++)
        {
            tree->haltTree();
            auto start = std::chrono::steady_clock::now();
            tree->tickOnce();
            auto elapsed = std::chrono::duration_cast<
                std::chrono::nanoseconds>(
                std::chrono::steady_clock::now() - start);
            times.push_back(elapsed.count() / 1000.0);  // us
        }

        double avg = std::accumulate(times.begin(), times.end(), 0.0)
                     / times.size();
        auto max_it = std::max_element(times.begin(), times.end());

        std::cout << "N=" << std::setw(3) << n
                  << "  avg=" << std::setw(8) << std::fixed 
                  << std::setprecision(1) << avg << " us"
                  << "  max=" << std::setw(8) << *max_it << " us"
                  << std::endl;
    }
}

경량 조건 노드(블랙보드 읽기만 수행)를 자식으로 사용하는 경우의 전형적 결과이다.

자식 수 (N)평균 Tick 시간 (μs)최대 Tick 시간 (μs)자식당 비용 (μs)
23.28.51.6
45.812.31.45
811.222.11.4
1621.538.71.34
3242.372.41.32
6484.1145.21.31

자식당 비용이 N 증가에 따라 약간 감소하는 것은 캐시 지역성(cache locality) 효과에 의한 것이다. 전체적으로 선형 증가 패턴이 확인된다.

3. 자식 유형별 영향 분석

자식 노드의 유형에 따라 Tick 비용이 크게 다르므로, 동일한 자식 수라도 전체 Tick 시간에 상이한 영향을 미친다.

3.1 경량 자식의 경우

블랙보드에서 값을 읽기만 하는 조건 노드의 Tick 비용은 1~5 μs 수준이다.

T_{\text{tick}}(N) \approx 2 + 1.5N \text{ (μs)}

자식 20개일 때 약 32 μs로, 대부분의 Tick 주기 예산 내에 수용된다.

중량 자식의 경우

ROS2 토픽 구독, 서비스 호출, 센서 데이터 처리 등을 수행하는 행동 노드의 Tick 비용은 100 μs ~ 수 ms이다.

T_{\text{tick}}(N) \approx 2 + 500N \text{ (μs, 중량 자식 기준)}

자식 10개일 때 약 5 ms로, 10 ms Tick 주기의 절반을 소비한다. 자식 20개이면 10 ms를 초과하여 Tick 주기 위반이 발생한다.

3.2 혼합 구성의 경우

실제 Parallel 구성은 경량 조건 노드와 중량 행동 노드가 혼합된다. 이 경우 전체 Tick 시간은 중량 자식에 의해 지배된다.

Parallel 구성: 조건 3개 (각 2 us) + 행동 2개 (각 300 us)
총 Tick 시간 ≈ 2 + (3 × 2) + (2 × 300) = 608 us

조건 노드의 비용(6 μs)은 전체의 약 1%에 불과하며, 행동 노드의 비용(600 μs)이 99%를 차지한다.

4. 확장성 한계

4.1 Tick 주기 기반 한계

Tick 주기 예산 T_{\text{budget}}이 주어졌을 때, 허용 가능한 최대 자식 수 N_{\text{max}}를 산출한다.

N_{\text{max}} = \frac{T_{\text{budget}} - T_{\text{overhead}}}{\bar{T}_c}

여기서 \bar{T}_c는 자식의 평균 Tick 비용이다.

Tick 주기 예산경량 자식 (\bar{T}_c = 2 μs)중량 자식 (\bar{T}_c = 500 μs)
1 ms~500~2
5 ms~2500~10
10 ms~5000~20
50 ms~25000~100

경량 조건 노드만으로 구성하면 수천 개의 자식도 수용 가능하지만, 중량 행동 노드가 포함되면 자식 수가 수십 개로 제한된다.

메모리 영향

자식 수 증가는 메모리 사용량에도 영향을 미친다. BehaviorTree.CPP에서 각 노드는 상태 정보, 포트 정보, 블랙보드 참조 등을 유지하므로, 노드당 수백 바이트에서 수 킬로바이트의 메모리를 소비한다. 자식 수가 수백 개를 초과하면 임베디드 시스템에서 메모리 제약이 발생할 수 있다.

실용적 지침

권장 자식 수

실무에서 Parallel 노드의 자식 수에 대한 지침은 다음과 같다.

상황권장 자식 수근거
안전 감시 + 주 행동2~3안전 감시는 경량, 주 행동은 1개
다중 센서 융합3~5센서당 하나의 자식
다중 행동 동시 실행2~4중량 행동의 누적 비용
대규모 모니터링5~10조건 노드 위주의 경량 구성

자식 수 초과 시 대안

자식 수가 권장 범위를 초과하는 경우의 대안이다.

  1. 계층적 Parallel 구성: 하나의 Parallel에 모든 자식을 배치하는 대신, 관련 자식을 서브트리로 그룹화하여 계층적으로 구성한다.
<!-- 비권장: 자식 8개의 단일 Parallel -->
<ParallelAll max_failures="0">
    <Sensor1/> <Sensor2/> <Sensor3/> <Sensor4/>
    <Action1/> <Action2/> <Action3/> <Action4/>
</ParallelAll>

<!-- 권장: 계층적 Parallel -->
<ParallelAll max_failures="0">
    <ParallelAll name="Sensors" max_failures="1">
        <Sensor1/> <Sensor2/> <Sensor3/> <Sensor4/>
    </ParallelAll>
    <ParallelAll name="Actions" max_failures="0">
        <Action1/> <Action2/> <Action3/> <Action4/>
    </ParallelAll>
</ParallelAll>
  1. 비동기 처리 위임: 중량 연산을 ROS2 액션 서버 등의 별도 프로세스로 위임하고, 행동 노드는 진행 상황만 확인하는 경량 폴링(polling)으로 구현한다.

  2. Tick 주기 분리: 모든 자식을 매 Tick에서 실행하지 않고, 자식별로 다른 주기를 적용하여 Tick당 실행 자식 수를 제한한다.

벤치마크 자동화

지속적 통합(CI) 환경에서 Parallel 노드의 Tick 시간 회귀(regression)를 감지하기 위한 벤치마크 자동화를 구성한다.

TEST(PerformanceTest, ParallelTickTimeRegression)
{
    auto tree = createTypicalParallelTree();

    // 1000회 Tick 측정
    std::vector<double> times;
    for (int i = 0; i < 1000; i++)
    {
        tree->haltTree();
        auto start = std::chrono::steady_clock::now();
        tree->tickOnce();
        auto elapsed = std::chrono::duration_cast<
            std::chrono::microseconds>(
            std::chrono::steady_clock::now() - start);
        times.push_back(elapsed.count());
    }

    double avg = std::accumulate(times.begin(), times.end(), 0.0)
                 / times.size();
    double max_val = *std::max_element(times.begin(), times.end());

    // 성능 회귀 감지: 평균이 기준의 150%를 초과하면 실패
    EXPECT_LT(avg, 100.0)    // 평균 100 us 이내
        << "Average tick time regression detected";
    EXPECT_LT(max_val, 500.0)  // 최대 500 us 이내
        << "Worst-case tick time regression detected";
}

이 테스트를 CI 파이프라인에 포함하면, 코드 변경에 의한 성능 저하를 조기에 감지할 수 있다.