1293.82 Tick 기반 디버깅 기법

1. Tick 기반 디버깅의 개념

Tick 기반 디버깅이란, 행동 트리의 Tick을 단위로 하여 실행 흐름을 분석하고 오류를 진단하는 기법이다. 전통적인 소스 코드 수준의 디버깅과 달리, Tick 기반 디버깅은 트리의 논리적 구조와 노드 상태의 시간적 변화에 초점을 맞춘다. 이는 행동 트리의 의사 결정 논리가 개별 함수가 아닌 트리 구조와 Tick 전파에 의해 결정되기 때문이다(Colledanchise & Ogren, 2018).

2. 디버깅 전략

2.1 로그 기반 사후 분석

실행 로그를 기록하고, 오류 발생 후 로그를 분석하여 원인을 추적하는 방식이다. 운영 환경에서 가장 실용적인 디버깅 방법이다.

디버깅 절차:
  1. FileLogger2로 실행 로그 기록
  2. 오류 발생 시점의 Tick 번호 식별
  3. Groot2에서 해당 Tick 전후의 상태 재생
  4. 상태 변화 시퀀스에서 비정상 전이 식별
  5. 원인 노드와 블랙보드 값 확인

2.2 실시간 모니터링

Groot2의 실시간 연결을 통해 트리의 현재 상태를 관찰하며 디버깅하는 방식이다.

// 실시간 모니터링 활성화
BT::Groot2Publisher groot_pub(tree, 1667);

// Groot2에서 localhost:1667로 연결하여 실시간 관찰

2.3 단계 실행(Step Execution)

Tick을 한 번에 하나씩 수동으로 실행하여, 각 Tick에서의 상태 변화를 확인하는 방식이다.

void stepDebug() {
    while (rclcpp::ok()) {
        printf("Press Enter to execute next tick (q to quit): ");
        char input;
        std::cin.get(input);
        
        if (input == 'q') break;
        
        executor_.spin_some();
        auto status = tree_.tickOnce();
        
        printf("Tick #%d completed. Tree status: %s\n",
               tick_count_++, BT::toStr(status).c_str());
        printTreeStatus(tree_);
        printBlackboard(tree_.rootBlackboard());
    }
}

3. 일반적 오류 유형과 진단 방법

3.1 노드가 예상과 다른 상태를 반환

증상: 조건 노드가 항상 FAILURE를 반환하여 후속 액션이 실행되지 않음.

진단 방법: 해당 노드의 입력 포트 값을 블랙보드에서 확인한다.

BT::NodeStatus tick() override {
    double battery;
    auto result = getInput("battery_level", battery);
    
    RCLCPP_DEBUG(logger_, "IsBatteryAbove: battery=%.2f, threshold=%.2f",
                 battery, threshold_);
    
    // 디버깅: 입력 포트의 실제 값 확인
    return (battery > threshold_) 
        ? BT::NodeStatus::SUCCESS 
        : BT::NodeStatus::FAILURE;
}

3.2 비동기 작업이 완료되지 않음

증상: 액션 노드가 RUNNING을 무한 반환.

진단 방법: onRunning()에서 외부 작업의 상태를 로깅한다.

BT::NodeStatus onRunning() override {
    auto status = goal_handle_->get_status();
    RCLCPP_DEBUG(logger_, 
        "NavigateAction onRunning: goal_status=%d, elapsed=%.1fs",
        status, getElapsedTime());
    
    // 타임아웃 검출
    if (getElapsedTime() > 60.0) {
        RCLCPP_ERROR(logger_, "NavigateAction timeout after 60s");
        return BT::NodeStatus::FAILURE;
    }
    
    return mapGoalStatus(status);
}

3.3 Halt가 자원을 정리하지 않음

증상: Halt 후 재시작 시 이전 작업의 잔류 상태가 간섭.

진단 방법: onHalted()에 로깅을 추가하여 호출 여부와 정리 과정을 확인한다.

3.4 블랙보드 값이 예상과 다름

증상: 노드가 잘못된 데이터에 기반하여 동작.

진단 방법: Tick 전후에 블랙보드의 주요 키 값을 출력한다.

void debugBlackboard(const BT::Blackboard::Ptr& bb) {
    RCLCPP_INFO(logger_, "=== Blackboard State ===");
    for (const auto& key : bb->getKeys()) {
        auto entry = bb->getEntry(key);
        RCLCPP_INFO(logger_, "  %s = %s",
                   std::string(key).c_str(),
                   entry->value.toStr().c_str());
    }
}

4. 조건부 로깅

디버깅 로그를 특정 조건에서만 활성화하여, 로그의 양을 관리 가능한 수준으로 유지한다.

BT::NodeStatus tick() override {
    auto result = evaluate();
    
    // 상태가 변경된 경우에만 로깅
    if (result != last_result_) {
        RCLCPP_INFO(logger_, "%s: %s -> %s",
                   name().c_str(),
                   BT::toStr(last_result_).c_str(),
                   BT::toStr(result).c_str());
        last_result_ = result;
    }
    
    return result;
}

5. 디버깅 도구 체계

도구용도장점단점
Groot2 실시간상태 관찰직관적, 실시간GUI 필요
Groot2 재생사후 분석상세 분석 가능로그 필요
ROS2 로깅상세 진단유연, 필터링 가능대량 출력
GDB/디버거코드 수준정밀 분석트리 논리 파악 어려움
단계 실행상호작용적제어 가능실시간 시나리오 불가
단위 테스트사전 검증자동화통합 동작 미검증

효과적인 디버깅은 이 도구들을 상황에 맞게 조합하여 사용하는 것이다. 트리 논리 수준의 오류는 Groot2와 로그 분석으로, 개별 노드의 구현 오류는 GDB와 단위 테스트로 진단한다.


참고 문헌

  • 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/