파라미터 값 확인 조건 노드 (Parameter Value Check Condition Node)

파라미터 값 확인 조건 노드 (Parameter Value Check Condition Node)

1. 개요

파라미터 값 확인 조건 노드는 ROS2 파라미터의 현재 값을 기대 값 또는 기준값과 비교하여 조건을 판정하는 조건 노드이다. 파라미터 시스템의 다양한 타입(불리언, 정수, 부동소수점, 문자열)에 대한 비교 연산을 지원하며, 동적으로 변경될 수 있는 설정 값을 행동 트리의 의사 결정에 즉시 반영한다. 본 절에서는 각 파라미터 타입별 값 확인 패턴과 범용적 파라미터 값 비교 조건 노드의 구현을 다룬다.

2. 타입별 파라미터 값 확인

2.1 불리언 파라미터 값 확인

불리언 파라미터는 기능 활성화/비활성화, 모드 전환 플래그 등에 사용된다. 값이 true인지 false인지를 직접 판정한다.

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

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<std::string>("param_name",
                                       "파라미터 이름"),
            BT::InputPort<bool>("expected_value", true,
                                "기대하는 불리언 값")
        };
    }

    BT::NodeStatus tick() override
    {
        std::string param_name;
        bool expected_value;
        getInput("param_name", param_name);
        getInput("expected_value", expected_value);

        if (!node_->has_parameter(param_name))
        {
            return BT::NodeStatus::FAILURE;
        }

        auto param = node_->get_parameter(param_name);
        if (param.get_type() != rclcpp::ParameterType::PARAMETER_BOOL)
        {
            return BT::NodeStatus::FAILURE;
        }

        if (param.as_bool() == expected_value)
        {
            return BT::NodeStatus::SUCCESS;
        }
        return BT::NodeStatus::FAILURE;
    }

private:
    rclcpp::Node::SharedPtr node_;
};

expected_value 입력 포트의 기본값을 true로 설정하여, XML에서 기대 값을 생략하면 파라미터가 true인지를 확인하는 것으로 동작한다.

2.2 정수 파라미터 값 확인

정수 파라미터에 대한 등호 비교, 부등호 비교, 범위 비교를 지원하는 조건 노드이다.

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

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<std::string>("param_name",
                                       "파라미터 이름"),
            BT::InputPort<std::string>("operator", "EQ",
                "비교 연산자 (EQ, NEQ, GT, LT, GTE, LTE)"),
            BT::InputPort<int64_t>("reference", "기준값")
        };
    }

    BT::NodeStatus tick() override
    {
        std::string param_name, op;
        int64_t reference;
        getInput("param_name", param_name);
        getInput("operator", op);
        getInput("reference", reference);

        if (!node_->has_parameter(param_name))
        {
            return BT::NodeStatus::FAILURE;
        }

        auto param = node_->get_parameter(param_name);
        if (param.get_type() !=
            rclcpp::ParameterType::PARAMETER_INTEGER)
        {
            return BT::NodeStatus::FAILURE;
        }

        int64_t value = param.as_int();
        bool result = compare(value, reference, op);
        return result ? BT::NodeStatus::SUCCESS
                      : BT::NodeStatus::FAILURE;
    }

private:
    bool compare(int64_t value, int64_t reference,
                 const std::string& op) const
    {
        if (op == "EQ")  return value == reference;
        if (op == "NEQ") return value != reference;
        if (op == "GT")  return value > reference;
        if (op == "LT")  return value < reference;
        if (op == "GTE") return value >= reference;
        if (op == "LTE") return value <= reference;
        return false;
    }

    rclcpp::Node::SharedPtr node_;
};

2.3 부동소수점 파라미터 값 확인

부동소수점 파라미터의 비교에서는 수치 정밀도를 고려하여야 한다.

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

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<std::string>("param_name",
                                       "파라미터 이름"),
            BT::InputPort<std::string>("operator", "LTE",
                "비교 연산자 (EQ, NEQ, GT, LT, GTE, LTE)"),
            BT::InputPort<double>("reference", "기준값"),
            BT::InputPort<double>("epsilon", 1e-9,
                "등호 비교 허용 오차")
        };
    }

    BT::NodeStatus tick() override
    {
        std::string param_name, op;
        double reference, epsilon;
        getInput("param_name", param_name);
        getInput("operator", op);
        getInput("reference", reference);
        getInput("epsilon", epsilon);

        if (!node_->has_parameter(param_name))
        {
            return BT::NodeStatus::FAILURE;
        }

        auto param = node_->get_parameter(param_name);
        if (param.get_type() !=
            rclcpp::ParameterType::PARAMETER_DOUBLE)
        {
            return BT::NodeStatus::FAILURE;
        }

        double value = param.as_double();
        bool result = compare(value, reference, op, epsilon);
        return result ? BT::NodeStatus::SUCCESS
                      : BT::NodeStatus::FAILURE;
    }

