1296.83 액션 노드의 타임아웃 처리

1. 개요

타임아웃 처리는 액션 노드가 지정된 시간 내에 작업을 완료하지 못하는 경우, 해당 작업을 중단하고 FAILURE를 반환하는 메커니즘이다. 타임아웃은 로봇 시스템의 교착 상태(deadlock) 방지, 비정상 동작 감지, 자원 효율적 사용을 보장하는 핵심 안전 장치이다.

비동기 액션 노드(StatefulActionNode)에서 RUNNING 상태가 무한히 지속되면, 행동 트리의 상위 제어 노드가 다른 경로를 탐색할 기회를 얻지 못한다. 타임아웃은 이러한 무한 대기를 방지하여 행동 트리의 반응성(reactivity)을 유지한다.

2. 타임아웃 구현 방식

2.1 노드 내부 타임아웃

가장 직접적인 방식은 액션 노드 내부에서 시작 시각을 기록하고, onRunning() 콜백에서 경과 시간을 검사하는 것이다.

BT::NodeStatus onStart() override
{
    start_time_ = node_->now();
    // 작업 시작 ...
    return BT::NodeStatus::RUNNING;
}

BT::NodeStatus onRunning() override
{
    double timeout;
    getInput("timeout", timeout);

    auto elapsed = (node_->now() - start_time_).seconds();
    if (elapsed > timeout)
    {
        RCLCPP_WARN(node_->get_logger(),
            "타임아웃 발생: %.1f초 경과 (제한: %.1f초)",
            elapsed, timeout);
        cleanupOnTimeout();
        return BT::NodeStatus::FAILURE;
    }

    // 정상 진행 확인 ...
    return BT::NodeStatus::RUNNING;
}

이 방식은 타임아웃 값을 입력 포트로 파라미터화할 수 있어, XML 행동 트리 정의에서 임무별로 다른 타임아웃을 지정할 수 있다는 장점이 있다.

2.2 데코레이터 기반 타임아웃

BehaviorTree.CPP는 Timeout 데코레이터 노드를 제공한다. 이 데코레이터는 자식 노드의 실행 시간이 지정된 제한을 초과하면 자식 노드를 중단(halt)하고 FAILURE를 반환한다.

<Timeout msec="30000">
    <NavigateToPose goal="{target_pose}" />
</Timeout>

데코레이터 방식은 액션 노드 내부에 타임아웃 로직을 구현하지 않아도 되므로, 기존 노드를 수정하지 않고 타임아웃을 추가할 수 있다. 그러나 타임아웃 발생 시 노드 내부의 자원 정리(cleanup)는 onHalted() 콜백에 의존하므로, onHalted()의 구현이 올바르게 되어 있어야 한다.

2.3 두 방식의 비교

특성내부 타임아웃데코레이터 타임아웃
구현 위치노드 내부 콜백XML 행동 트리 정의
자원 정리직접 수행 가능onHalted() 의존
세밀한 제어부분 타임아웃 가능전체 노드에 적용
재사용성노드에 종속임의 노드에 적용 가능
오류 정보상세 기록 가능제한적

실무에서는 두 방식을 병용하는 것이 효과적이다. 노드 내부에 기본 타임아웃을 구현하되, 필요에 따라 데코레이터로 추가 제한을 적용한다.

3. 타임아웃 값 결정

3.1 동작 특성에 기반한 결정

타임아웃 값은 해당 동작의 예상 소요 시간에 안전 여유(safety margin)를 추가하여 결정한다.

T_{\text{timeout}} = T_{\text{expected}} + T_{\text{margin}}

안전 여유는 일반적으로 예상 소요 시간의 50~100%를 추가하거나, 고정 시간(5~10초)을 추가하는 방식으로 설정한다.

동작 유형예상 소요 시간권장 타임아웃
이륙 (10m)5~10초20~30초
경유점 비행 (1km)60~120초180~300초
착륙10~30초45~60초
이미지 촬영0.1~1초5초
물체 탐지0.5~5초10초

3.2 동적 타임아웃 계산

비행 거리에 따라 타임아웃을 동적으로 계산하는 방식이다. 예를 들어, 경유점 비행의 타임아웃은 거리와 비행 속도로부터 산출할 수 있다.

T_{\text{timeout}} = \frac{d}{v_{\text{min}}} \times k_{\text{safety}}

여기서 d는 목표까지의 거리, v_{\text{min}}은 최소 예상 비행 속도, k_{\text{safety}}는 안전 계수(일반적으로 1.5~2.0)이다.

