1295.86 디버깅 전략

1. Parallel 및 Reactive 노드 디버깅의 난이도

Parallel 노드와 Reactive 노드(ReactiveSequence, ReactiveFallback)는 행동 트리에서 디버깅이 가장 어려운 노드 범주에 속한다. 그 이유는 다음과 같다.

  1. 다중 자식의 동시 상태 관리: Parallel 노드는 모든 자식의 상태를 동시에 추적하여야 하므로, 단일 경로를 따르는 Sequence/Fallback에 비해 상태 공간이 기하급수적으로 증가한다.

  2. 매 Tick 재평가: Reactive 노드는 매 Tick마다 자식을 처음부터 재평가하므로, 특정 Tick에서 어떤 자식이 어떤 순서로 평가되었는지를 추적하여야 한다.

  3. Halt의 비가시성: Halt 전파는 노드의 반환값에 직접 반영되지 않으므로, 로그나 시각화 도구 없이는 Halt가 정확히 수행되었는지를 확인하기 어렵다.

  4. 정책의 복합성: 성공/실패 정책의 충족 여부가 다수 자식의 상태 조합에 의존하므로, 개별 자식의 상태만으로는 Parallel의 결과를 즉시 판단하기 어렵다.

2. BehaviorTree.CPP의 내장 디버깅 기능

2.1 로거(Logger) 인프라

BehaviorTree.CPP는 BT::StatusChangeLogger 기반의 로거 인프라를 제공한다. 노드의 상태 변화가 발생할 때마다 콜백이 호출되어 로그를 기록한다.

#include "behaviortree_cpp/loggers/bt_cout_logger.h"
#include "behaviortree_cpp/loggers/bt_file_logger2.h"
#include "behaviortree_cpp/loggers/bt_minitrace_logger.h"

BT::Tree tree = factory.createTreeFromText(xml_text);

// 콘솔 로거: 상태 변화를 표준 출력에 기록
BT::StdCoutLogger cout_logger(tree);

// 파일 로거: 상태 변화를 바이너리 파일에 기록 (Groot2 호환)
BT::FileLogger2 file_logger(tree, "bt_trace.btlog");

// MiniTrace 로거: Chrome Tracing 형식으로 기록
BT::MinitraceLogger minitrace_logger(tree, "bt_trace.json");

2.2 콘솔 로거의 출력 형식

StdCoutLogger는 노드의 상태 변화를 다음 형식으로 출력한다.

[ParallelAll] IDLE -> RUNNING
  [NavigateToGoal] IDLE -> RUNNING
  [MonitorBattery] IDLE -> RUNNING
  [MonitorBattery] RUNNING -> SUCCESS
  [NavigateToGoal] RUNNING -> SUCCESS
[ParallelAll] RUNNING -> SUCCESS

Parallel 노드의 경우 모든 자식의 상태 변화가 순차적으로 기록되므로, 어떤 자식이 어떤 순서로 상태를 변경하였는지를 추적할 수 있다.

2.3 Groot2를 활용한 실시간 시각화

Groot2는 BehaviorTree.CPP의 공식 시각화 도구이다. BT::Groot2Publisher를 트리에 연결하면 실행 중인 트리의 상태를 실시간으로 시각화할 수 있다.

#include "behaviortree_cpp/loggers/groot2_publisher.h"

BT::Tree tree = factory.createTreeFromText(xml_text);

// Groot2 퍼블리셔: TCP 소켓을 통해 Groot2에 상태 전송
BT::Groot2Publisher groot_publisher(tree, 1667);

Groot2에서 Parallel 노드를 시각화하면, 각 자식 노드의 현재 상태가 색상으로 표시된다. RUNNING은 노란색, SUCCESS는 녹색, FAILURE는 빨간색, IDLE은 회색으로 표현된다. Reactive 노드에서 우선순위 전환이 발생하면, 이전 분기의 색상이 IDLE로 전환되고 새 분기가 활성화되는 과정을 시각적으로 확인할 수 있다.

3. 커스텀 디버깅 로거의 구현

내장 로거가 제공하는 정보가 충분하지 않은 경우, 커스텀 로거를 구현하여 Parallel 및 Reactive 노드에 특화된 디버깅 정보를 수집할 수 있다.

class ParallelDebugLogger : public BT::StatusChangeLogger
{
public:
    ParallelDebugLogger(const BT::Tree& tree)
        : StatusChangeLogger(tree.rootNode()) {}

    void callback(BT::Duration timestamp,
                  const BT::TreeNode& node,
                  BT::NodeStatus prev_status,
                  BT::NodeStatus status) override
    {
        // Parallel 노드의 자식 상태 변화 추적
        auto* parent = node.getParent();
        if (parent && parent->type() == BT::NodeType::CONTROL)
        {
            std::cout << "[" << timestamp.count() << "us] "
                      << parent->name() << "/" << node.name()
                      << ": " << toStr(prev_status) 
                      << " -> " << toStr(status) << std::endl;
        }

        // Halt 감지
        if (status == BT::NodeStatus::IDLE && 
            prev_status == BT::NodeStatus::RUNNING)
        {
            std::cout << "  ** HALT detected: " << node.name() 
                      << std::endl;
        }
    }

    void flush() override {}
};

이 커스텀 로거는 부모-자식 관계를 함께 출력하여 Parallel 노드의 어떤 자식이 상태를 변경하였는지를 명확히 식별하고, RUNNING에서 IDLE로의 전이를 감지하여 Halt 발생을 명시적으로 표시한다.

4. 디버깅 접근 방법

4.1 상태 스냅샷 기법

매 Tick에서 Parallel 노드의 모든 자식 상태를 스냅샷으로 기록하는 기법이다.