private:
    bool compare(double value, double reference,
                 const std::string& op, double epsilon) const
    {
        if (op == "EQ")  return std::abs(value - reference) < epsilon;
        if (op == "NEQ") return std::abs(value - reference) >= epsilon;
        if (op == "GT")  return value > reference;
        if (op == "LT")  return value < reference;
        if (op == "GTE") return value >= reference;
        if (op == "LTE") return value <= reference;
        return false;
    }

    rclcpp::Node::SharedPtr node_;
};

epsilon 매개변수는 등호(EQ) 및 부등(NEQ) 비교에서 부동소수점 수의 정밀도 한계를 보상한다. 기본값 \epsilon = 10^{-9}는 대부분의 실용적 상황에서 적절하다.

2.4 문자열 파라미터 값 확인

문자열 파라미터는 동작 모드, 프레임 ID, 네임스페이스 등의 텍스트 설정에 사용된다.

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

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<std::string>("param_name",
                                       "파라미터 이름"),
            BT::InputPort<std::string>("expected_value",
                                       "기대하는 문자열 값"),
            BT::InputPort<bool>("case_sensitive", true,
                                "대소문자 구분 여부")
        };
    }

    BT::NodeStatus tick() override
    {
        std::string param_name, expected_value;
        bool case_sensitive;
        getInput("param_name", param_name);
        getInput("expected_value", expected_value);
        getInput("case_sensitive", case_sensitive);

        if (!node_->has_parameter(param_name))
        {
            return BT::NodeStatus::FAILURE;
        }

        auto param = node_->get_parameter(param_name);
        if (param.get_type() !=
            rclcpp::ParameterType::PARAMETER_STRING)
        {
            return BT::NodeStatus::FAILURE;
        }

        std::string value = param.as_string();

        bool match;
        if (case_sensitive)
        {
            match = (value == expected_value);
        }
        else
        {
            std::string val_lower = value;
            std::string exp_lower = expected_value;
            std::transform(val_lower.begin(), val_lower.end(),
                           val_lower.begin(), ::tolower);
            std::transform(exp_lower.begin(), exp_lower.end(),
                           exp_lower.begin(), ::tolower);
            match = (val_lower == exp_lower);
        }

        return match ? BT::NodeStatus::SUCCESS
                     : BT::NodeStatus::FAILURE;
    }

private:
    rclcpp::Node::SharedPtr node_;
};

3. 범용 파라미터 값 확인 조건 노드

모든 스칼라 파라미터 타입을 단일 클래스에서 처리하는 범용 구현이다. 파라미터의 실제 타입을 런타임에 감지하여 적절한 비교를 수행한다.

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

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<std::string>("param_name",
                                       "파라미터 이름"),
            BT::InputPort<std::string>("expected_value",
                "기대 값 (문자열로 전달, 타입에 따라 자동 변환)"),
            BT::InputPort<std::string>("operator", "EQ",
                "비교 연산자")
        };
    }

    BT::NodeStatus tick() override
    {
        std::string param_name, expected_str, op;
        getInput("param_name", param_name);
        getInput("expected_value", expected_str);
        getInput("operator", op);

        if (!node_->has_parameter(param_name))
        {
            return BT::NodeStatus::FAILURE;
        }

        auto param = node_->get_parameter(param_name);

        switch (param.get_type())
        {
        case rclcpp::ParameterType::PARAMETER_BOOL:
        {
            bool expected = (expected_str == "true" ||
                             expected_str == "True" ||
                             expected_str == "1");
            return (param.as_bool() == expected)
                       ? BT::NodeStatus::SUCCESS
                       : BT::NodeStatus::FAILURE;
        }
        case rclcpp::ParameterType::PARAMETER_INTEGER:
        {
            int64_t expected = std::stoll(expected_str);
            return compareNumeric(
                       static_cast<double>(param.as_int()),
                       static_cast<double>(expected), op)
                       ? BT::NodeStatus::SUCCESS
                       : BT::NodeStatus::FAILURE;
        }
        case rclcpp::ParameterType::PARAMETER_DOUBLE:
        {
            double expected = std::stod(expected_str);
            return compareNumeric(param.as_double(), expected, op)
                       ? BT::NodeStatus::SUCCESS
                       : BT::NodeStatus::FAILURE;
        }
        case rclcpp::ParameterType::PARAMETER_STRING:
        {
            return (param.as_string() == expected_str)
                       ? BT::NodeStatus::SUCCESS
                       : BT::NodeStatus::FAILURE;
        }
        default:
            return BT::NodeStatus::FAILURE;
        }
    }