BT::NodeStatus onStart() override
{
    double distance = computeDistance(
        current_position_, target_position_);
    double speed;
    getInput("speed", speed);

    // 동적 타임아웃 계산
    double dynamic_timeout =
        (distance / (speed * 0.5)) * 1.5;

    // 최소/최대 타임아웃 적용
    dynamic_timeout = std::clamp(
        dynamic_timeout, 10.0, 600.0);

    effective_timeout_ = dynamic_timeout;
    // ...
}

4. 타임아웃 발생 시 자원 정리

4.1 ROS2 액션 취소

진행 중인 ROS2 액션을 취소하여 서버 측 자원을 해제한다.

void cleanupOnTimeout()
{
    if (goal_handle_)
    {
        RCLCPP_INFO(node_->get_logger(),
            "타임아웃에 의한 액션 취소 요청");
        action_client_->async_cancel_goal(goal_handle_);
        goal_handle_.reset();
    }

    // 구독 해제
    subscription_.reset();

    // 상태 초기화
    goal_completed_ = false;
    goal_succeeded_ = false;
}

4.2 하드웨어 안전 상태 전환

타임아웃이 물리적 동작(비행, 이동 등)에서 발생한 경우, 로봇이 안전한 상태로 전환되도록 해야 한다. 드론의 경우 타임아웃 발생 시 위치 유지(position hold) 모드로 전환하는 것이 일반적이다.

5. 다단계 타임아웃

복잡한 동작에서는 전체 동작의 타임아웃과 하위 단계의 타임아웃을 구분하여 적용할 수 있다.

BT::NodeStatus onRunning() override
{
    auto elapsed = (node_->now() - start_time_).seconds();

    // 1단계 타임아웃: 골 수락 대기
    if (!goal_accepted_ && elapsed > goal_accept_timeout_)
    {
        RCLCPP_WARN(node_->get_logger(),
            "골 수락 타임아웃");
        return BT::NodeStatus::FAILURE;
    }

    // 2단계 타임아웃: 전체 동작 완료 대기
    if (elapsed > total_timeout_)
    {
        RCLCPP_WARN(node_->get_logger(),
            "전체 타임아웃");
        cleanupOnTimeout();
        return BT::NodeStatus::FAILURE;
    }

    // ...
}

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

6.1 내부 타임아웃 파라미터화

<NavigateToPose goal="{target_pose}"
                timeout="60.0" />

6.2 데코레이터 타임아웃 적용

<Timeout msec="30000">
    <Sequence>
        <CaptureImage image="{image}" />
        <DetectObject image="{image}"
                      detections="{objects}" />
    </Sequence>
</Timeout>

6.3 타임아웃과 재시도 결합

<RetryNode num_attempts="3">
    <Timeout msec="15000">
        <ConnectToServer server="{addr}" />
    </Timeout>
</RetryNode>

이 구조에서는 서버 연결에 15초의 타임아웃을 적용하고, 타임아웃 실패 시 최대 3회 재시도한다. 전체 최대 소요 시간은 45초가 된다.

6.4 타임아웃 실패 시 대체 행동

<Fallback>
    <Timeout msec="60000">
        <NavigateToPose goal="{target}" />
    </Timeout>
    <Sequence>
        <LogMessage level="WARN"
                    message="내비게이션 타임아웃, 귀환" />
        <ReturnToHome />
    </Sequence>
</Fallback>

7. 타임아웃 관련 주의 사항

  • 너무 짧은 타임아웃: 정상적인 동작이 완료되기 전에 타임아웃이 발생하여 불필요한 실패가 빈번해진다.
  • 너무 긴 타임아웃: 실제 오류 상황에서 시스템이 오랜 시간 대기하여 반응성이 저하된다.
  • 시계 동기화: ROS2의 시뮬레이션 시간(simulation time)을 사용하는 환경에서는 node_->now()가 시뮬레이션 시간을 반환하므로, 실시간 타임아웃과 시뮬레이션 타임아웃이 일치하지 않을 수 있다.
  • 네트워크 지연 고려: 분산 ROS2 환경에서는 통신 지연이 타임아웃 판정에 영향을 미칠 수 있으므로, 네트워크 왕복 시간(RTT)을 고려하여 여유를 설정해야 한다.

8. 참고 문헌

  • Colledanchise, M. and Ögren, P., “Behavior Trees in Robotics and AI: An Introduction,” CRC Press, 2018.
  • Faconti, D. and Contributors, “BehaviorTree.CPP: A C++ library to build Behavior Trees,” GitHub Repository, https://github.com/BehaviorTree/BehaviorTree.CPP.
  • Macenski, S. et al., “The Marathon 2: A Navigation System,” arXiv preprint arXiv:2003.00368, 2020.

버전: 2026-04-04