타임아웃 확인 조건 노드 (Timeout Check Condition Node)

타임아웃 확인 조건 노드 (Timeout Check Condition Node)

1. 개요

타임아웃 확인 조건 노드는 지정된 시간이 경과하였는지를 판정하는 조건 노드이다. 특정 이벤트의 발생을 대기하거나, 행동의 실행 시간을 제한하거나, 센서 데이터의 유효 기간을 확인하는 등의 목적으로 활용된다. 타임아웃이 경과하면 SUCCESS를 반환하고, 아직 경과하지 않았으면 FAILURE를 반환한다.

2. 타임아웃의 의미론

타임아웃 조건의 반환 의미는 “타임아웃이 경과하였는가?“라는 질문에 대한 답이다.

상태의미반환
경과 시간 < t_{\text{timeout}}타임아웃 미경과FAILURE
경과 시간 \geq t_{\text{timeout}}타임아웃 경과SUCCESS

이 의미론은 행동 트리에서의 사용 맥락에 따라 Inverter 데코레이터를 적용하여 “아직 시간이 남았는가?“로 변환할 수 있다.

3. 구현

3.1 노드 생성 시점 기준 타임아웃

class HasTimeoutElapsed : public BT::ConditionNode
{
public:
    HasTimeoutElapsed(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>("timeout_sec", 10.0,
                "타임아웃 시간 (초)")
        };
    }

    BT::NodeStatus tick() override
    {
        if (!initialized_)
        {
            start_time_ = node_->get_clock()->now();
            initialized_ = true;
        }

        double timeout;
        getInput("timeout_sec", timeout);

        double elapsed =
            (node_->get_clock()->now() - start_time_).seconds();

        if (elapsed >= timeout)
        {
            return BT::NodeStatus::SUCCESS;
        }
        return BT::NodeStatus::FAILURE;
    }

private:
    rclcpp::Node::SharedPtr node_;
    rclcpp::Time start_time_;
    bool initialized_;
};

3.2 리셋 가능 타임아웃

블랙보드를 통해 외부에서 타이머를 리셋할 수 있는 타임아웃 조건 노드이다.

class ResettableTimeout : public BT::ConditionNode
{
public:
    ResettableTimeout(const std::string& name,
                      const BT::NodeConfiguration& config,
                      rclcpp::Node::SharedPtr node)
        : BT::ConditionNode(name, config),
          node_(node),
          initialized_(false),
          last_reset_count_(0)
    {}

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<double>("timeout_sec", 10.0,
                "타임아웃 시간 (초)"),
            BT::InputPort<int>("reset_counter", 0,
                "리셋 카운터 (값 변경 시 타이머 리셋)")
        };
    }

    BT::NodeStatus tick() override
    {
        int reset_count;
        getInput("reset_counter", reset_count);

        if (!initialized_ || reset_count != last_reset_count_)
        {
            start_time_ = node_->get_clock()->now();
            initialized_ = true;
            last_reset_count_ = reset_count;
        }

        double timeout;
        getInput("timeout_sec", timeout);

        double elapsed =
            (node_->get_clock()->now() - start_time_).seconds();

        if (elapsed >= timeout)
        {
            return BT::NodeStatus::SUCCESS;
        }
        return BT::NodeStatus::FAILURE;
    }

private:
    rclcpp::Node::SharedPtr node_;
    rclcpp::Time start_time_;
    bool initialized_;
    int last_reset_count_;
};

reset_counter 입력 포트의 값이 변경되면 타이머가 리셋된다. 다른 노드가 블랙보드에 카운터 값을 기록하여 타이머를 제어할 수 있다.

4. XML 행동 트리에서의 활용

4.1 이벤트 대기 타임아웃

<BehaviorTree ID="EventWaitWithTimeout">
    <Fallback>
        <Sequence>
            <Inverter>
                <Condition ID="HasTimeoutElapsed"
                           timeout_sec="30.0"/>
            </Inverter>
            <Condition ID="IsEventDetected"
                       topic_name="/event"/>
            <Action ID="HandleEvent"/>
        </Sequence>
        <Action ID="TimeoutFallback"/>
    </Fallback>
</BehaviorTree>

30초 이내에 이벤트가 감지되면 이벤트를 처리하고, 타임아웃이 경과하면 대체 행동을 실행한다.

4.2 반복 작업의 시간 제한

<BehaviorTree ID="TimeLimitedRetry">
    <ReactiveSequence>
        <Inverter>
            <Condition ID="HasTimeoutElapsed"
                       timeout_sec="120.0"/>
        </Inverter>
        <RetryNode num_attempts="10">
            <Action ID="AttemptTask"/>
        </RetryNode>
    </ReactiveSequence>
</BehaviorTree>

120초 이내에 최대 10회 작업을 재시도하며, 타임아웃이 경과하면 재시도를 중단한다.

5. BehaviorTree.CPP의 TimeoutNode 데코레이터와의 비교

특성타임아웃 조건 노드TimeoutNode 데코레이터
노드 유형조건 노드 (리프)데코레이터 (부모)
제어 대상시간 조건만 평가자식 노드의 실행 시간 제한
반환 상태SUCCESS/FAILURE자식 반환 또는 FAILURE(타임아웃 시)
사용 목적시간 기반 분기 결정행동 실행 시간 강제 제한
RUNNING 반환불가자식이 RUNNING이면 RUNNING

시간 조건을 기반으로 행동 트리의 흐름을 제어하려면 조건 노드를, 특정 행동의 실행 시간을 강제로 제한하려면 TimeoutNode 데코레이터를 사용하는 것이 적절하다.

6. 설계 시 고려 사항

6.1 타이머 초기화 시점

타이머가 노드의 첫 번째 tick에서 초기화되는지, 노드 생성 시 초기화되는지에 따라 동작이 달라진다. 행동 트리가 생성된 후 실제 실행까지 지연이 있는 경우, 첫 번째 tick 시점에서 초기화하는 것이 적절하다.

6.2 시뮬레이션 시간과의 호환

rclcpp::Node::get_clock()을 통해 시간을 획득하면, use_sim_time 설정에 따라 시뮬레이션 시간이 자동으로 적용된다. 시뮬레이션에서 시간을 일시 정지하면 타이머도 정지하므로, 시뮬레이션 환경에서도 일관된 동작이 보장된다.

6.3 타이머 정밀도

행동 트리의 tick 주기가 타임아웃 정밀도를 결정한다. tick 주기가 100ms인 경우, 타임아웃 판정의 정밀도는 ±100ms이다. 높은 시간 정밀도가 필요한 경우 tick 주기를 줄이거나, 별도의 ROS2 타이머를 활용하여야 한다.

7. 참고 문헌

  • 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.12026-04-04초안 작성