private:
    bool compareNumeric(double value, double reference,
                        const std::string& op) const
    {
        if (op == "EQ")  return std::abs(value - reference) < 1e-9;
        if (op == "NEQ") return std::abs(value - reference) >= 1e-9;
        if (op == "GT")  return value > reference;
        if (op == "LT")  return value < reference;
        if (op == "GTE") return value >= reference;
        if (op == "LTE") return value <= reference;
        return false;
    }

    rclcpp::Node::SharedPtr node_;
};

범용 구현은 기대 값을 문자열로 전달받아 파라미터의 실제 타입에 따라 변환한다. 이 방식은 XML 행동 트리 정의에서 단일 노드 타입으로 모든 파라미터 비교를 처리할 수 있다는 장점이 있으나, 문자열 파싱 과정에서의 변환 오류 가능성을 내���한다.

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

4.1 동작 모드 기반 분기

<BehaviorTree ID="ModeSelector">
    <Fallback>
        <Sequence>
            <Condition ID="CheckStringParameter"
                       param_name="navigation_mode"
                       expected_value="waypoint"/>
            <Action ID="WaypointNavigation"/>
        </Sequence>
        <Sequence>
            <Condition ID="CheckStringParameter"
                       param_name="navigation_mode"
                       expected_value="exploration"/>
            <Action ID="FrontierExploration"/>
        </Sequence>
    </Fallback>
</BehaviorTree>

4.2 속도 제한 파라미터 기반 조건부 행동

<BehaviorTree ID="SpeedLimitedNav">
    <ReactiveSequence>
        <Condition ID="CheckDoubleParameter"
                   param_name="max_velocity"
                   operator="GT"
                   reference="0.0"/>
        <Action ID="NavigateToGoal"/>
    </ReactiveSequence>
</BehaviorTree>

max_velocity 파라미터가 0보다 큰 경우에만 내비게이션을 수행한다. 운용자가 이 파라미터를 0으로 설정하면 내비게이션이 정지된다.

4.3 범용 노드를 활용한 다양한 비교

<Sequence>
    <Condition ID="CheckParameterValue"
               param_name="safety_level"
               expected_value="2"
               operator="GTE"/>
    <Condition ID="CheckParameterValue"
               param_name="auto_recovery_enabled"
               expected_value="true"/>
    <Action ID="AutoRecovery"/>
</Sequence>

5. 파라미터 값 확인과 파라미터 이벤트 연동

파라미터 값을 매 tick마다 get_parameter()로 읽는 방식은 단순하지만, 파라미터가 변경되지 않은 경우에도 반복적으로 조회하는 비효율이 있다. 파라미터 이벤트 콜백을 활용하면, 파라미터가 변경될 때에만 내부 캐시를 갱신하고 tick() 에서는 캐시 값을 참조하는 방식으로 최적화할 수 있다.

class CheckParameterCached : public BT::ConditionNode
{
public:
    CheckParameterCached(const std::string& name,
                         const BT::NodeConfiguration& config,
                         rclcpp::Node::SharedPtr node)
        : BT::ConditionNode(name, config), node_(node)
    {
        std::string param_name;
        getInput("param_name", param_name);

        // 초기값 캐싱
        if (node_->has_parameter(param_name))
        {
            cached_param_ = node_->get_parameter(param_name);
            initialized_ = true;
        }

        // 변경 콜백 등록
        param_handler_ =
            std::make_shared<rclcpp::ParameterEventHandler>(node_);
        cb_handle_ = param_handler_->add_parameter_callback(
            param_name,
            [this](const%20rclcpp::Parameter&%20param) {
                std::lock_guard<std::mutex> lock(mutex_);
                cached_param_ = param;
                initialized_ = true;
            });
    }

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<std::string>("param_name",
                                       "파라미터 이름"),
            BT::InputPort<std::string>("expected_value",
                                       "기대 값"),
            BT::InputPort<std::string>("operator", "EQ",
                                       "비교 연산자")
        };
    }

    BT::NodeStatus tick() override
    {
        std::lock_guard<std::mutex> lock(mutex_);
        if (!initialized_)
        {
            return BT::NodeStatus::FAILURE;
        }

        std::string expected_str, op;
        getInput("expected_value", expected_str);
        getInput("operator", op);

        // cached_param_을 기반으로 비교 수행
        return evaluateCached(expected_str, op);
    }

