경과 시간 비교 조건 노드 (Elapsed Time Comparison Condition Node)
1. 개요
경과 시간 비교 조건 노드는 특정 기준 시점으로부터 경과한 시간을 기준값과 비교하여 조건을 판정하는 조건 노드이다. 타임아웃 확인 조건 노드가 단순히 시간 초과 여부만을 판정하는 것과 달리, 경과 시간 비교 조건 노드는 다양한 비교 연산(미만, 이상, 범위 내 등)을 지원하여 유연한 시간 기반 조건 평가를 가능하게 한다.
2. 경과 시간의 산출
경과 시간 \Delta t는 기준 시점 t_0으로부터 현재 시점 t까지의 ���이이다.
\Delta t = t - t_0
기준 시점 t_0는 다음 중 하나로 설정된다.
| 기준 시점 | 설명 |
|---|---|
| 노드 최초 tick 시점 | 조건 노드가 처음 평가된 시점 |
| 블랙보드에 기록된 시점 | 다른 노드가 기록한 이벤트 발생 시점 |
| 행동 트리 시작 시점 | 행동 트리의 실행이 개시된 시점 |
| 마지막 리셋 시점 | 외부에서 타이머를 리셋한 시점 |
구현
다양한 비교 연산 지원
class IsElapsedTimeCompare : public BT::ConditionNode
{
public:
IsElapsedTimeCompare(const std::string& name,
const BT::NodeConfiguration& config,
rclcpp::Node::SharedPtr node)
: BT::ConditionNode(name, config),
node_(node),
initialized_(false)
{}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<double>("reference_sec", "기준 시간 (초)"),
BT::InputPort<std::string>("operator", "GT",
"비교 연산자 (GT, LT, GTE, LTE, EQ)")
};
}
BT::NodeStatus tick() override
{
if (!initialized_)
{
start_time_ = node_->get_clock()->now();
initialized_ = true;
}
double reference;
std::string op;
getInput("reference_sec", reference);
getInput("operator", op);
double elapsed =
(node_->get_clock()->now() - start_time_).seconds();
bool result = false;
if (op == "GT") result = elapsed > reference;
else if (op == "LT") result = elapsed < reference;
else if (op == "GTE") result = elapsed >= reference;
else if (op == "LTE") result = elapsed <= reference;
else if (op == "EQ") result = std::abs(elapsed - reference) < 0.1;
return result ? BT::NodeStatus::SUCCESS
: BT::NodeStatus::FAILURE;
}
private:
rclcpp::Node::SharedPtr node_;
rclcpp::Time start_time_;
bool initialized_;
};
블랙보드 기준 시점 기반
다른 노드가 블랙보드에 기록한 시점을 기준으로 경과 시간을 평가한다.
class IsElapsedSinceEvent : public BT::ConditionNode
{
public:
IsElapsedSinceEvent(const std::string& name,
const BT::NodeConfiguration& config,
rclcpp::Node::SharedPtr node)
: BT::ConditionNode(name, config), node_(node)
{}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<double>("event_timestamp",
"이벤트 발생 시각 (에포크 초)"),
BT::InputPort<double>("min_elapsed_sec",
"최소 경과 시간 (초)"),
BT::InputPort<double>("max_elapsed_sec",
"최대 경과 시간 (초)")
};
}
BT::NodeStatus tick() override
{
double event_time, min_elapsed, max_elapsed;
getInput("event_timestamp", event_time);
getInput("min_elapsed_sec", min_elapsed);
getInput("max_elapsed_sec", max_elapsed);
double now_sec = node_->get_clock()->now().seconds();
double elapsed = now_sec - event_time;
if (elapsed >= min_elapsed && elapsed <= max_elapsed)
{
return BT::NodeStatus::SUCCESS;
}
return BT::NodeStatus::FAILURE;
}
private:
rclcpp::Node::SharedPtr node_;
};
쿨다운(Cooldown) 패턴
특정 행동이 실행된 후 일정 시간이 경과하여야만 다시 실행을 허용하는 패턴이다.
class IsCooldownElapsed : public BT::ConditionNode
{
public:
IsCooldownElapsed(const std::string& name,
const BT::NodeConfiguration& config,
rclcpp::Node::SharedPtr node)
: BT::ConditionNode(name, config),
node_(node),
has_last_execution_(false)
{}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<double>("cooldown_sec", 5.0,
"쿨다운 시간 (초)"),
BT::InputPort<double>("last_execution_time", 0.0,
"마지막 실행 시각 (블랙보드에서)")
};
}
BT::NodeStatus tick() override
{
double cooldown, last_exec;
getInput("cooldown_sec", cooldown);
if (!getInput("last_execution_time", last_exec) ||
last_exec <= 0.0)
{
return BT::NodeStatus::SUCCESS;
}
double now_sec = node_->get_clock()->now().seconds();
double elapsed = now_sec - last_exec;
if (elapsed >= cooldown)
{
return BT::NodeStatus::SUCCESS;
}
return BT::NodeStatus::FAILURE;
}
private:
rclcpp::Node::SharedPtr node_;
bool has_last_execution_;
};
XML 행동 트리에서의 활용
주기적 상태 점검
<BehaviorTree ID="PeriodicHealthCheck">
<Sequence>
<Condition ID="IsElapsedTimeCompare"
reference_sec="60.0"
operator="GTE"/>
<Action ID="PerformDiagnostics"/>
<Action ID="ResetTimer"/>
</Sequence>
</BehaviorTree>
쿨다운 기반 복구 제한
<BehaviorTree ID="CooldownRecovery">
<Sequence>
<Condition ID="IsCooldownElapsed"
cooldown_sec="10.0"
last_execution_time="{last_recovery_time}"/>
<Action ID="PerformRecovery"
output_time="{last_recovery_time}"/>
</Sequence>
</BehaviorTree>
복구 행동은 마지막 실행으로부��� 10초 이상 경과하여야만 다시 실행된다. 이를 통해 복구 행동의 과도한 반복을 방지한다.
시간 창(Time Window) 내 조건 평가
<BehaviorTree ID="TimeWindowedAction">
<Sequence>
<Condition ID="IsElapsedSinceEvent"
event_timestamp="{mission_start_time}"
min_elapsed_sec="10.0"
max_elapsed_sec="300.0"/>
<Action ID="PerformTimedAction"/>
</Sequence>
</BehaviorTree>
임무 시작 후 10초~300초 사이에만 특정 행���을 수행한다.
설계 시 고려 사항
부동소수점 시간 비교의 정밀도
rclcpp::Time::seconds()는 double 타입을 반환하므로, 큰 값에서 정밀도가 저하될 수 있다. 에포크(epoch) 이후의 초 단위 값은 10^9 수준이므로, 나노초 수준의 정밀도는 보장되지 않는다. 그러나 행동 트리의 tick 주기(밀리초 ~ 초 단위)에서는 이 정밀도 제한이 문제가 되지 않는다.
다중 조건 노드 간 타이머 공유
복수의 시간 관련 조건 노드가 동일��� 기준 시���을 참조하여야 하는 경우, 블랙보드에 기준 시점을 기록하고 각 조건 노드가 이를 읽어오는 방식을 사용한다. 각 노드가 독립적으로 타이머를 관리하면 초기화 시점의 차이로 인해 불일치가 발생할 수 있다.
참고 문헌
- Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
- BehaviorTree.CPP 공식 문서. https://www.behaviortree.dev/
- ROS2 공식 문서. https://docs.ros.org/en/humble/
| 버전 | 날짜 | 변경 사항 |
|---|---|---|
| v0.1 | 2026-04-04 | 초안 작성 |