1296.85 액션 노드의 실패 원인 보고

1. 개요

액션 노드의 실패 원인 보고는 노드가 FAILURE를 반환할 때 실패의 원인, 맥락, 심각도를 체계적으로 기록하고 전달하는 메커니즘이다. 행동 트리에서 FAILURE 반환값만으로는 실패의 구체적 원인을 파악할 수 없으므로, 보조적인 실패 정보 전달 채널이 필요하다.

실패 원인 보고는 실시간 오류 진단, 사후 분석, 자동 복구 결정 등의 목적으로 활용된다. 상위 노드가 실패 원인을 참조하여 적절한 복구 전략을 선택할 수 있도록 하는 것이 설계의 핵심 목표이다.

2. 실패 정보 전달 방식

2.1 블랙보드 출력 포트를 통한 전달

가장 직접적인 방식은 블랙보드의 출력 포트를 통해 실패 정보를 전달하는 것이다.

static BT::PortsList providedPorts()
{
    return {
        // 기능 포트
        BT::InputPort<double>("target_altitude",
            "목표 고도"),
        // 실패 보고 포트
        BT::OutputPort<int>("error_code",
            "오류 코드"),
        BT::OutputPort<std::string>("error_message",
            "오류 메시지"),
        BT::OutputPort<std::string>("error_context",
            "오류 발생 맥락")
    };
}

BT::NodeStatus onRunning() override
{
    if (action_rejected_)
    {
        setOutput("error_code", 1201);
        setOutput("error_message",
                  "액션 서버가 목표를 거부함");
        setOutput("error_context",
                  "target_altitude=" +
                  std::to_string(target_altitude_));
        return BT::NodeStatus::FAILURE;
    }
    // ...
}

2.2 ROS2 로깅을 통한 기록

rclcpp 로깅 매크로를 통해 실패 정보를 로그에 기록한다. 이 방식은 /rosout 토픽을 통해 중앙 로그 수집 시스템에서 실패 이력을 분석할 수 있는 장점이 있다.

if (timeout_expired)
{
    RCLCPP_ERROR(node_->get_logger(),
        "[%s] 타임아웃 발생 - "
        "경과: %.1f초, 제한: %.1f초, "
        "잔여 거리: %.1f m",
        name().c_str(),
        elapsed, timeout, remaining_distance);
    return BT::NodeStatus::FAILURE;
}

2.3 진단 토픽을 통한 발행

diagnostic_msgs/msg/DiagnosticStatus 메시지를 활용하여 구조화된 실패 정보를 전용 진단 토픽으로 발행한다.

void reportFailure(const std::string& error_msg,
                   int error_code,
                   const std::map<std::string,
                       std::string>& details)
{
    diagnostic_msgs::msg::DiagnosticStatus status;
    status.level =
        diagnostic_msgs::msg::DiagnosticStatus::ERROR;
    status.name = name();
    status.message = error_msg;
    status.hardware_id = "behavior_tree";

    for (const auto& [key, value] : details)
    {
        diagnostic_msgs::msg::KeyValue kv;
        kv.key = key;
        kv.value = value;
        status.values.push_back(kv);
    }

    diagnostic_msgs::msg::DiagnosticArray diag_array;
    diag_array.header.stamp = node_->now();
    diag_array.status.push_back(status);
    diagnostics_pub_->publish(diag_array);
}

3. 오류 코드 체계

3.1 체계적 오류 코드 설계

오류 코드는 실패 원인을 정수값으로 표현하여 프로그래밍적 비교와 자동화된 처리를 가능하게 한다.

namespace ErrorCode
{
    // 통신 오류 (1000~1099)
    constexpr int SERVER_UNAVAILABLE = 1001;
    constexpr int CONNECTION_TIMEOUT = 1002;
    constexpr int GOAL_REJECTED      = 1003;
    constexpr int ACTION_ABORTED     = 1004;

    // 입력 오류 (1100~1199)
    constexpr int PORT_READ_FAILURE  = 1101;
    constexpr int INVALID_PARAMETER  = 1102;
    constexpr int MISSING_INPUT      = 1103;

    // 실행 오류 (1200~1299)
    constexpr int EXECUTION_TIMEOUT  = 1201;
    constexpr int PRECONDITION_FAIL  = 1202;
    constexpr int HARDWARE_ERROR     = 1203;

