From 2fdc1b0319a0eb1b173549b411c30f228bc95866 Mon Sep 17 00:00:00 2001 From: CursedRock17 Date: Mon, 1 Apr 2024 01:29:04 -0400 Subject: [PATCH] Adding unit tests Signed-off-by: CursedRock17 --- rclcpp/CMakeLists.txt | 1 + .../rclcpp/parameter_descriptor_wrapper.hpp | 28 ++++++------ .../rclcpp/parameter_descriptor_wrapper.cpp | 44 ++++++++++--------- rclcpp/test/rclcpp/test_parameter_service.cpp | 30 +++++++++++++ 4 files changed, 69 insertions(+), 34 deletions(-) diff --git a/rclcpp/CMakeLists.txt b/rclcpp/CMakeLists.txt index b2d1023064..e22f3f240a 100644 --- a/rclcpp/CMakeLists.txt +++ b/rclcpp/CMakeLists.txt @@ -96,6 +96,7 @@ set(${PROJECT_NAME}_SRCS src/rclcpp/node_options.cpp src/rclcpp/parameter.cpp src/rclcpp/parameter_client.cpp + src/rclcpp/parameter_descriptor_wrapper.cpp src/rclcpp/parameter_event_handler.cpp src/rclcpp/parameter_events_filter.cpp src/rclcpp/parameter_map.cpp diff --git a/rclcpp/include/rclcpp/parameter_descriptor_wrapper.hpp b/rclcpp/include/rclcpp/parameter_descriptor_wrapper.hpp index 6f87022cb0..34f88475f5 100644 --- a/rclcpp/include/rclcpp/parameter_descriptor_wrapper.hpp +++ b/rclcpp/include/rclcpp/parameter_descriptor_wrapper.hpp @@ -25,6 +25,7 @@ #include "rcl_interfaces/msg/parameter_descriptor.hpp" #include "rclcpp/node.hpp" +#include "rclcpp/parameter_value.hpp" #include "node_interfaces/node_parameters_interface.hpp" #include "rclcpp/node_interfaces/get_node_parameters_interface.hpp" @@ -43,25 +44,24 @@ class ParameterDescription // Builder Methods: // Describes the instances in a parameter_description object - ParameterDescription & SetName(const std::string & name); - ParameterDescription & SetType(std::uint8_t type); - ParameterDescription & SetDescriptionText(const std::string & description); - ParameterDescription & SetAdditionalConstraints(const std::string & constraints); - ParameterDescription & SetReadOnly(bool read_only); - ParameterDescription & SetDynamicTyping(bool dynamic_typing); - ParameterDescription & SetFloatingPointDescriptionRange(float min = 0.0f, float max = 1.0f, - float step = 0.0f); - ParameterDescription & SetIntegerDescriptionRange(int min = 0, int max = 1, int step = 0); + ParameterDescription & set_name(const std::string & name); + ParameterDescription & set_type(std::uint8_t type); + ParameterDescription & set_description_text(const std::string & description); + ParameterDescription & set_additional_constraints(const std::string & constraints); + ParameterDescription & set_read_only(bool read_only); + ParameterDescription & set_dynamic_typing(bool dynamic_typing); + ParameterDescription & set_floating_point_description_range(float min, float max, float step); + ParameterDescription & set_integer_description_range(int min, int max, int step); // Need the current node in order to begin the configuration state // for it via the declare_parameter function - template - ParameterDescription & DeclareParameter( - ParameterType default_value, + template + ParameterDescription & declare_parameter( + const rclcpp::ParameterValue & default_value, NodeT && node) { auto node_param = rclcpp::node_interfaces::get_node_parameters_interface(node); - node_param->declare_parameter( + node_param->declare_parameter( parameter_descriptor.name, default_value, parameter_descriptor); return *this; @@ -69,7 +69,7 @@ class ParameterDescription private: // The main descriptor object we're meant to initialize and adjust - rcl_interfaces::msg::ParameterDescriptor parameter_descriptor = {}; + rcl_interfaces::msg::ParameterDescriptor parameter_descriptor; }; } // namespace rclcpp diff --git a/rclcpp/src/rclcpp/parameter_descriptor_wrapper.cpp b/rclcpp/src/rclcpp/parameter_descriptor_wrapper.cpp index 97268959b0..c9fa6e366b 100644 --- a/rclcpp/src/rclcpp/parameter_descriptor_wrapper.cpp +++ b/rclcpp/src/rclcpp/parameter_descriptor_wrapper.cpp @@ -20,7 +20,7 @@ namespace rclcpp ParameterDescription::ParameterDescription() { // Need to set this in the constructor, but it doesn't necessarily need to be used - parameter_descriptor.type{rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET}; + parameter_descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET; } rcl_interfaces::msg::ParameterDescriptor ParameterDescription::build() const @@ -32,61 +32,65 @@ rcl_interfaces::msg::ParameterDescriptor ParameterDescription::build() const // Builder methods which set up the original class // They all follow the same format of initing the value given within the base class // then returning the current class -ParameterDescription & ParameterDescription::SetName(const std::string & name) +ParameterDescription & ParameterDescription::set_name(const std::string & name) { parameter_descriptor.name = name; return *this; } -ParameterDescription & ParameterDescription::SetType(std::uint8_t type) +ParameterDescription & ParameterDescription::set_type(std::uint8_t type) { parameter_descriptor.type = type; return *this; } -ParameterDescription & ParameterDescription::SetDescriptionText(const std::string & description) +ParameterDescription & ParameterDescription::set_description_text(const std::string & description) { parameter_descriptor.description = description; return *this; } -ParameterDescription & ParameterDescription::SetAdditionalConstraints( +ParameterDescription & ParameterDescription::set_additional_constraints( const std::string & constraints) { - parameter_descriptor.constraints = constraints; + parameter_descriptor.additional_constraints = constraints; return *this; } -ParameterDescription & ParameterDescription::SetReadOnly(bool read_only) +ParameterDescription & ParameterDescription::set_read_only(bool read_only) { parameter_descriptor.read_only = read_only; return *this; } -ParameterDescription & ParameterDescription::SetDynamicTyping(bool dynamic_typing) +ParameterDescription & ParameterDescription::set_dynamic_typing(bool dynamic_typing) { parameter_descriptor.dynamic_typing = dynamic_typing; return *this; } // Here is the Specific range function for this parameter description -ParameterDescription & ParameterDescription::SetFloatingPointDescriptionRange( - float min, float max, - float step) +ParameterDescription & ParameterDescription::set_floating_point_description_range( + float min, float max, float step) { - parameter_descriptor.floating_point_range.resize(1); - parameter_descriptor.floating_point_range.at(0).from_value = min; - parameter_descriptor.floating_point_range.at(0).to_value = max; - parameter_descriptor.floating_point_range.at(0).step = step; + if (parameter_descriptor.type == rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) { + parameter_descriptor.floating_point_range.resize(1); + parameter_descriptor.floating_point_range.at(0).from_value = min; + parameter_descriptor.floating_point_range.at(0).to_value = max; + parameter_descriptor.floating_point_range.at(0).step = step; + } return *this; } -ParameterDescription & ParameterDescription::SetIntegerDescriptionRange(int min, int max, int step) +ParameterDescription & ParameterDescription::set_integer_description_range( + int min, int max, int step) { - parameter_descriptor.integer_range.resize(1); - parameter_descriptor.integer_range.at(0).from_value = min; - parameter_descriptor.integer_range.at(0).to_value = max; - parameter_descriptor.integer_range.at(0).step = step; + if (parameter_descriptor.type == rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER) { + parameter_descriptor.integer_range.resize(1); + parameter_descriptor.integer_range.at(0).from_value = min; + parameter_descriptor.integer_range.at(0).to_value = max; + parameter_descriptor.integer_range.at(0).step = step; + } return *this; } diff --git a/rclcpp/test/rclcpp/test_parameter_service.cpp b/rclcpp/test/rclcpp/test_parameter_service.cpp index 7d63d0866d..d8d97cac39 100644 --- a/rclcpp/test/rclcpp/test_parameter_service.cpp +++ b/rclcpp/test/rclcpp/test_parameter_service.cpp @@ -20,6 +20,7 @@ #include #include "rclcpp/rclcpp.hpp" +#include "rclcpp/parameter_descriptor_wrapper.hpp" #include "../../src/rclcpp/parameter_service_names.hpp" using namespace std::chrono_literals; @@ -119,3 +120,32 @@ TEST_F(TestParameterService, describe_parameters) { EXPECT_EQ(0u, parameter_descs.size()); } } + +TEST_F(TestParameterService, parameter_descriptor) { + { + rclcpp::ParameterDescription param_description; + rclcpp::ParameterValue param_value(1); + + param_description.set_name("int_parameter"); + param_description.set_type(2); + param_description.set_description_text("description"); + param_description.set_additional_constraints("constraints"); + param_description.set_read_only(false); + param_description.set_integer_description_range(0, 10, 1); + + auto param = param_description.build(); + param_description.declare_parameter(param_value, node); + + EXPECT_EQ("int_parameter", param.name); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, param.type); + EXPECT_EQ("description", param.description); + EXPECT_EQ("constraints", param.additional_constraints); + EXPECT_EQ(0u, param.read_only); + EXPECT_EQ(0u, param.dynamic_typing); + EXPECT_EQ(0u, param.integer_range.at(0).from_value); + EXPECT_EQ(10, param.integer_range.at(0).to_value); + EXPECT_EQ(1, param.integer_range.at(0).step); + + ASSERT_EQ(1, client->get_parameter("int_parameter", 0)); + } +}