시간 관련 조건 노드 설계 (Time-Related Condition Node Design)

시간 관련 조건 노드 설계 (Time-Related Condition Node Design)

1. 개요

시간 관련 조건 노드는 시간의 경과, 타임아웃, 실행 시간 한계 등 시간적 조건을 평가하여 행동 트리의 의사 결정을 지원하는 조건 노드 군이다. 로봇 시스템에서 시간 기반 조건은 작업 제한 시간 준수, 센서 데이터 유효 기간 확인, 주기적 동작 트리거, 타임아웃 기반 오류 감지 등에 광범위하게 활용된다.

2. 시간 관련 조건의 범주

2.1 주요 분류

범주설명활용 예시
타임아웃 확인특정 이벤트 이후 경과 시간이 한계를 초과하였는지 판정센서 데이터 유효성, 통신 타임아웃
경과 시간 비교두 시점 사이의 경과 시간을 기준값과 비교주기적 작업 트리거, 쿨다운
실행 시간 한계특정 행동의 실행 시간이 한계를 초과하였는지 판정작업 제한 시간, 무한 루프 방지
절대 시각 확인현재 시각이 특정 시간 범위 내에 있는지 판정야간 운용 금지, 근무 시간 제한

3. ROS2 시간 시스템

3.1 rclcpp::Clock과 시간 소스

ROS2에서 시간은 rclcpp::Clock 객체를 통해 관리되며, 다음 세 가지 시간 소스를 지원한다.

시간 소스rclcpp::ClockType특성
시스템 시간RCL_SYSTEM_TIMEUTC 기반, NTP 동기화 가능
단조 시간RCL_STEADY_TIME단조 증가, 경과 시간 측정에 적합
ROS 시간RCL_ROS_TIME시뮬레이션 시간 호환

경과 시간 측정에는 단조 시간(RCL_STEADY_TIME)을 사용하는 것이 적절하며, 이는 NTP 동기화에 의한 시계 점프의 영향을 받지 않는다. 다만, 시뮬레이션 환경과의 호환성이 필요한 경우 ROS 시간(RCL_ROS_TIME)을 사용한다.

3.2 rclcpp::Time과 rclcpp::Duration

rclcpp::Time은 시점(time point)을, rclcpp::Duration은 시간 간격(duration)을 표현한다. 두 Time 객체의 차이는 Duration을 반환하며, Durationseconds() 메서드로 초 단위 값을 얻는다.

4. 공통 설계 패턴

4.1 내부 타이머 패턴

시간 관련 조건 노드는 내부적으로 시간 상태를 유지하여야 하므로, 조건 노드의 순수 함수 원칙과 부분적으로 충돌한다. 그러나 시간은 외부에서 제어할 수 없는 자연적 상태이며, 조건 노드 내부의 시간 추적은 외부 시스템에 부작용을 미치지 않으므로 허용된다.

class TimeConditionBase : public BT::ConditionNode
{
public:
    TimeConditionBase(const std::string& name,
                      const BT::NodeConfiguration& config,
                      rclcpp::Node::SharedPtr node)
        : BT::ConditionNode(name, config),
          node_(node),
          start_time_(node->get_clock()->now()),
          started_(false)
    {}

protected:
    rclcpp::Node::SharedPtr node_;
    rclcpp::Time start_time_;
    bool started_;

    rclcpp::Time now() const
    {
        return node_->get_clock()->now();
    }

    double elapsedSeconds() const
    {
        return (now() - start_time_).seconds();
    }

    void resetTimer()
    {
        start_time_ = now();
        started_ = true;
    }
};

4.2 타임아웃 조건 노드의 기본 구조

class HasTimeoutElapsed : public TimeConditionBase
{
public:
    HasTimeoutElapsed(const std::string& name,
                      const BT::NodeConfiguration& config,
                      rclcpp::Node::SharedPtr node)
        : TimeConditionBase(name, config, node)
    {}

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<double>("timeout_sec", 10.0,
                "타임아웃 시간 (초)")
        };
    }

    BT::NodeStatus tick() override
    {
        if (!started_)
        {
            resetTimer();
        }

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

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

5. XML 행동 트리에서의 활용 패턴

5.1 타임아웃 기반 행동 전환

<BehaviorTree ID="TimeoutBasedSwitch">
    <Fallback>
        <Sequence>
            <Inverter>
                <Condition ID="HasTimeoutElapsed"
                           timeout_sec="30.0"/>
            </Inverter>
            <Action ID="WaitForEvent"/>
        </Sequence>
        <Action ID="TimeoutRecovery"/>
    </Fallback>
</BehaviorTree>

30초 동안 이벤트를 대기하고, 타임아웃이 경과하면 복구 행동을 실행한다.

5.2 주기적 작업 트리거

<BehaviorTree ID="PeriodicTask">
    <ReactiveSequence>
        <Condition ID="HasIntervalElapsed"
                   interval_sec="5.0"/>
        <Action ID="PerformPeriodicCheck"/>
    </ReactiveSequence>
</BehaviorTree>

6. 설계 시 고려 사항

6.1 시뮬레이션 시간 호환성

시뮬레이션 환경에서는 use_sim_time 파라미터에 따라 시간의 진행 속도가 실제와 다를 수 있다. rclcpp::Node::get_clock()이 반환하는 시계는 이 설정을 자동으로 반영하므로, 시뮬레이션과 실제 환경 모두에서 올바르게 동작한다.

6.2 타이머 리셋 시점

타이머를 언제 리셋하는지에 따라 조건 노드의 의미론이 달라진다. 노드 생성 시 리셋, 첫 번째 tick 시 리셋, 명시적 리셋 등의 정책이 있으며, 사용 목적에 맞는 정책을 선택하여야 한다.

6.3 시간 조건과 데코레이터의 관계

BehaviorTree.CPP는 TimeoutNode, Delay 등의 시간 관련 데코레이터를 제공한다. 데코레이터는 자식 노드의 실행 시간을 제한하는 반면, 조건 노드는 시간적 상태를 평가하여 분기를 결정한다. 두 메커니즘의 용도를 구분하여 적절한 것을 선택하여야 한다.

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초안 작성