1296.84 액션 노드의 재시도 로직 구현

1. 개요

재시도 로직은 액션 노드의 실행이 실패했을 때, 동일한 작업을 일정 조건 하에서 반복 수행하여 일시적 오류로부터 복구하는 메커니즘이다. 로봇 시스템에서 통신 지연, 센서 데이터 일시 손실, 일시적 장애물 등에 의한 실패는 재시도를 통해 해결되는 경우가 빈번하므로, 적절한 재시도 전략은 시스템의 강건성(robustness)을 크게 향상시킨다.

행동 트리에서 재시도 로직은 두 가지 수준에서 구현할 수 있다. 첫째는 BehaviorTree.CPP가 제공하는 RetryNode 데코레이터를 활용하는 트리 수준의 재시도이고, 둘째는 액션 노드 내부에 재시도 로직을 직접 구현하는 노드 수준의 재시도이다.

2. 트리 수준 재시도: RetryNode 데코레이터

2.1 기본 사용법

RetryNode는 자식 노드가 FAILURE를 반환하면 지정된 횟수만큼 재실행한다.

<RetryNode num_attempts="3">
    <CaptureImage camera_topic="/camera/image_raw"
                  image="{image}" />
</RetryNode>

위 구조에서 이미지 촬영이 실패하면 최대 3회까지 재시도한다. 모든 시도가 실패하면 RetryNode 자체가 FAILURE를 반환한다.

2.2 RetryNode의 동작 원리

RetryNode의 실행 흐름은 다음과 같다.

  1. 자식 노드를 tick한다.
  2. 자식이 SUCCESS를 반환하면 SUCCESS를 반환한다.
  3. 자식이 RUNNING을 반환하면 RUNNING을 반환한다.
  4. 자식이 FAILURE를 반환하면 시도 횟수를 증가시킨다.
  5. 시도 횟수가 num_attempts 이하이면 자식을 halt한 후 다시 tick한다.
  6. 시도 횟수가 num_attempts를 초과하면 FAILURE를 반환한다.

2.3 재시도 간 대기 시간 삽입

연속적인 재시도 사이에 대기 시간을 두어 일시적 오류의 해소를 기다리려면, SequenceWait 노드를 결합한다.

<RetryNode num_attempts="3">
    <Sequence>
        <ConnectToServer server="{server_addr}" />
        <Wait duration="2.0" />
    </Sequence>
</RetryNode>

그러나 이 구조에서 Wait은 연결 성공 후에도 실행된다. 대기를 실패 시에만 적용하려면 다음과 같이 구성한다.

<RetryNode num_attempts="3">
    <Fallback>
        <ConnectToServer server="{server_addr}" />
        <Sequence>
            <Wait duration="2.0" />
            <AlwaysFailure />
        </Sequence>
    </Fallback>
</RetryNode>

이 구조에서 연결이 실패하면 2초 대기 후 AlwaysFailureFAILURE를 반환하고, FallbackFAILURE를 반환하여 RetryNode가 재시도를 수행한다.

3. 노드 수준 재시도

3.1 내부 재시도 구현

액션 노드 내부에서 재시도 로직을 구현하면, 재시도 조건과 전략을 세밀하게 제어할 수 있다.

class ResilientAction : public BT::StatefulActionNode
{
public:
    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<int>("max_retries", 3,
                "최대 재시도 횟수"),
            BT::InputPort<double>("retry_delay", 1.0,
                "재시도 간격 (초)"),
            // ... 기타 포트
        };
    }

    BT::NodeStatus onStart() override
    {
        retry_count_ = 0;
        getInput("max_retries", max_retries_);
        getInput("retry_delay", retry_delay_);
        return attemptExecution();
    }

    BT::NodeStatus onRunning() override
    {
        if (waiting_for_retry_)
        {
            auto elapsed =
                (node_->now() - retry_start_time_).seconds();
            if (elapsed >= retry_delay_)
            {
                waiting_for_retry_ = false;
                return attemptExecution();
            }
            return BT::NodeStatus::RUNNING;
        }

        // 작업 진행 확인
        if (task_failed_)
        {
            retry_count_++;
            if (retry_count_ >= max_retries_)
            {
                RCLCPP_ERROR(node_->get_logger(),
                    "최대 재시도 횟수 초과 (%d회)",
                    max_retries_);
                return BT::NodeStatus::FAILURE;
            }

            RCLCPP_WARN(node_->get_logger(),
                "재시도 %d/%d", retry_count_, max_retries_);
            waiting_for_retry_ = true;
            retry_start_time_ = node_->now();
            return BT::NodeStatus::RUNNING;
        }

        if (task_succeeded_)
        {
            return BT::NodeStatus::SUCCESS;
        }

        return BT::NodeStatus::RUNNING;
    }

