1293.92 주기적 Tick과 이벤트 기반 Tick의 혼합
1. 혼합 실행 모델의 동기
순수 주기적 Tick 모델은 이벤트가 없는 기간에도 동일한 연산을 반복하여 자원을 낭비하며, 이벤트에 대한 응답이 최대 1주기만큼 지연된다. 반면, 순수 이벤트 기반 모델은 RUNNING 상태의 비동기 노드에 대한 주기적 재방문이 보장되지 않고, 이벤트 소스가 누락되면 트리가 영구적으로 정지할 위험이 있다. 이 두 모델의 단점을 보완하기 위해, 주기적 Tick을 기본 프레임으로 유지하면서 긴급 이벤트 발생 시 즉각 Tick을 추가로 실행하는 혼합(hybrid) 모델이 사용된다(Colledanchise & Ogren, 2018).
2. 혼합 모델의 구조
혼합 모델은 두 가지 Tick 트리거 소스를 동시에 운용한다.
┌───────────────────────────────────────────┐
│ 혼합 Tick 실행기 │
│ │
│ ┌─────────────┐ ┌──────────────────┐ │
│ │ 주기적 타이머 │ │ 이벤트 감지기 │ │
│ │ (10~100 Hz) │ │ (토픽, 서비스, │ │
│ │ │ │ 블랙보드 변경) │ │
│ └──────┬──────┘ └────────┬─────────┘ │
│ │ │ │
│ ▼ ▼ │
│ ┌──────────────────────────────┐ │
│ │ Tick 스케줄러 │ │
│ │ (중복 방지, 최소 간격 보장) │ │
│ └──────────────┬───────────────┘ │
│ ▼ │
│ tree.tickOnce() │
└───────────────────────────────────────────┘
3. 혼합 실행기의 구현
class HybridTickExecutor {
public:
HybridTickExecutor(BT::Tree& tree,
rclcpp::Node::SharedPtr node,
int base_rate_hz)
: tree_(tree), node_(node),
base_period_(std::chrono::milliseconds(1000 / base_rate_hz)) {}
void run() {
auto next_tick_time = std::chrono::steady_clock::now();
while (rclcpp::ok()) {
// ROS2 콜백 처리
rclcpp::spin_some(node_);
auto now = std::chrono::steady_clock::now();
bool should_tick = false;
// 주기적 Tick 조건
if (now >= next_tick_time) {
should_tick = true;
next_tick_time = now + base_period_;
}
// 이벤트 기반 Tick 조건
if (event_pending_.exchange(false)) {
should_tick = true;
// 이벤트에 의한 Tick 후 주기 타이머 리셋
next_tick_time = now + base_period_;
}
if (should_tick) {
executeTick();
}
// 짧은 대기로 CPU 점유 제한
std::this_thread::sleep_for(std::chrono::microseconds(500));
}
}
void triggerEvent() {
event_pending_ = true;
}
private:
void executeTick() {
std::lock_guard<std::mutex> lock(tick_mutex_);
tree_.tickOnce();
tick_count_++;
}
BT::Tree& tree_;
rclcpp::Node::SharedPtr node_;
std::chrono::milliseconds base_period_;
std::atomic<bool> event_pending_{false};
std::mutex tick_mutex_;
int tick_count_{0};
};
4. 이벤트 우선순위에 따른 차등 처리
모든 이벤트가 동일한 긴급도를 가지지 않으므로, 이벤트 유형에 따라 차등적인 Tick 정책을 적용한다.
4.1 긴급 이벤트
안전 관련 이벤트(비상 정지, 충돌 감지)는 즉각 Tick을 트리거하며, 현재 대기 중인 주기적 Tick보다 우선적으로 처리된다.
void onEmergencyEvent() {
// 블랙보드 갱신 후 즉각 Tick
tree_.rootBlackboard()->set("emergency", true);
executor_.triggerEvent();
}
4.2 일반 이벤트
목표 변경, 새로운 경로 수신 등의 일반 이벤트는 다음 주기적 Tick에서 함께 처리되거나, 설정에 따라 즉각 Tick을 트리거한다.
4.3 저우선순위 이벤트
로그 업데이트, 상태 보고 등의 저우선순위 이벤트는 별도의 Tick을 트리거하지 않고, 다음 주기적 Tick에서 자연스럽게 처리된다.
enum class EventPriority { HIGH, NORMAL, LOW };
void handleEvent(EventPriority priority) {
switch (priority) {
case EventPriority::HIGH:
executor_.triggerEvent(); // 즉각 Tick
break;
case EventPriority::NORMAL:
if (config_.trigger_on_normal_events) {
executor_.triggerEvent();
}
break;
case EventPriority::LOW:
// 다음 주기적 Tick에서 처리
break;
}
}
5. 적응적 주기 조정
혼합 모델에서 기본 주기를 시스템 상태에 따라 동적으로 조정하는 전략이다. RUNNING 상태의 노드가 없으면 주기를 낮추어 자원을 절약하고, 활성 작업이 많으면 주기를 높여 응답성을 유지한다.
void adjustBaseRate(const BT::Tree& tree) {
auto root_status = tree.rootNode()->status();
if (root_status == BT::NodeStatus::RUNNING) {
// 활성 작업 중: 높은 주기
base_period_ = std::chrono::milliseconds(10); // 100 Hz
} else {
// 유휴 상태: 낮은 주기
base_period_ = std::chrono::milliseconds(100); // 10 Hz
}
}
6. 이벤트 통합과 중복 제거
짧은 시간 내에 동일한 유형의 이벤트가 다수 발생하면, 각각에 대해 Tick을 실행하는 것은 낭비이다. 이벤트 통합(event coalescing)을 통해 동일 유형의 이벤트를 하나로 병합하고, 가장 최신의 데이터만을 사용하여 단일 Tick을 실행한다.
class EventCoalescer {
public:
void recordEvent(const std::string& type) {
std::lock_guard<std::mutex> lock(mutex_);
pending_events_.insert(type);
}
bool consumeEvents() {
std::lock_guard<std::mutex> lock(mutex_);
bool had_events = !pending_events_.empty();
pending_events_.clear();
return had_events;
}
private:
std::set<std::string> pending_events_;
std::mutex mutex_;
};
7. 혼합 모델의 설계 지침
| 설계 항목 | 권장 사항 |
|---|---|
| 기본 주기 | 10~100 Hz (로봇 특성에 따라 설정) |
| 긴급 이벤트 | 항상 즉각 Tick 트리거 |
| 일반 이벤트 | 응답 요구에 따라 즉각 또는 지연 처리 |
| 최소 Tick 간격 | 주기의 50% 이상 권장 |
| 이벤트 통합 | 동일 유형 이벤트 병합 |
| RUNNING 노드 | 주기적 Tick으로 재방문 보장 |
| 적응적 주기 | 시스템 부하에 따라 동적 조정 |
혼합 모델은 주기적 Tick의 예측 가능성과 이벤트 기반 Tick의 응답성을 동시에 확보하는 실무적으로 가장 널리 적용되는 접근이다. Nav2 등 ROS2 기반 네비게이션 프레임워크에서도 주기적 Tick을 기본으로 하면서 특정 이벤트에 대한 즉각 반응을 지원하는 유사한 구조를 채택하고 있다(Macenski et al., 2020).
참고 문헌
- 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/
- Macenski, S., Martín, F., White, R., & Clavero, J. G. (2020). The Marathon 2: A Navigation System. arXiv preprint arXiv:2003.00368.