1293.74 Tick 시간 초과 시 처리 전략

1. 시간 초과 처리의 필요성

Tick 실행 시간이 설정된 예산을 초과하면, 후속 Tick의 지연이 누적되어 시스템의 시간적 정확성이 저하된다. 시간 초과 시 적절한 처리 전략을 적용하지 않으면, 조건 재평가가 지연되고 외부 상태 변화에 대한 응답이 늦어져 로봇의 안전성이 위협받을 수 있다. 시간 초과 처리 전략은 오버런의 영향을 최소화하고 시스템의 정상 운영을 복구하기 위한 체계적 접근이다(Colledanchise & Ogren, 2018).

2. 즉시 다음 Tick 실행

오버런 발생 시 sleep 시간을 0으로 설정하여 즉시 다음 Tick을 실행하는 전략이다. 이는 누적된 지연을 빠르게 회복하기 위한 방법이다.

void tickLoop() {
    auto next_tick_time = std::chrono::steady_clock::now();
    const auto tick_period = std::chrono::milliseconds(100);
    
    while (rclcpp::ok()) {
        executor_.spin_some();
        tree_.tickOnce();
        
        next_tick_time += tick_period;
        auto now = std::chrono::steady_clock::now();
        
        if (now < next_tick_time) {
            std::this_thread::sleep_until(next_tick_time);
        } else {
            // 오버런: sleep 없이 즉시 다음 Tick
            RCLCPP_WARN(logger_, "Tick overrun, skipping sleep");
            // next_tick_time을 현재로 리셋하여 지연 누적 방지
            next_tick_time = now;
        }
    }
}

3. Tick 건너뛰기(Skip)

오버런으로 인해 다음 Tick 시점이 이미 지난 경우, 해당 Tick을 건너뛰고 다다음 Tick 시점에 실행하는 전략이다.

void tickLoop() {
    auto next_tick_time = std::chrono::steady_clock::now();
    const auto tick_period = std::chrono::milliseconds(100);
    int skipped_ticks = 0;
    
    while (rclcpp::ok()) {
        executor_.spin_some();
        tree_.tickOnce();
        
        next_tick_time += tick_period;
        auto now = std::chrono::steady_clock::now();
        
        while (next_tick_time <= now) {
            next_tick_time += tick_period;
            skipped_ticks++;
        }
        
        if (skipped_ticks > 0) {
            RCLCPP_WARN(logger_, "Skipped %d ticks due to overrun", 
                       skipped_ticks);
            skipped_ticks = 0;
        }
        
        std::this_thread::sleep_until(next_tick_time);
    }
}

4. 비필수 노드 건너뛰기

오버런이 감지되면 현재 Tick 내에서 비필수 노드의 Tick을 건너뛰어 실행 시간을 줄이는 전략이다. 로깅, 시각화, 통계 수집 등의 부차적 노드가 건너뛰기 대상이다.

class SkippableAction : public BT::SyncActionNode {
public:
    BT::NodeStatus tick() override {
        if (isOverrunMode()) {
            // 오버런 모드: 비필수 작업 건너뛰기
            return BT::NodeStatus::SUCCESS;
        }
        
        // 정상 모드: 전체 작업 수행
        performLogging();
        updateVisualization();
        return BT::NodeStatus::SUCCESS;
    }
};

5. Tick 주기 동적 조정

연속적 오버런이 발생하면 Tick 주기를 자동으로 늘려 오버런을 방지하는 전략이다.

class AdaptiveTickRate {
public:
    void onOverrun() {
        consecutive_overruns_++;
        if (consecutive_overruns_ >= threshold_) {
            // Tick 주기 증가 (주파수 감소)
            current_period_ = std::min(
                current_period_ * 1.5,
                max_period_
            );
            consecutive_overruns_ = 0;
            RCLCPP_WARN(logger_, 
                "Tick period increased to %.1f ms",
                current_period_.count() / 1000.0);
        }
    }

    void onNormalTick() {
        consecutive_overruns_ = 0;
        // 정상 상태에서 점진적으로 원래 주기로 복귀
        if (current_period_ > target_period_) {
            current_period_ = std::max(
                current_period_ * 0.95,
                target_period_
            );
        }
    }

private:
    std::chrono::microseconds current_period_;
    std::chrono::microseconds target_period_;
    std::chrono::microseconds max_period_;
    int consecutive_overruns_{0};
    int threshold_{3};
};

6. 안전 모드 전환

심각한 오버런(예산의 2배 이상 초과 또는 연속 다수 회 오버런)이 발생하면, 트리를 축소된 안전 모드 트리로 전환하는 전략이다.

void onCriticalOverrun() {
    RCLCPP_ERROR(logger_, "Critical overrun: switching to safe mode tree");
    
    // 현재 트리의 모든 RUNNING 노드를 Halt
    tree_.haltTree();
    
    // 안전 모드 트리로 전환
    tree_ = factory_.createTreeFromFile("safe_mode_tree.xml");
    
    // 안전 모드 진입 상태 발행
    publishSafetyStatus(SafetyLevel::SAFE_MODE);
}

안전 모드 트리는 필수적인 안전 조건 확인과 정지 명령만을 포함하는 경량 트리로 구성된다.

7. 처리 전략의 비교

전략장점단점적용 상황
즉시 다음 Tick지연 회복 빠름연속 오버런 시 효과 없음일시적 부하 증가
Tick 건너뛰기주기 정확성 유지건너뛴 Tick의 상태 변화 미반영간헐적 오버런
비필수 노드 건너뛰기Tick 내 부하 감소부차적 기능 손실경미한 오버런
Tick 주기 조정구조적 해결응답성 저하지속적 오버런
안전 모드 전환안전 보장기능 대폭 축소심각한 오버런

8. 계층적 처리 전략

실무에서는 오버런의 심각도에 따라 계층적으로 대응 전략을 적용한다.

단계 1 (경미): 즉시 다음 Tick + 경고 로그
  → 해결되지 않으면
단계 2 (보통): 비필수 노드 건너뛰기 + 진단 발행
  → 해결되지 않으면
단계 3 (심각): Tick 주기 동적 증가
  → 해결되지 않으면
단계 4 (치명): 안전 모드 트리 전환

각 단계의 전환 조건은 연속 오버런 횟수, 오버런 비율, 초과 시간의 크기 등을 기준으로 설정한다.


참고 문헌

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