1295.87 Parallel 자식 동시 실행 추적

1. 동시 실행 추적의 필요성

Parallel 노드는 모든 자식에게 Tick을 전파하여 논리적 동시 실행을 구현한다. 그러나 실제로는 단일 스레드에서 자식이 순차적으로 Tick되므로, 각 자식의 실행 순서, 소요 시간, 상태 변화를 추적하는 것이 디버깅과 성능 분석에 필수적이다. 특히 다수의 자식이 있는 Parallel 노드에서 특정 자식의 지연이 전체 Tick 시간에 미치는 영향을 파악하기 위해서는 자식별 실행 추적이 요구된다.

2. Tick 단위 실행 추적 로거

Parallel 노드의 각 자식이 Tick되는 순서와 소요 시간을 추적하는 로거를 구현한다.

class ParallelExecutionTracer : public BT::StatusChangeLogger
{
public:
    struct TickRecord
    {
        int tick_number;
        std::string child_name;
        BT::NodeStatus before;
        BT::NodeStatus after;
        std::chrono::microseconds duration;
    };

    ParallelExecutionTracer(const BT::Tree& tree)
        : StatusChangeLogger(tree.rootNode()) {}

    void callback(BT::Duration timestamp,
                  const BT::TreeNode& node,
                  BT::NodeStatus prev_status,
                  BT::NodeStatus status) override
    {
        auto* parent = node.getParent();
        if (!parent) return;

        // Parallel 노드의 직접 자식인 경우만 추적
        if (parent->registrationName() == "ParallelAll" ||
            parent->registrationName() == "ParallelNode")
        {
            TickRecord record;
            record.tick_number = current_tick_;
            record.child_name = node.name();
            record.before = prev_status;
            record.after = status;
            record.duration = std::chrono::duration_cast<
                std::chrono::microseconds>(timestamp - last_timestamp_);

            records_.push_back(record);
            last_timestamp_ = timestamp;
        }
    }

    void onNewTick() { current_tick_++; }
    const std::vector<TickRecord>& records() const { return records_; }
    void flush() override {}

private:
    std::vector<TickRecord> records_;
    int current_tick_ = 0;
    BT::Duration last_timestamp_{};
};

3. 상태 행렬 기반 추적

Parallel 노드의 모든 자식 상태를 Tick별 행렬(matrix)로 기록하면, 자식 간의 상태 변화 패턴을 한눈에 파악할 수 있다.

class ParallelStateMatrix
{
public:
    using StateRow = std::vector<BT::NodeStatus>;

    void recordTick(const BT::ControlNode* parallel_node)
    {
        StateRow row;
        for (size_t i = 0; i < parallel_node->childrenCount(); i++)
        {
            row.push_back(parallel_node->child(i)->status());
        }
        matrix_.push_back(row);
    }

    void printMatrix(
        const std::vector<std::string>& child_names) const
    {
        // 헤더 출력
        std::cout << std::setw(6) << "Tick";
        for (const auto& name : child_names)
            std::cout << std::setw(12) << name;
        std::cout << std::endl;

        // 행 출력
        for (size_t tick = 0; tick < matrix_.size(); tick++)
        {
            std::cout << std::setw(6) << tick;
            for (const auto& status : matrix_[tick])
            {
                std::cout << std::setw(12) << BT::toStr(status);
            }
            std::cout << std::endl;
        }
    }

    // 특정 자식의 상태 전이 시점 탐색
    int findTransitionTick(size_t child_index,
                           BT::NodeStatus from,
                           BT::NodeStatus to) const
    {
        for (size_t tick = 1; tick < matrix_.size(); tick++)
        {
            if (matrix_[tick - 1][child_index] == from &&
                matrix_[tick][child_index] == to)
            {
                return static_cast<int>(tick);
            }
        }
        return -1;  // 전이 미발견
    }

private:
    std::vector<StateRow> matrix_;
};

상태 행렬의 출력 예시는 다음과 같다.

  Tick  NavigateToGoal  MonitorBattery  MonitorSafety
     0         IDLE           IDLE          IDLE
     1       RUNNING        RUNNING       RUNNING
     2       RUNNING        SUCCESS       RUNNING
     3       RUNNING        SUCCESS       RUNNING
     4       SUCCESS        SUCCESS       SUCCESS

이 행렬에서 MonitorBattery가 Tick 2에서 SUCCESS로 전이한 반면, NavigateToGoal은 Tick 4까지 RUNNING을 유지하였음을 확인할 수 있다.

4. 자식별 Tick 소요 시간 프로파일링

Parallel 노드의 각 자식이 tick() 호출에 소요하는 시간을 측정하여, 성능 병목을 식별한다.

class ParallelTickProfiler
{
public:
    struct ProfileEntry
    {
        std::string child_name;
        std::chrono::microseconds total_time{0};
        std::chrono::microseconds max_time{0};
        std::chrono::microseconds min_time{
            std::chrono::microseconds::max()};
        int tick_count = 0;
    };

    void beginChild(const std::string& name)
    {
        current_child_ = name;
        start_time_ = std::chrono::steady_clock::now();
    }

    void endChild()
    {
        auto elapsed = std::chrono::duration_cast<
            std::chrono::microseconds>(
            std::chrono::steady_clock::now() - start_time_);

        auto& entry = profiles_[current_child_];
        entry.child_name = current_child_;
        entry.total_time += elapsed;
        entry.max_time = std::max(entry.max_time, elapsed);
        entry.min_time = std::min(entry.min_time, elapsed);
        entry.tick_count++;
    }