    // 환경 오류 (1300~1399)
    constexpr int OBSTACLE_DETECTED  = 1301;
    constexpr int GEOFENCE_VIOLATION = 1302;
    constexpr int WEATHER_LIMIT      = 1303;
}

3.2 오류 코드를 이용한 조건 분기

상위 행동 트리에서 오류 코드를 참조하여 실패 원인에 따른 분기를 수행할 수 있다.

<Fallback>
    <NavigateToPose goal="{target}"
                    error_code="{nav_error}" />
    <Sequence>
        <!-- 장애물에 의한 실패인 경우 우회 경로 시도 -->
        <CheckEquals value="{nav_error}" target="1301" />
        <ComputeAlternativePath
            original="{target}"
            alternative="{alt_target}" />
        <NavigateToPose goal="{alt_target}" />
    </Sequence>
    <Sequence>
        <!-- 기타 실패: 귀환 -->
        <ReturnToHome />
    </Sequence>
</Fallback>

4. 실패 보고 기반 클래스

반복되는 실패 보고 로직을 기반 클래스로 추상화하여 일관성을 확보할 수 있다.

class ReportableActionNode : public BT::StatefulActionNode
{
public:
    ReportableActionNode(
        const std::string& name,
        const BT::NodeConfiguration& config)
        : BT::StatefulActionNode(name, config)
    {
    }

    static BT::PortsList commonPorts()
    {
        return {
            BT::OutputPort<int>("error_code",
                "오류 코드"),
            BT::OutputPort<std::string>("error_message",
                "오류 메시지")
        };
    }

protected:
    BT::NodeStatus reportFailure(
        int code, const std::string& message)
    {
        setOutput("error_code", code);
        setOutput("error_message", message);
        RCLCPP_ERROR(logger_, "[%s] 오류 %d: %s",
            name().c_str(), code, message.c_str());
        return BT::NodeStatus::FAILURE;
    }

    rclcpp::Logger logger_{
        rclcpp::get_logger("action_node")};
};

파생 클래스에서는 reportFailure()를 호출하여 간결하게 실패를 보고한다.

class TakeoffAction : public ReportableActionNode
{
    BT::NodeStatus onStart() override
    {
        if (!action_client_->wait_for_action_server(
                std::chrono::seconds(3)))
        {
            return reportFailure(
                ErrorCode::SERVER_UNAVAILABLE,
                "Takeoff 서버 연결 불가");
        }
        // ...
    }
};

5. 실패 이력 관리

5.1 실패 이력 누적

행동 트리의 실행 과정에서 발생한 실패를 누적하여 기록하면, 반복되는 실패 패턴을 식별하고 시스템 수준의 문제를 진단할 수 있다.

struct FailureRecord
{
    rclcpp::Time timestamp;
    std::string node_name;
    int error_code;
    std::string error_message;
};

class FailureHistory
{
public:
    void addRecord(const FailureRecord& record)
    {
        records_.push_back(record);
        if (records_.size() > max_records_)
        {
            records_.erase(records_.begin());
        }
    }

    int countRecentFailures(
        const std::string& node_name,
        double window_seconds) const;

    std::vector<FailureRecord> getRecords() const
    {
        return records_;
    }

private:
    std::vector<FailureRecord> records_;
    size_t max_records_{1000};
};

5.2 반복 실패 감지

동일 노드에서 단기간에 반복적으로 실패가 발생하면, 일시적 오류가 아닌 구조적 문제일 가능성이 높다. 이 경우 재시도를 중단하고 상위 시스템에 경고를 발행해야 한다.

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

<Sequence>
    <Fallback>
        <CaptureImage image="{image}"
                      error_code="{cap_error}"
                      error_message="{cap_msg}" />
        <Sequence>
            <LogMessage level="ERROR"
                        message="촬영 실패: {cap_msg}" />
            <ForceFailure />
        </Sequence>
    </Fallback>
</Sequence>

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.
  • Open Robotics, “ROS 2 Diagnostics,” ROS 2 Documentation, https://docs.ros.org/en/rolling/p/diagnostic_msgs/.

버전: 2026-04-04