1293.95 실시간 시스템에서의 Tick 보장
1. Tick 보장의 정의
실시간 시스템에서의 Tick 보장이란, 행동 트리의 Tick이 지정된 주기(period)와 데드라인(deadline) 내에서 확실하게 실행됨을 보증하는 것이다. 이 보장은 Tick 실행의 주기성(periodicity), 완료 시간의 상한(bounded execution time), 그리고 Tick 누락 없는 연속성(continuity)의 세 가지 속성을 포함한다.
2. 주기적 Tick 실행의 보장
2.1 실시간 타이머
ROS2의 기본 타이머는 범용 운영 체제의 타이머에 기반하므로, 정확한 주기 보장이 어렵다. 실시간 요구가 있는 경우, POSIX 실시간 타이머나 실시간 스케줄러 기반의 주기적 실행을 사용한다.
#include <time.h>
#include <signal.h>
class RealtimeTickTimer {
public:
RealtimeTickTimer(int period_us) : period_us_(period_us) {}
void run(BT::Tree& tree) {
struct timespec next_tick;
clock_gettime(CLOCK_MONOTONIC, &next_tick);
while (running_) {
// 다음 Tick 시점 계산
next_tick.tv_nsec += period_us_ * 1000;
if (next_tick.tv_nsec >= 1000000000L) {
next_tick.tv_sec++;
next_tick.tv_nsec -= 1000000000L;
}
// Tick 실행
tree.tickOnce();
// 다음 주기까지 정밀 대기
clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME,
&next_tick, nullptr);
}
}
private:
int period_us_;
std::atomic<bool> running_{true};
};
clock_nanosleep에 TIMER_ABSTIME 플래그를 사용하면 절대 시각 기반의 대기가 수행되어, Tick 실행 시간의 변동에 의한 주기 드리프트(drift)를 방지한다.
2.2 주기 정확도의 검증
Tick 주기의 실제 정확도를 측정하여 요구 사항을 충족하는지 검증한다.
class PeriodMonitor {
public:
void recordTick() {
auto now = std::chrono::steady_clock::now();
if (has_previous_) {
auto period = std::chrono::duration_cast<std::chrono::microseconds>(
now - previous_tick_).count();
jitter_us_ = std::abs(period - expected_period_us_);
max_jitter_us_ = std::max(max_jitter_us_, jitter_us_);
if (jitter_us_ > jitter_threshold_us_) {
RCLCPP_WARN(logger_,
"Tick period jitter: %ldus (threshold: %ldus)",
jitter_us_, jitter_threshold_us_);
}
}
previous_tick_ = now;
has_previous_ = true;
}
private:
std::chrono::steady_clock::time_point previous_tick_;
bool has_previous_{false};
long expected_period_us_;
long jitter_us_{0};
long max_jitter_us_{0};
long jitter_threshold_us_;
rclcpp::Logger logger_;
};
3. 최악 실행 시간의 보장
3.1 정적 분석에 의한 WCET 추정
최악 실행 시간(Worst-Case Execution Time, WCET)은 모든 가능한 실행 경로 중 가장 긴 실행 시간이다. 행동 트리의 WCET는 트리의 최악 순회 경로와 각 노드의 최악 실행 시간의 합으로 추정한다.
WCET_{tick} = \sum_{i \in \text{worst path}} WCET_{node_i} + C_{overhead}
여기서 C_{overhead}는 트리 순회, 블랙보드 접근, ROS2 콜백 처리 등의 고정 오버헤드이다.
실행 시간 제한 메커니즘
개별 노드의 실행 시간을 제한하는 워치독(watchdog) 메커니즘을 적용한다.
class WatchdogTickExecutor {
public:
BT::NodeStatus tickWithWatchdog(BT::Tree& tree,
std::chrono::microseconds timeout) {
auto start = std::chrono::steady_clock::now();
auto status = tree.tickOnce();
auto elapsed = std::chrono::steady_clock::now() - start;
if (elapsed > timeout) {
RCLCPP_ERROR(logger_,
"Tick exceeded watchdog: %ldus > %ldus",
std::chrono::duration_cast<std::chrono::microseconds>(elapsed).count(),
timeout.count());
handleOverrun();
}
return status;
}
private:
void handleOverrun() {
overrun_count_++;
if (overrun_count_ > max_consecutive_overruns_) {
enterSafeMode();
}
}
rclcpp::Logger logger_;
int overrun_count_{0};
int max_consecutive_overruns_{3};
};
Tick 누락 방지
누락 검출
예상 Tick 횟수와 실제 Tick 횟수를 비교하여 Tick 누락을 검출한다.
void checkTickMiss(int expected_tick_id) {
if (actual_tick_id_ != expected_tick_id) {
int missed = expected_tick_id - actual_tick_id_;
RCLCPP_WARN(logger_,
"Missed %d tick(s) at expected tick #%d",
missed, expected_tick_id);
// 누락 통계 기록
total_missed_ticks_ += missed;
actual_tick_id_ = expected_tick_id;
}
actual_tick_id_++;
}
누락 시 복구 전략
Tick 누락이 발생한 경우의 복구 전략은 시스템의 실시간 요구 수준에 따라 다르다.
| 전략 | 동작 | 적용 상황 |
|---|---|---|
| 건너뛰기 | 누락된 Tick을 무시하고 다음 주기 진행 | 연성 실시간 |
| 보상 실행 | 누락 횟수만큼 연속 Tick 실행 | 확고한 실시간 |
| 안전 모드 | 안전 행동으로 전환 | 경성 실시간 |
| 재시작 | 트리를 초기화하고 재시작 | 비치명적 시스템 |
자원 예약 기반 보장
CPU 시간 예약
실시간 스케줄링 정책(SCHED_FIFO, SCHED_DEADLINE)을 통해 Tick 실행 스레드에 충분한 CPU 시간을 예약한다.
#ifdef __linux__
#include <sched.h>
void setDeadlineScheduler(pid_t tid,
uint64_t runtime_ns,
uint64_t deadline_ns,
uint64_t period_ns) {
struct sched_attr attr;
memset(&attr, 0, sizeof(attr));
attr.size = sizeof(attr);
attr.sched_policy = SCHED_DEADLINE;
attr.sched_runtime = runtime_ns;
attr.sched_deadline = deadline_ns;
attr.sched_period = period_ns;
syscall(SYS_sched_setattr, tid, &attr, 0);
}
// 예: 10ms 주기, 5ms 실행 시간, 10ms 데드라인
setDeadlineScheduler(gettid(), 5000000, 10000000, 10000000);
#endif
SCHED_DEADLINE은 Linux 커널이 지정된 주기 내에서 보장된 CPU 시간을 제공하는 데드라인 기반 스케줄링 정책이다.
메모리 예약
Tick 실행에 필요한 모든 메모리를 사전에 할당하고 잠금(lock)하여, 실행 중 메모리 관련 지연을 제거한다.
void preallocateResources() {
// 스택 사전 확보
char stack_probe[1024 * 1024];
memset(stack_probe, 0, sizeof(stack_probe));
// 힙 메모리 사전 할당 및 잠금
mlockall(MCL_CURRENT | MCL_FUTURE);
}
실시간 ROS2 통신의 보장
행동 트리의 Tick 내에서 수행되는 ROS2 통신이 실시간 요구를 충족하려면, DDS 구현의 실시간 지원이 필요하다. Cyclone DDS, Fast DDS 등의 DDS 구현은 실시간 프로파일을 제공하며, 공유 메모리 전송(shared memory transport)을 통해 네트워크 계층의 비결정적 지연을 제거할 수 있다.
// 공유 메모리 기반 QoS 설정
rclcpp::QoS rt_qos(1);
rt_qos.reliable();
rt_qos.keep_last(1);
// DDS 벤더별 공유 메모리 설정은 QoS 프로파일 XML에서 구성
보장 수준의 검증
실시간 Tick 보장은 설계 단계의 정적 분석과 운영 단계의 동적 검증을 모두 필요로 한다. 동적 검증에서는 장시간의 스트레스 테스트를 수행하여, Tick 주기 지터, 데드라인 위반 빈도, 최대 실행 시간 등의 지표를 수집하고 요구 사항과 비교한다.
참고 문헌
- 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/