    void printReport() const
    {
        std::cout << std::setw(20) << "Child"
                  << std::setw(12) << "AvgTime(us)"
                  << std::setw(12) << "MaxTime(us)"
                  << std::setw(12) << "MinTime(us)"
                  << std::setw(8) << "Ticks"
                  << std::endl;

        for (const auto& [name, entry] : profiles_)
        {
            auto avg = entry.total_time.count() / entry.tick_count;
            std::cout << std::setw(20) << name
                      << std::setw(12) << avg
                      << std::setw(12) << entry.max_time.count()
                      << std::setw(12) << entry.min_time.count()
                      << std::setw(8) << entry.tick_count
                      << std::endl;
        }
    }

private:
    std::map<std::string, ProfileEntry> profiles_;
    std::string current_child_;
    std::chrono::steady_clock::time_point start_time_;
};

프로파일링 결과의 예시이다.

               Child  AvgTime(us)  MaxTime(us)  MinTime(us)   Ticks
      NavigateToGoal          450         1200           80     100
      MonitorBattery           12           25            8     100
       MonitorSafety           15           30           10     100

이 결과에서 NavigateToGoal의 평균 Tick 소요 시간이 450μs로, 다른 자식(12~15μs)에 비해 30배 이상 크다는 것을 확인할 수 있다. 이는 Parallel 노드 전체의 Tick 시간이 NavigateToGoal에 의해 지배됨을 의미한다.

5. Chrome Tracing 형식 출력

BehaviorTree.CPP의 MinitraceLogger는 Chrome Tracing 형식(chrome://tracing)으로 로그를 출력한다. 이 형식은 Parallel 자식의 시간적 배치를 시각적으로 확인하는 데 유용하다.

BT::Tree tree = factory.createTreeFromText(xml_text);
BT::MinitraceLogger minitrace(tree, "parallel_trace.json");

// 트리 실행
while (tree.tickOnce() == BT::NodeStatus::RUNNING)
{
    std::this_thread::sleep_for(std::chrono::milliseconds(10));
}

생성된 parallel_trace.json 파일을 Chrome 브라우저의 chrome://tracing에서 열면, 각 자식 노드의 실행이 타임라인 위에 수평 막대로 표시된다. Parallel 노드의 자식은 동일 Tick 내에서 순차적으로 배치되어, 논리적 동시 실행이 실제로는 순차적 Tick으로 구현됨을 시각적으로 확인할 수 있다.

6. 자식 실행 순서의 영향 추적

Parallel 노드에서 자식의 Tick 순서는 XML에서의 선언 순서를 따른다. 이 순서가 결과에 영향을 미치는지를 추적하는 것이 중요하다.

class ExecutionOrderTracker
{
public:
    void recordExecution(int tick, const std::string& child_name,
                         BT::NodeStatus result)
    {
        order_log_.push_back({tick, child_name, result});
    }

    // 특정 Tick에서의 실행 순서 출력
    void printTickOrder(int tick) const
    {
        std::cout << "Tick " << tick << " execution order:"
                  << std::endl;
        int seq = 0;
        for (const auto& entry : order_log_)
        {
            if (entry.tick == tick)
            {
                std::cout << "  [" << seq++ << "] " 
                          << entry.child_name
                          << " -> " << BT::toStr(entry.result)
                          << std::endl;
            }
        }
    }

    // 블랙보드 쓰기 충돌 가능성 진단
    void detectWriteConflicts(
        const std::map<std::string, std::vector<std::string>>& 
            write_keys) const
    {
        // write_keys: 자식 이름 → 블랙보드에 쓰는 키 목록
        std::map<std::string, std::vector<std::string>> key_writers;
        for (const auto& [child, keys] : write_keys)
        {
            for (const auto& key : keys)
                key_writers[key].push_back(child);
        }

        for (const auto& [key, writers] : key_writers)
        {
            if (writers.size() > 1)
            {
                std::cerr << "[WARNING] Blackboard key '" << key
                          << "' written by multiple children: ";
                for (const auto& w : writers)
                    std::cerr << w << " ";
                std::cerr << std::endl;
            }
        }
    }

private:
    struct Entry
    {
        int tick;
        std::string child_name;
        BT::NodeStatus result;
    };
    std::vector<Entry> order_log_;
};

블랙보드 쓰기 충돌 진단은 Parallel 자식 간의 데이터 경합 가능성을 사전에 식별하여, 실행 순서에 의존하는 미묘한 결함을 방지한다.

7. 실무 적용 절차

Parallel 자식 동시 실행 추적을 실무에 적용하는 절차를 정리한다.

  1. 추적 로거 연결: 트리 생성 후 ParallelExecutionTracer 또는 MinitraceLogger를 연결한다.

  2. 상태 행렬 수집: 의심되는 Parallel 노드에 대해 ParallelStateMatrix를 구성하여 Tick별 자식 상태를 기록한다.

  3. 성능 프로파일링: ParallelTickProfiler로 자식별 Tick 소요 시간을 측정하여 병목을 식별한다.

  4. 블랙보드 충돌 진단: ExecutionOrderTracker의 충돌 진단 기능으로 데이터 경합 가능성을 확인한다.

  5. 시각적 분석: Chrome Tracing 또는 Groot2를 통해 시각적으로 실행 흐름을 검토한다.

이러한 추적 도구를 개발 및 테스트 단계에서 활용하되, 프로덕션 환경에서는 성능 오버헤드를 고려하여 로깅 수준을 조절하거나 비활성화하여야 한다.