1293.96 Tick 데드라인 준수 전략
1. Tick 데드라인의 정의
Tick 데드라인이란, 단일 Tick의 실행이 완료되어야 하는 시간적 상한이다. Tick 주기가 T이면, 각 Tick은 해당 주기 내에 완료되어야 다음 Tick의 정시 실행이 보장된다. 데드라인을 위반하면 Tick의 누적 지연이 발생하고, 이는 로봇의 제어 응답성 저하와 센서 데이터의 실효성 상실로 이어진다(Colledanchise & Ogren, 2018).
2. 데드라인 준수를 위한 설계 전략
2.1 노드 실행 시간의 상한 설정
각 노드의 tick() 함수가 일정 시간 이내에 반환되도록 설계한다. 특히, 동기 노드는 블로킹 호출을 포함해서는 안 되며, 비동기 작업은 StatefulActionNode 패턴을 사용하여 RUNNING을 반환하고 다음 Tick에서 상태를 확인하는 비블로킹 방식으로 구현한다.
// 잘못된 설계: 동기 노드에서 블로킹 호출
BT::NodeStatus tick() override {
auto result = service_client_->call(request_); // 블로킹 — 데드라인 위반 위험
return processResult(result);
}
// 올바른 설계: 비동기 처리
BT::NodeStatus onStart() override {
future_ = service_client_->async_send_request(request_);
return BT::NodeStatus::RUNNING;
}
BT::NodeStatus onRunning() override {
if (future_.wait_for(std::chrono::milliseconds(0)) ==
std::future_status::ready) {
return processResult(future_.get());
}
return BT::NodeStatus::RUNNING;
}
2.2 Tick 시간 예산의 분배
전체 Tick 데드라인을 노드 그룹별로 분배하여, 각 그룹이 할당된 시간 내에 완료되도록 관리한다.
Tick 주기: 10ms
├── ROS2 콜백 처리: 2ms (20%)
├── 조건 노드 평가: 2ms (20%)
├── 액션 노드 실행: 4ms (40%)
└── 여유(margin): 2ms (20%)
여유 시간은 시스템 스케줄링 지터, 캐시 미스, 페이지 폴트 등의 비결정적 요인을 흡수하기 위해 확보한다. 일반적으로 전체 주기의 20~30%를 여유로 설정한다.
2.3 조기 종료의 활용
Tick 실행 중 경과 시간을 모니터링하여, 데드라인에 근접하면 나머지 노드의 평가를 생략하고 현재까지의 결과로 Tick을 완료하는 전략이다.
class DeadlineAwareExecutor {
public:
BT::NodeStatus tickWithDeadline(BT::Tree& tree,
std::chrono::microseconds deadline) {
tick_start_ = std::chrono::steady_clock::now();
deadline_ = deadline;
// 데드라인 정보를 블랙보드에 설정
auto bb = tree.rootBlackboard();
bb->set("tick_deadline_us", deadline.count());
bb->set("tick_start_time", tick_start_);
return tree.tickOnce();
}
bool isNearDeadline(double margin_ratio = 0.9) const {
auto elapsed = std::chrono::steady_clock::now() - tick_start_;
auto elapsed_us = std::chrono::duration_cast<
std::chrono::microseconds>(elapsed).count();
return elapsed_us >= deadline_.count() * margin_ratio;
}
private:
std::chrono::steady_clock::time_point tick_start_;
std::chrono::microseconds deadline_;
};
3. 데드라인 위반 시 대응 전략
3.1 단계적 대응
데드라인 위반의 심각도에 따라 단계적으로 대응한다.
enum class OverrunSeverity {
MINOR, // 데드라인의 110% 이내
MODERATE, // 데드라인의 150% 이내
SEVERE // 데드라인의 150% 초과
};
void handleOverrun(std::chrono::microseconds actual,
std::chrono::microseconds deadline) {
double ratio = static_cast<double>(actual.count()) / deadline.count();
if (ratio < 1.1) {
// 경미: 로그 기록만
RCLCPP_DEBUG(logger_, "Minor overrun: %.1f%%", ratio * 100);
} else if (ratio < 1.5) {
// 중간: 경고 및 비필수 노드 비활성화
RCLCPP_WARN(logger_, "Moderate overrun: %.1f%%", ratio * 100);
disableNonCriticalNodes();
} else {
// 심각: 안전 모드 진입
RCLCPP_ERROR(logger_, "Severe overrun: %.1f%%", ratio * 100);
enterSafeMode();
}
}
3.2 적응적 트리 축소
반복적인 데드라인 위반이 발생하면, 트리의 일부 분기를 동적으로 비활성화하여 Tick 실행 시간을 줄인다. 비필수 행동(로깅, 상태 보고, 보조 작업 등)을 순차적으로 비활성화하고, 핵심 행동(안전, 네비게이션)만 유지한다.
void reduceTreeComplexity(int level) {
switch (level) {
case 1:
// 상세 로깅 비활성화
disableLoggingNodes();
break;
case 2:
// 보조 모니터링 비활성화
disableMonitoringNodes();
break;
case 3:
// 비필수 행동 비활성화
disableOptionalBehaviors();
break;
case 4:
// 최소 안전 행동만 유지
activateSafetyOnlyMode();
break;
}
}
3.3 Tick 주기의 동적 조정
데드라인 위반이 지속되면 Tick 주기를 늘려 각 Tick의 시간 여유를 확보한다. 시스템 부하가 감소하면 원래 주기로 복귀한다.
void adaptTickPeriod(std::chrono::microseconds last_tick_time) {
if (last_tick_time > current_period_ * 0.9) {
// 데드라인에 근접: 주기 증가
current_period_ = std::min(
current_period_ * 1.5,
max_period_);
RCLCPP_WARN(logger_, "Increasing tick period to %ldus",
current_period_.count());
} else if (last_tick_time < current_period_ * 0.5 &&
current_period_ > nominal_period_) {
// 여유 충분: 주기 감소 (원래 주기로 복귀)
current_period_ = std::max(
current_period_ * 0.8,
nominal_period_);
}
}
4. 예방적 데드라인 관리
4.1 실행 시간 추세 분석
과거 Tick의 실행 시간 추세를 분석하여, 데드라인 위반이 발생하기 전에 선제적으로 대응한다.
class TrendAnalyzer {
public:
void addSample(long execution_time_us) {
samples_.push_back(execution_time_us);
if (samples_.size() > window_size_) {
samples_.pop_front();
}
}
bool isIncreasingTrend() const {
if (samples_.size() < window_size_) return false;
// 이동 평균의 기울기 계산
long first_half_avg = 0, second_half_avg = 0;
size_t half = samples_.size() / 2;
for (size_t i = 0; i < half; ++i)
first_half_avg += samples_[i];
for (size_t i = half; i < samples_.size(); ++i)
second_half_avg += samples_[i];
first_half_avg /= half;
second_half_avg /= (samples_.size() - half);
return second_half_avg > first_half_avg * 1.1;
}
private:
std::deque<long> samples_;
size_t window_size_{100};
};
5. 데드라인 준수 전략의 종합
| 전략 | 적용 시점 | 효과 | 부작용 |
|---|---|---|---|
| 비블로킹 설계 | 설계 시 | 근본적 해결 | 구현 복잡도 증가 |
| 시간 예산 분배 | 설계 시 | 체계적 관리 | 유연성 제한 |
| 조기 종료 | 실행 중 | 즉시 효과 | 행동 불완전 |
| 적응적 축소 | 실행 중 | 점진적 대응 | 기능 저하 |
| 주기 동적 조정 | 실행 중 | 여유 확보 | 응답성 저하 |
| 추세 분석 | 실행 중 | 사전 예방 | 오탐 가능 |
가장 효과적인 접근은 설계 단계에서 모든 노드를 비블로킹으로 구현하고, 실행 단계에서 모니터링과 적응적 대응을 병행하는 것이다.
참고 문헌
- 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/