1293.18 ROS2 타이머 기반 Tick 구현
1. ROS2 타이머의 기본 원리
ROS2 타이머(Timer)는 지정된 주기마다 콜백 함수를 호출하는 메커니즘이다. rclcpp::Node::create_wall_timer() 또는 create_timer()를 통해 생성되며, ROS2 실행기(Executor)가 타이머의 만료 여부를 확인하고 해당 콜백을 실행한다. 행동 트리(Behavior Tree)의 Tick을 타이머 콜백으로 구현하면, Tick 주기가 ROS2의 시간 관리 체계에 통합되어 일관된 주기적 실행이 가능해진다(Macenski et al., 2022).
2. Wall Timer와 ROS Timer의 구분
ROS2는 두 종류의 타이머를 제공하며, 행동 트리의 Tick 구현에서 적절한 타이머 유형의 선택이 중요하다.
2.1 Wall Timer
create_wall_timer()로 생성되는 Wall Timer는 시스템 실시간 시계(wall clock)를 기반으로 동작한다. 실제 경과 시간에 따라 콜백이 호출되므로, 실제 로봇 환경에서의 Tick 구현에 적합하다.
tick_timer_ = this->create_wall_timer(
std::chrono::milliseconds(100),
std::bind(&BtNode::tick_callback, this)
);
2.2 ROS Timer
create_timer()로 생성되는 ROS Timer는 ROS2 시간 소스(time source)를 기반으로 동작한다. use_sim_time 파라미터가 활성화된 경우 시뮬레이션 시간을 따르므로, 시뮬레이션 환경에서의 Tick 구현에 적합하다. 시뮬레이션이 일시 정지(pause)되면 타이머도 정지하고, 시뮬레이션 속도가 변경되면 타이머의 실효 주기도 비례하여 변경된다.
tick_timer_ = this->create_timer(
std::chrono::milliseconds(100),
std::bind(&BtNode::tick_callback, this),
this->get_clock()
);
시뮬레이션과 실제 환경 모두에서 동작해야 하는 소프트웨어의 경우, ROS Timer를 사용하고 use_sim_time 파라미터로 시간 소스를 전환하는 것이 권장된다.
3. 기본 구현 구조
ROS2 타이머 기반 Tick의 기본 구현 구조는 다음과 같다.
#include <rclcpp/rclcpp.hpp>
#include <behaviortree_cpp/bt_factory.h>
class BtTickNode : public rclcpp::Node {
public:
BtTickNode() : Node("bt_tick_node") {
// 파라미터 선언 및 초기화
this->declare_parameter("tick_rate_hz", 10.0);
double tick_rate = this->get_parameter("tick_rate_hz")
.as_double();
// 행동 트리 생성
factory_.registerNodesFromPlugins(/* ... */);
tree_ = factory_.createTreeFromFile("tree.xml");
// 타이머 생성
auto period = std::chrono::duration_cast<
std::chrono::nanoseconds>(
std::chrono::duration<double>(1.0 / tick_rate));
tick_timer_ = this->create_wall_timer(
period,
std::bind(&BtTickNode::on_tick, this)
);
RCLCPP_INFO(this->get_logger(),
"Behavior tree tick started at %.1f Hz", tick_rate);
}
private:
void on_tick() {
auto start = std::chrono::steady_clock::now();
auto status = tree_.tickOnce();
auto elapsed = std::chrono::steady_clock::now() - start;
auto elapsed_ms = std::chrono::duration_cast<
std::chrono::milliseconds>(elapsed).count();
if (status != BT::NodeStatus::RUNNING) {
RCLCPP_INFO(this->get_logger(),
"Tree finished with status: %s",
BT::toStr(status).c_str());
tick_timer_->cancel();
}
}
BT::BehaviorTreeFactory factory_;
BT::Tree tree_;
rclcpp::TimerBase::SharedPtr tick_timer_;
};
4. 타이머 정밀도와 지터
ROS2 타이머의 실제 실행 주기는 설정된 주기와 정확히 일치하지 않을 수 있다. 타이머 콜백의 실행 시점은 실행기의 스케줄링, 운영체제의 스케줄러 해상도, 다른 콜백의 실행 시간 등에 의해 영향을 받으며, 이로 인해 실제 Tick 간격에 지터(jitter)가 발생한다.
지터의 크기는 다음 요인에 의해 결정된다.
| 요인 | 영향 |
|---|---|
| OS 스케줄러 해상도 | 일반 Linux: ~1ms, RT 커널: ~10\mus |
| 다른 콜백의 실행 시간 | 긴 콜백이 타이머 콜백의 실행을 지연시킴 |
| 실행기 유형 | SingleThreaded 실행기에서 더 큰 지터 발생 |
| 시스템 부하 | 높은 CPU 부하에서 지터 증가 |
지터를 측정하기 위해 각 Tick 콜백의 실행 시점을 기록하고, 연속 실행 간격의 통계적 분포를 분석할 수 있다.
void on_tick() {
auto now = std::chrono::steady_clock::now();
if (last_tick_time_.time_since_epoch().count() > 0) {
auto interval = now - last_tick_time_;
auto interval_ms = std::chrono::duration_cast<
std::chrono::microseconds>(interval).count();
// 지터 분석을 위한 간격 기록
tick_intervals_.push_back(interval_ms);
}
last_tick_time_ = now;
tree_.tickOnce();
}
5. 타이머 재진입 방지
타이머 콜백 내에서 Tick 실행이 타이머 주기보다 오래 걸리는 경우, 다음 타이머 콜백이 이전 Tick이 완료되기 전에 실행될 수 있다. SingleThreadedExecutor에서는 이 문제가 자연스럽게 방지되지만(동일 스레드에서 순차 실행), MultiThreadedExecutor에서는 동일한 타이머 콜백이 동시에 실행될 위험이 있다.
이를 방지하기 위해 MutuallyExclusiveCallbackGroup을 사용하거나, 실행 중 플래그(flag)를 통해 재진입을 차단한다.
void on_tick() {
if (tick_in_progress_.exchange(true)) {
RCLCPP_WARN(this->get_logger(),
"Tick overrun: previous tick still running");
return;
}
tree_.tickOnce();
tick_in_progress_.store(false);
}
std::atomic<bool> tick_in_progress_{false};
6. 타이머 수명 주기 관리
행동 트리의 실행이 완료(SUCCESS 또는 FAILURE)되면 타이머를 중지하여 불필요한 Tick 발생을 방지해야 한다. 또한 행동 트리를 재시작하거나 새로운 트리로 교체해야 하는 경우, 타이머의 중지와 재생성이 필요하다.
void start_tree(const std::string& tree_file) {
// 기존 타이머 중지
if (tick_timer_) {
tick_timer_->cancel();
}
// 새 트리 생성
tree_ = factory_.createTreeFromFile(tree_file);
// 타이머 재생성
tick_timer_ = this->create_wall_timer(
tick_period_,
std::bind(&BtTickNode::on_tick, this)
);
}
void stop_tree() {
if (tick_timer_) {
tick_timer_->cancel();
}
tree_.haltTree();
}
타이머 취소(cancel()) 시에는 현재 실행 중인 Tick 콜백이 완료될 때까지 대기하지 않으므로, 트리 해체(haltTree) 호출과의 순서에 주의해야 한다.
7. 실행 시간 모니터링 통합
타이머 기반 Tick 구현에 실행 시간 모니터링을 통합하면, Tick 오버런의 조기 감지와 성능 분석이 가능해진다.
void on_tick() {
auto start = std::chrono::steady_clock::now();
auto status = tree_.tickOnce();
auto elapsed = std::chrono::steady_clock::now() - start;
auto elapsed_us = std::chrono::duration_cast<
std::chrono::microseconds>(elapsed).count();
// 실행 시간 통계 갱신
tick_count_++;
total_exec_time_us_ += elapsed_us;
max_exec_time_us_ = std::max(max_exec_time_us_, elapsed_us);
// 오버런 경고
auto period_us = std::chrono::duration_cast<
std::chrono::microseconds>(tick_period_).count();
if (elapsed_us > period_us) {
overrun_count_++;
RCLCPP_WARN(this->get_logger(),
"Tick overrun: %ld us (period: %ld us)",
elapsed_us, period_us);
}
if (status != BT::NodeStatus::RUNNING) {
RCLCPP_INFO(this->get_logger(),
"Tree completed. Ticks: %lu, Avg: %.1f us, "
"Max: %ld us, Overruns: %lu",
tick_count_,
static_cast<double>(total_exec_time_us_) / tick_count_,
max_exec_time_us_, overrun_count_);
tick_timer_->cancel();
}
}
8. 시뮬레이션 환경에서의 고려 사항
Gazebo 등의 시뮬레이터와 연동하여 행동 트리를 실행하는 경우, use_sim_time 파라미터를 활성화하고 ROS Timer를 사용해야 한다. 이를 통해 시뮬레이션의 시간 흐름에 동기화된 Tick 실행이 보장된다.
bt_tick_node:
ros__parameters:
use_sim_time: true
tick_rate_hz: 10.0
시뮬레이션 시간 기반 타이머를 사용하면, 시뮬레이션을 실시간보다 빠르게 또는 느리게 실행하더라도 행동 트리가 시뮬레이션 내의 물리적 시간에 대해 일관된 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/
- Macenski, S., Foote, T., Gerkey, B., Lalancette, C., & Woodall, W. (2022). Robot Operating System 2: Design, architecture, and uses in the wild. Science Robotics, 7(66), eabm6074.