private:
    BT::NodeStatus attemptExecution();
    int retry_count_{0};
    int max_retries_{3};
    double retry_delay_{1.0};
    bool waiting_for_retry_{false};
    rclcpp::Time retry_start_time_;
    std::atomic<bool> task_failed_{false};
    std::atomic<bool> task_succeeded_{false};
};

3.2 트리 수준과 노드 수준 비교

특성트리 수준 (RetryNode)노드 수준 (내부 로직)
구현 복잡도낮음 (XML 정의)높음 (C++ 코드)
유연성제한적높음
재시도 조건 제어전체 실패만부분 실패 구분 가능
상태 보존매 시도마다 초기화누적 상태 활용 가능
재사용성높음노드 종속

4. 재시도 전략

4.1 고정 간격 재시도

매 재시도 사이에 동일한 대기 시간을 적용한다.

T_{\text{wait}}(n) = T_{\text{fixed}} \quad \forall n

구현이 간단하며 대부분의 일시적 오류에 효과적이다.

4.2 지수 백오프 (Exponential Backoff)

재시도 횟수가 증가할수록 대기 시간을 기하급수적으로 증가시킨다. 이 전략은 서버 과부하 등의 상황에서 재시도에 의한 추가 부하를 방지한다.

T_{\text{wait}}(n) = T_{\text{base}} \times 2^{n-1}

여기서 n은 재시도 횟수, T_{\text{base}}는 기본 대기 시간이다.

double computeBackoffDelay(int retry_count,
                           double base_delay,
                           double max_delay)
{
    double delay = base_delay *
                   std::pow(2.0, retry_count - 1);
    return std::min(delay, max_delay);
}

4.3 지터 추가 (Jittered Backoff)

지수 백오프에 무작위 지터(jitter)를 추가하여, 다수의 클라이언트가 동시에 재시도하는 군집 효과(thundering herd problem)를 방지한다.

T_{\text{wait}}(n) = T_{\text{base}} \times 2^{n-1} \times U(0.5, 1.5)

여기서 U(a, b)[a, b] 범위의 균등 분포 난수이다.

4.4 조건부 재시도

오류의 종류에 따라 재시도 여부를 결정한다. 일시적 오류에 대해서만 재시도하고, 영구적 오류에 대해서는 즉시 실패를 반환한다.

BT::NodeStatus onRunning() override
{
    if (task_failed_)
    {
        if (isRetryableError(error_code_))
        {
            // 일시적 오류: 재시도
            retry_count_++;
            if (retry_count_ < max_retries_)
            {
                return scheduleRetry();
            }
        }
        // 영구적 오류 또는 재시도 소진: 즉시 실패
        return BT::NodeStatus::FAILURE;
    }
    // ...
}

bool isRetryableError(int error_code)
{
    // 통신 타임아웃, 일시적 서버 거부 등
    return (error_code == ERROR_TIMEOUT ||
            error_code == ERROR_SERVER_BUSY ||
            error_code == ERROR_TEMPORARY_FAILURE);
}

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

5.1 단순 재시도

<RetryNode num_attempts="5">
    <SendMessage topic="/gcs/report"
                 message="{status}" />
</RetryNode>

5.2 재시도와 대체 행동 결합

<Fallback>
    <RetryNode num_attempts="3">
        <NavigateToPose goal="{primary_goal}" />
    </RetryNode>
    <RetryNode num_attempts="2">
        <NavigateToPose goal="{secondary_goal}" />
    </RetryNode>
    <ReturnToHome />
</Fallback>

이 구조에서는 주 목표로의 이동을 3회 재시도하고, 실패하면 보조 목표로 2회 재시도하며, 모든 시도가 실패하면 귀환한다.

5.3 재시도 횟수 동적 결정

블랙보드를 통해 재시도 횟수를 동적으로 설정할 수 있다.

<SetBlackboard output_key="retries"
               value="5" />
<RetryNode num_attempts="{retries}">
    <CaptureImage image="{image}" />
</RetryNode>

6. 재시도 관련 주의 사항

  • 멱등성 보장: 재시도되는 동작은 멱등성(idempotency)을 보장해야 한다. 즉, 동일 동작을 여러 번 수행해도 결과가 동일해야 한다. 예를 들어, 데이터 전송 작업이 재시도되면 중복 전송이 발생할 수 있으므로, 수신 측에서 중복 감지 메커니즘을 갖추어야 한다.
  • 부작용 누적 방지: 재시도 시 이전 시도의 부작용(생성된 파일, 변경된 상태 등)이 누적되지 않도록 정리해야 한다.
  • 자원 소진 방지: 무제한 재시도는 배터리, 시간, 네트워크 대역폭 등의 자원을 소진할 수 있으므로, 최대 재시도 횟수와 총 소요 시간에 상한을 설정해야 한다.

7. 참고 문헌

  • 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.
  • Nygard, M. T., “Release It! Design and Deploy Production-Ready Software,” 2nd ed., Pragmatic Bookshelf, 2018.

버전: 2026-04-04