class ParallelStateSnapshot
{
public:
    struct Snapshot
    {
        int tick_number;
        std::vector<std::pair<std::string, BT::NodeStatus>> child_states;
        BT::NodeStatus parallel_result;
    };

    void capture(int tick, const BT::ControlNode* parallel_node)
    {
        Snapshot snap;
        snap.tick_number = tick;
        snap.parallel_result = parallel_node->status();

        for (size_t i = 0; i < parallel_node->childrenCount(); i++)
        {
            auto* child = parallel_node->child(i);
            snap.child_states.emplace_back(
                child->name(), child->status());
        }

        snapshots_.push_back(snap);
    }

    void printAll() const
    {
        for (const auto& snap : snapshots_)
        {
            std::cout << "Tick " << snap.tick_number 
                      << " [Parallel=" << toStr(snap.parallel_result)
                      << "]:" << std::endl;
            for (const auto& [name, status] : snap.child_states)
            {
                std::cout << "  " << name << ": " 
                          << toStr(status) << std::endl;
            }
        }
    }

private:
    std::vector<Snapshot> snapshots_;
};

이 스냅샷을 매 Tick에서 수집하면, Parallel 노드의 자식 상태가 Tick에 따라 어떻게 변화하는지를 시계열로 분석할 수 있다.

4.2 조건부 중단점 기법

특정 조건이 충족될 때만 실행을 중단하는 디버깅 기법이다. BehaviorTree.CPP 자체는 중단점을 지원하지 않으나, 커스텀 데코레이터를 통해 유사한 기능을 구현할 수 있다.

class DebugBreakpoint : public BT::DecoratorNode
{
public:
    DebugBreakpoint(const std::string& name, 
                    const BT::NodeConfig& config)
        : DecoratorNode(name, config) {}

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<std::string>("break_on", "SUCCESS",
                "중단 조건 (SUCCESS, FAILURE, RUNNING)")
        };
    }

    BT::NodeStatus tick() override
    {
        auto child_status = child_node_->executeTick();

        std::string break_condition;
        getInput("break_on", break_condition);

        if (toStr(child_status) == break_condition)
        {
            std::cerr << "[BREAKPOINT] " << name() 
                      << ": child returned " << break_condition
                      << std::endl;
            // 디버거 연결 시 여기에 실제 중단점 설정
            // __builtin_debugtrap(); // 또는 raise(SIGTRAP);
        }

        return child_status;
    }
};

4.3 블랙보드 상태 덤프 기법

Parallel 자식 간 블랙보드 데이터 충돌을 진단하기 위해, 매 Tick에서 블랙보드의 관련 키-값 쌍을 덤프한다.

void dumpBlackboard(const BT::Blackboard& bb,
                    const std::vector<std::string>& keys,
                    int tick_number)
{
    std::cout << "=== Blackboard Dump (Tick " 
              << tick_number << ") ===" << std::endl;
    for (const auto& key : keys)
    {
        auto entry = bb.getEntry(key);
        if (entry)
        {
            std::cout << "  " << key << " = " 
                      << entry->value.type().name() << std::endl;
        }
        else
        {
            std::cout << "  " << key << " = <not set>" << std::endl;
        }
    }
}

5. 일반적 결함 유형과 진단 방법

5.1 Parallel이 예상과 다른 결과를 반환하는 경우

증상: Parallel이 SUCCESS를 반환하여야 하는데 FAILURE를 반환하거나, 그 반대이다.

진단 절차:

  1. 상태 스냅샷을 활성화하여 정책 판정 시점의 자식 상태를 확인한다.
  2. 성공/실패 정책의 매개변수(max_failures 등)가 올바르게 설정되었는지 확인한다.
  3. 자식의 완료 순서가 예상과 다른지 확인한다.

5.2 Reactive 노드에서 선점이 발생하지 않는 경우

증상: 상위 조건이 활성화되었으나 하위 분기가 계속 실행된다.

진단 절차:

  1. 조건 노드가 실제로 매 Tick마다 재평가되는지 로그로 확인한다.
  2. 조건 노드가 SyncActionNode가 아닌 ConditionNode로 올바르게 구현되었는지 확인한다.
  3. ReactiveFallback 대신 일반 Fallback이 사용되지 않았는지 XML을 확인한다.

5.3 Halt가 전파되지 않는 경우

증상: 정책 충족 후에도 자식이 계속 RUNNING 상태를 유지한다.

진단 절차:

  1. 커스텀 노드의 halt() 메서드가 올바르게 구현되었는지 확인한다. ControlNode::halt()를 호출하였는지, haltChildren()을 호출하였는지 확인한다.
  2. StatefulActionNodeonHalted()가 구현되었는지 확인한다.
  3. 로거에서 RUNNING → IDLE 전이가 기록되는지 확인한다.

6. 디버깅 도구 선택 기준

디버깅 도구적합한 상황장점제한
StdCoutLogger개발 초기 단계설정이 간단대량 로그 시 가독성 저하
FileLogger2사후 분석Groot2 재생 가능실시간 확인 불가
Groot2Publisher실시간 모니터링시각적 직관성네트워크 오버헤드
MinitraceLogger타이밍 분석Chrome DevTools 호환상태 정보 제한
커스텀 로거특정 노드 심층 분석맞춤 정보 수집구현 비용
상태 스냅샷정책 판정 진단상태 조합 전체 기록메모리 사용량

개발 단계에서는 StdCoutLogger와 Groot2를 병용하는 것이 효율적이며, 운영 환경에서의 사후 분석에는 FileLogger2를 활용한다. Parallel 자식의 상태 조합에 대한 심층 분석이 필요한 경우 커스텀 로거와 상태 스냅샷을 조합하여 사용한다.