1293.91 이벤트 발생 시 즉각 Tick 실행
1. 즉각 Tick 실행의 정의
즉각 Tick 실행(immediate tick execution)이란, 외부 이벤트가 감지된 시점에서 다음 주기를 기다리지 않고 즉시 행동 트리의 Tick을 실행하는 메커니즘이다. 주기적 Tick 모델에서는 이벤트 발생과 다음 Tick 사이에 최대 1주기의 지연이 존재하지만, 즉각 실행에서는 이 지연을 제거하여 이벤트에 대한 트리의 반응 시간을 최소화한다(Colledanchise & Ogren, 2018).
2. 즉각 실행이 필요한 시나리오
2.1 긴급 정지 이벤트
장애물 감지, 충돌 임박, 안전 영역 이탈 등의 긴급 상황에서는 Tick 주기를 기다리는 지연조차 허용되지 않는다. 즉각 Tick 실행을 통해 트리가 즉시 안전 행동으로 전환해야 한다.
2.2 목표 변경 이벤트
사용자 또는 상위 시스템으로부터 새로운 목표가 수신되면, 현재 행동을 즉시 재평가하여 새로운 목표에 대한 계획을 수립해야 한다.
2.3 비동기 작업 완료 이벤트
ROS2 액션의 결과가 수신되면, 대기 중인 노드의 상태를 즉시 갱신하여 후속 행동을 개시해야 한다. 주기적 Tick에서는 결과 수신 후 다음 Tick까지 후속 행동의 개시가 지연된다.
3. 즉각 Tick 실행의 구현
3.1 인터럽트 방식
주기적 Tick의 대기(sleep)를 인터럽트하여 즉시 Tick을 실행하는 방식이다. 조건 변수(condition variable)를 활용한다.
class InterruptibleTickLoop {
public:
InterruptibleTickLoop(BT::Tree& tree, int tick_rate_hz)
: tree_(tree),
tick_period_(std::chrono::milliseconds(1000 / tick_rate_hz)) {}
void run() {
while (running_) {
tree_.tickOnce();
// 이벤트 발생 시 즉시 깨어남, 아니면 주기까지 대기
std::unique_lock<std::mutex> lock(mutex_);
cv_.wait_for(lock, tick_period_, [this]() {
return immediate_tick_requested_.load();
});
immediate_tick_requested_ = false;
}
}
void requestImmediateTick() {
immediate_tick_requested_ = true;
cv_.notify_one();
}
void stop() {
running_ = false;
cv_.notify_one();
}
private:
BT::Tree& tree_;
std::chrono::milliseconds tick_period_;
std::mutex mutex_;
std::condition_variable cv_;
std::atomic<bool> immediate_tick_requested_{false};
std::atomic<bool> running_{true};
};
이 구현에서 requestImmediateTick()이 호출되면 wait_for가 즉시 반환되어 다음 Tick이 실행된다. 이벤트가 없으면 정상 주기에 따라 Tick이 실행된다.
3.2 ROS2 콜백과의 통합
ROS2 토픽 콜백에서 즉각 Tick을 트리거하는 패턴이다.
class EventTriggeredBTNode : public rclcpp::Node {
public:
EventTriggeredBTNode() : Node("bt_executor") {
// 긴급 정지 토픽 구독
emergency_sub_ = create_subscription<std_msgs::msg::Bool>(
"emergency_stop", rclcpp::QoS(1).reliable(),
[this](std_msgs::msg::Bool::SharedPtr%20msg) {
tree_.rootBlackboard()->set("emergency_stop", msg->data);
tick_loop_->requestImmediateTick();
});
// 목표 수신 토픽 구독
goal_sub_ = create_subscription<geometry_msgs::msg::PoseStamped>(
"goal_pose", 10,
[this](geometry_msgs::msg::PoseStamped::SharedPtr%20msg) {
tree_.rootBlackboard()->set("goal_pose", *msg);
tick_loop_->requestImmediateTick();
});
}
private:
BT::Tree tree_;
std::unique_ptr<InterruptibleTickLoop> tick_loop_;
rclcpp::Subscription<std_msgs::msg::Bool>::SharedPtr emergency_sub_;
rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr goal_sub_;
};
3.3 액션 결과 수신 시 즉각 Tick
ROS2 액션의 결과 콜백에서 즉각 Tick을 트리거하여, 비동기 작업 완료 후 후속 행동을 즉시 개시한다.
void resultCallback(
const rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose>::WrappedResult& result) {
// 결과를 블랙보드에 저장
tree_.rootBlackboard()->set("navigate_result", result.code);
// 즉각 Tick 트리거
tick_loop_->requestImmediateTick();
}
4. 즉각 Tick과 Tick 순서 보장
즉각 Tick 요청이 현재 실행 중인 Tick과 동시에 발생할 수 있으므로, Tick의 원자적 실행을 보장해야 한다. 하나의 Tick이 완료되기 전에 다른 Tick이 시작되면 트리의 상태 일관성이 깨질 수 있다.
void executeTick() {
std::lock_guard<std::mutex> lock(tick_mutex_);
tree_.tickOnce();
}
이 보호에 의해, 즉각 Tick 요청이 현재 Tick 실행 중에 도착하면, 현재 Tick이 완료된 후에 새로운 Tick이 실행된다.
5. 즉각 Tick의 연쇄 방지
하나의 Tick 실행 결과가 블랙보드를 변경하고, 이 변경이 다시 이벤트로 감지되어 즉각 Tick을 트리거하는 연쇄(cascade) 현상이 발생할 수 있다. 이는 무한 루프를 유발하므로, 다음과 같은 방어 전략이 필요하다.
void triggerTick() {
// Tick 실행 중에는 재트리거 방지
if (tick_in_progress_) {
pending_retick_ = true;
return;
}
tick_in_progress_ = true;
tree_.tickOnce();
tick_in_progress_ = false;
// 보류된 Tick이 있으면 1회만 추가 실행
if (pending_retick_) {
pending_retick_ = false;
tick_in_progress_ = true;
tree_.tickOnce();
tick_in_progress_ = false;
}
}
6. 즉각 Tick과 스레드 안전성
이벤트 콜백은 ROS2 실행기의 콜백 스레드에서 호출되며, Tick 실행은 별도의 스레드에서 수행될 수 있다. 블랙보드에 대한 동시 접근을 보호하기 위해, 블랙보드 쓰기와 Tick 트리거 사이의 원자성을 보장해야 한다.
void onEventReceived(const EventData& data) {
{
std::lock_guard<std::mutex> lock(bb_mutex_);
tree_.rootBlackboard()->set("event_data", data);
}
tick_loop_->requestImmediateTick();
}
7. 즉각 Tick의 성능 영향
즉각 Tick 실행은 이벤트 응답성을 향상시키지만, 이벤트 빈도가 높은 경우 Tick 실행 빈도가 예상을 초과하여 CPU 부하가 증가할 수 있다. 최소 Tick 간격(minimum tick interval)을 설정하여 과도한 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/