private:
    BT::NodeStatus evaluateCached(const std::string& expected,
                                  const std::string& op)
    {
        switch (cached_param_.get_type())
        {
        case rclcpp::ParameterType::PARAMETER_BOOL:
        {
            bool exp = (expected == "true" || expected == "1");
            return (cached_param_.as_bool() == exp)
                       ? BT::NodeStatus::SUCCESS
                       : BT::NodeStatus::FAILURE;
        }
        case rclcpp::ParameterType::PARAMETER_DOUBLE:
        {
            double ref = std::stod(expected);
            double val = cached_param_.as_double();
            if (op == "EQ")
                return std::abs(val - ref) < 1e-9
                           ? BT::NodeStatus::SUCCESS
                           : BT::NodeStatus::FAILURE;
            if (op == "GT")
                return val > ref ? BT::NodeStatus::SUCCESS
                                 : BT::NodeStatus::FAILURE;
            if (op == "LT")
                return val < ref ? BT::NodeStatus::SUCCESS
                                 : BT::NodeStatus::FAILURE;
            if (op == "GTE")
                return val >= ref ? BT::NodeStatus::SUCCESS
                                  : BT::NodeStatus::FAILURE;
            if (op == "LTE")
                return val <= ref ? BT::NodeStatus::SUCCESS
                                  : BT::NodeStatus::FAILURE;
            return BT::NodeStatus::FAILURE;
        }
        case rclcpp::ParameterType::PARAMETER_STRING:
            return (cached_param_.as_string() == expected)
                       ? BT::NodeStatus::SUCCESS
                       : BT::NodeStatus::FAILURE;
        default:
            return BT::NodeStatus::FAILURE;
        }
    }

    rclcpp::Node::SharedPtr node_;
    std::shared_ptr<rclcpp::ParameterEventHandler> param_handler_;
    std::shared_ptr<rclcpp::ParameterCallbackHandle> cb_handle_;
    std::mutex mutex_;
    rclcpp::Parameter cached_param_;
    bool initialized_{false};
};

6. 설계 시 고려 사항

6.1 파라미터 미선언 처리

ROS2에서 선언되지 않은 파라미터에 접근하면 rclcpp::exceptions::ParameterNotDeclaredException 예외가 발생한다. 조건 노드에서는 has_parameter() 메서드로 사전 검사를 수행하거나, 예외를 포착하여 FAILURE를 반환하여야 한다.

6.2 파라미터 타입 변환의 안전성

범용 파라미터 확인 노드에서 문자열을 수치 타입으로 변환할 때, std::stod()std::stoll() 호출이 변환 실패 시 std::invalid_argument 또는 std::out_of_range 예외를 발생시킬 수 있다. 이러한 예외를 적절히 처리하여 조건 노드가 비정상 종료되지 않도록 하여야 한다.

6.3 파라미터 변경의 원자성

ROS2 파라미터 시스템은 개별 파라미터의 변경이 원자적(atomic)으로 이루어지지만, 복수의 파라미터를 동시에 변경하는 경우 중간 상태가 관측될 수 있다. 예를 들어, modemax_speed를 동시에 변경하려는 경우, 행동 트리가 새로운 mode 값과 이전의 max_speed 값을 조합하여 판정할 수 있다. 이를 방지하기 위해 set_parameters_atomically() 메서드를 사용하여 복수의 파라미터를 원자적으로 변경하거나, 조건 노드에서 관련 파라미터들의 일관성을 검증하는 로직을 추가하여야 한다.

7. 참고 문헌

  • Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
  • ROS2 파라미터 공식 문서. https://docs.ros.org/en/humble/Concepts/Basic/About-Parameters.html
  • BehaviorTree.CPP 공식 문서. https://www.behaviortree.dev/

버전날짜변경 사항
v0.12026-04-04초안 작성