실행 시간 한계 확인 조건 노드 (Execution Time Limit Check Condition Node)
1. 개요
실행 시간 한계 확인 조건 노드는 특정 행동이나 임무의 실행 시간이 사전에 정의된 한계를 초과하지 않았는지를 판정하는 조건 노드이다. 장시간 실행되는 행동은 시스템 자원 고갈, 배터리 소진, 임무 기한 초과 등의 문제를 초래할 수 있으며, 무한 루프나 교착 상태에 빠진 행동을 감지하는 안전 장치로도 기능한다.
2. 실행 시간 한계의 적용 대상
| 적용 대상 | 설명 | 한계 예시 |
|---|---|---|
| 전체 임무 | 임무 전체의 실행 시간 제한 | 30분, 1시간 |
| 단일 행동 | 개별 액션 노드의 실행 시간 제한 | 30초, 60초 |
| 복구 시도 | 복구 행동의 총 실행 시간 제한 | 60초 |
| 탐색 작업 | 특정 영역 탐색의 시간 제한 | 5분 |
3. 구현
3.1 임무 수준 실행 시간 한계
임무 시작 시점으로부터의 경과 시간이 한계를 초과하지 않았는지를 판정한다.
class IsWithinTimeLimit : public BT::ConditionNode
{
public:
IsWithinTimeLimit(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>("time_limit_sec", 600.0,
"실행 시간 한계 (초)")
};
}
BT::NodeStatus tick() override
{
if (!initialized_)
{
start_time_ = node_->get_clock()->now();
initialized_ = true;
}
double limit;
getInput("time_limit_sec", limit);
double elapsed =
(node_->get_clock()->now() - start_time_).seconds();
if (elapsed <= limit)
{
return BT::NodeStatus::SUCCESS;
}
return BT::NodeStatus::FAILURE;
}
private:
rclcpp::Node::SharedPtr node_;
rclcpp::Time start_time_;
bool initialized_;
};
3.2 블랙보드 시작 시각 기반 한계
다른 노드가 블랙보드에 기록한 시작 시각을 기준으로 실행 시간 한계를 평가한다.
class IsActionWithinTimeLimit : public BT::ConditionNode
{
public:
IsActionWithinTimeLimit(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>("start_time",
"행동 시작 시각 (에포크 초)"),
BT::InputPort<double>("time_limit_sec", 60.0,
"실행 시간 한계 (초)")
};
}
BT::NodeStatus tick() override
{
double start_time, limit;
if (!getInput("start_time", start_time))
{
return BT::NodeStatus::FAILURE;
}
getInput("time_limit_sec", limit);
double now_sec = node_->get_clock()->now().seconds();
double elapsed = now_sec - start_time;
if (elapsed >= 0.0 && elapsed <= limit)
{
return BT::NodeStatus::SUCCESS;
}
return BT::NodeStatus::FAILURE;
}
private:
rclcpp::Node::SharedPtr node_;
};
3.3 잔여 시간 출력
실행 시간 한계까지의 잔여 시간을 블랙보드에 출력하여 다른 노드가 참조할 수 있도록 한다.
class CheckTimeLimitWithRemaining : public BT::ConditionNode
{
public:
CheckTimeLimitWithRemaining(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>("time_limit_sec", 300.0,
"실행 시간 한계 (초)"),
BT::OutputPort<double>("remaining_sec",
"잔여 시간 (초)")
};
}
BT::NodeStatus tick() override
{
if (!initialized_)
{
start_time_ = node_->get_clock()->now();
initialized_ = true;
}
double limit;
getInput("time_limit_sec", limit);
double elapsed =
(node_->get_clock()->now() - start_time_).seconds();
double remaining = limit - elapsed;
setOutput("remaining_sec", remaining);
if (remaining > 0.0)
{
return BT::NodeStatus::SUCCESS;
}
return BT::NodeStatus::FAILURE;
}
private:
rclcpp::Node::SharedPtr node_;
rclcpp::Time start_time_;
bool initialized_;
};
이 구현은 출력 포트를 사용하므로 엄밀한 조건 노드의 부작용 금지 원칙과 충돌할 수 있다. 블랙보드에 잔여 시간을 기록하는 것은 행동 트리 내부의 데이터 공유이며 외부 시스템에 영향을 미치지 않으나, 설계 순수성이 중요한 경우 별도의 액션 노드로 분리하는 것이 바람직하다.
4. XML 행동 트리에서의 활용
4.1 임무 시간 한계 감시
<BehaviorTree ID="TimeLimitedMission">
<ReactiveSequence>
<Condition ID="IsWithinTimeLimit"
time_limit_sec="1800.0"/>
<SubTree ID="MissionExecution"/>
</ReactiveSequence>
</BehaviorTree>
30분(1800초) 한계 내에서 임무를 수행하며, 한계를 초과하면 임무가 중단된다.
4.2 잔여 시간 기반 행동 적응
<BehaviorTree ID="AdaptiveTimeMission">
<ReactiveSequence>
<Condition ID="CheckTimeLimitWithRemaining"
time_limit_sec="600.0"
remaining_sec="{time_remaining}"/>
<Fallback>
<Sequence>
<Condition ID="IsElapsedTimeCompare"
reference_sec="60.0"
operator="GT"/>
<Action ID="ReturnToBase"/>
</Sequence>
<Action ID="ContinueMission"/>
</Fallback>
</ReactiveSequence>
</BehaviorTree>
잔여 시간이 60초 이하가 되면 기지 귀환을 시작한다.
5. 설계 시 고려 사항
5.1 TimeoutNode 데코레이터와의 차이
TimeoutNode 데코레이터는 자식 노드가 RUNNING을 반환하는 시간을 제한하며, 타임아웃 시 자식을 중단하고 FAILURE를 반환한다. 반면, 실행 시간 한계 확인 조건 노드는 조건을 평가할 뿐이며, 시간 초과 시의 행동은 상위 제어 구조에서 결정한다. 두 메커니즘은 상호 보완적으로 활용할 수 있다.
5.2 시간 한계의 동적 조정
배터리 잔량, 기상 조건, 작업 복잡도 등에 따라 시간 한계를 동적으로 조정하여야 하는 경우가 있다. 블랙보드를 통해 시간 한계를 동적으로 전달하면 이러한 유연성을 구현할 수 있다.
5.3 누적 실행 시간 추적
단일 행동의 연속 실행 시간이 아닌, 여러 번에 걸쳐 실행된 총 누적 시간을 추적하여야 하는 경우가 있다. 이 경우 블랙보드에 누적 시간을 기록하고, 조건 노드에서 이를 참조하여 한계를 평가하는 방식이 적절하다.
6. 참고 문헌
- Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
- BehaviorTree.CPP 공식 문서. https://www.behaviortree.dev/
| 버전 | 날짜 | 변경 사항 |
|---|---|---|
| v0.1 | 2026-04-04 | 초안 작성 |