From 6c441ca62c769f123fcde52a22ffcb76c4cb4f68 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 29 May 2018 15:03:15 -0700 Subject: [PATCH] rclcpp::parameter::ParameterVariant -> rclcpp::Parameter --- rclcpp/include/rclcpp/node.hpp | 10 +-- rclcpp/include/rclcpp/node_impl.hpp | 12 +-- .../node_interfaces/node_parameters.hpp | 12 +-- .../node_parameters_interface.hpp | 12 +-- rclcpp/include/rclcpp/parameter.hpp | 25 +++--- rclcpp/include/rclcpp/parameter_client.hpp | 14 +-- rclcpp/include/rclcpp/rclcpp.hpp | 2 +- rclcpp/src/rclcpp/node.cpp | 10 +-- .../node_interfaces/node_parameters.cpp | 20 ++--- rclcpp/src/rclcpp/parameter.cpp | 54 ++++++------ rclcpp/src/rclcpp/parameter_client.cpp | 28 +++--- rclcpp/src/rclcpp/parameter_service.cpp | 8 +- rclcpp/test/test_parameter.cpp | 88 +++++++++---------- rclcpp/test/test_time_source.cpp | 8 +- .../rclcpp_lifecycle/lifecycle_node.hpp | 10 +-- .../rclcpp_lifecycle/lifecycle_node_impl.hpp | 6 +- rclcpp_lifecycle/src/lifecycle_node.cpp | 10 +-- 17 files changed, 163 insertions(+), 166 deletions(-) diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index 37f9b05f90..149b81d0cb 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -256,11 +256,11 @@ class Node : public std::enable_shared_from_this RCLCPP_PUBLIC std::vector - set_parameters(const std::vector & parameters); + set_parameters(const std::vector & parameters); RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult - set_parameters_atomically(const std::vector & parameters); + set_parameters_atomically(const std::vector & parameters); template void @@ -269,18 +269,18 @@ class Node : public std::enable_shared_from_this const ParameterT & value); RCLCPP_PUBLIC - std::vector + std::vector get_parameters(const std::vector & names) const; RCLCPP_PUBLIC - rclcpp::parameter::ParameterVariant + rclcpp::Parameter get_parameter(const std::string & name) const; RCLCPP_PUBLIC bool get_parameter( const std::string & name, - rclcpp::parameter::ParameterVariant & parameter) const; + rclcpp::Parameter & parameter) const; /// Assign the value of the parameter if set into the parameter argument. /** diff --git a/rclcpp/include/rclcpp/node_impl.hpp b/rclcpp/include/rclcpp/node_impl.hpp index 25d6a6819a..e841f614f0 100644 --- a/rclcpp/include/rclcpp/node_impl.hpp +++ b/rclcpp/include/rclcpp/node_impl.hpp @@ -203,10 +203,10 @@ Node::set_parameter_if_not_set( const std::string & name, const ParameterT & value) { - rclcpp::parameter::ParameterVariant parameter_variant; - if (!this->get_parameter(name, parameter_variant)) { + rclcpp::Parameter parameter; + if (!this->get_parameter(name, parameter)) { this->set_parameters({ - rclcpp::parameter::ParameterVariant(name, value), + rclcpp::Parameter(name, value), }); } } @@ -215,10 +215,10 @@ template bool Node::get_parameter(const std::string & name, ParameterT & value) const { - rclcpp::parameter::ParameterVariant parameter_variant; - bool result = get_parameter(name, parameter_variant); + rclcpp::Parameter parameter; + bool result = get_parameter(name, parameter); if (result) { - value = parameter_variant.get_value(); + value = parameter.get_value(); } return result; diff --git a/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp b/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp index 6020bda9c1..eb02d97459 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_parameters.hpp @@ -62,22 +62,22 @@ class NodeParameters : public NodeParametersInterface virtual std::vector set_parameters( - const std::vector & parameters); + const std::vector & parameters); RCLCPP_PUBLIC virtual rcl_interfaces::msg::SetParametersResult set_parameters_atomically( - const std::vector & parameters); + const std::vector & parameters); RCLCPP_PUBLIC virtual - std::vector + std::vector get_parameters(const std::vector & names) const; RCLCPP_PUBLIC virtual - rclcpp::parameter::ParameterVariant + rclcpp::Parameter get_parameter(const std::string & name) const; RCLCPP_PUBLIC @@ -85,7 +85,7 @@ class NodeParameters : public NodeParametersInterface bool get_parameter( const std::string & name, - rclcpp::parameter::ParameterVariant & parameter) const; + rclcpp::Parameter & parameter) const; RCLCPP_PUBLIC virtual @@ -114,7 +114,7 @@ class NodeParameters : public NodeParametersInterface ParametersCallbackFunction parameters_callback_ = nullptr; - std::map parameters_; + std::map parameters_; Publisher::SharedPtr events_publisher_; diff --git a/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp index 7902130d27..9d76c6a249 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_parameters_interface.hpp @@ -41,22 +41,22 @@ class NodeParametersInterface virtual std::vector set_parameters( - const std::vector & parameters) = 0; + const std::vector & parameters) = 0; RCLCPP_PUBLIC virtual rcl_interfaces::msg::SetParametersResult set_parameters_atomically( - const std::vector & parameters) = 0; + const std::vector & parameters) = 0; RCLCPP_PUBLIC virtual - std::vector + std::vector get_parameters(const std::vector & names) const = 0; RCLCPP_PUBLIC virtual - rclcpp::parameter::ParameterVariant + rclcpp::Parameter get_parameter(const std::string & name) const = 0; RCLCPP_PUBLIC @@ -64,7 +64,7 @@ class NodeParametersInterface bool get_parameter( const std::string & name, - rclcpp::parameter::ParameterVariant & parameter) const = 0; + rclcpp::Parameter & parameter) const = 0; RCLCPP_PUBLIC virtual @@ -83,7 +83,7 @@ class NodeParametersInterface using ParametersCallbackFunction = std::function< rcl_interfaces::msg::SetParametersResult( - const std::vector &)>; + const std::vector &)>; RCLCPP_PUBLIC virtual diff --git a/rclcpp/include/rclcpp/parameter.hpp b/rclcpp/include/rclcpp/parameter.hpp index ba2a66aa8a..26c8c0e261 100644 --- a/rclcpp/include/rclcpp/parameter.hpp +++ b/rclcpp/include/rclcpp/parameter.hpp @@ -27,23 +27,21 @@ namespace rclcpp { -namespace parameter -{ // Structure to store an arbitrary parameter with templated get/set methods -class ParameterVariant +class Parameter { public: RCLCPP_PUBLIC - ParameterVariant(); + Parameter(); RCLCPP_PUBLIC - ParameterVariant(const std::string & name, const ParameterValue & value); + Parameter(const std::string & name, const ParameterValue & value); template RCLCPP_PUBLIC - explicit ParameterVariant(const std::string & name, ValueTypeT value) - : ParameterVariant(name, ParameterValue(value)) + explicit Parameter(const std::string & name, ValueTypeT value) + : Parameter(name, ParameterValue(value)) { } @@ -116,7 +114,7 @@ class ParameterVariant as_string_array() const; RCLCPP_PUBLIC - static ParameterVariant + static Parameter from_parameter(const rcl_interfaces::msg::Parameter & parameter); RCLCPP_PUBLIC @@ -158,17 +156,16 @@ class ParameterVariant /// Return a json encoded version of the parameter intended for a dict. RCLCPP_PUBLIC std::string -_to_json_dict_entry(const ParameterVariant & param); +_to_json_dict_entry(const Parameter & param); RCLCPP_PUBLIC std::ostream & -operator<<(std::ostream & os, const rclcpp::parameter::ParameterVariant & pv); +operator<<(std::ostream & os, const rclcpp::Parameter & pv); RCLCPP_PUBLIC std::ostream & -operator<<(std::ostream & os, const std::vector & parameters); +operator<<(std::ostream & os, const std::vector & parameters); -} // namespace parameter } // namespace rclcpp namespace std @@ -177,12 +174,12 @@ namespace std /// Return a json encoded version of the parameter intended for a list. RCLCPP_PUBLIC std::string -to_string(const rclcpp::parameter::ParameterVariant & param); +to_string(const rclcpp::Parameter & param); /// Return a json encoded version of a vector of parameters, as a string. RCLCPP_PUBLIC std::string -to_string(const std::vector & parameters); +to_string(const std::vector & parameters); } // namespace std diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index a9442b0173..cfd9a8e0ad 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -68,11 +68,11 @@ class AsyncParametersClient const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); RCLCPP_PUBLIC - std::shared_future> + std::shared_future> get_parameters( const std::vector & names, std::function< - void(std::shared_future>) + void(std::shared_future>) > callback = nullptr); RCLCPP_PUBLIC @@ -86,7 +86,7 @@ class AsyncParametersClient RCLCPP_PUBLIC std::shared_future> set_parameters( - const std::vector & parameters, + const std::vector & parameters, std::function< void(std::shared_future>) > callback = nullptr); @@ -94,7 +94,7 @@ class AsyncParametersClient RCLCPP_PUBLIC std::shared_future set_parameters_atomically( - const std::vector & parameters, + const std::vector & parameters, std::function< void(std::shared_future) > callback = nullptr); @@ -185,7 +185,7 @@ class SyncParametersClient const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters); RCLCPP_PUBLIC - std::vector + std::vector get_parameters(const std::vector & parameter_names); RCLCPP_PUBLIC @@ -231,11 +231,11 @@ class SyncParametersClient RCLCPP_PUBLIC std::vector - set_parameters(const std::vector & parameters); + set_parameters(const std::vector & parameters); RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult - set_parameters_atomically(const std::vector & parameters); + set_parameters_atomically(const std::vector & parameters); RCLCPP_PUBLIC rcl_interfaces::msg::ListParametersResult diff --git a/rclcpp/include/rclcpp/rclcpp.hpp b/rclcpp/include/rclcpp/rclcpp.hpp index 518ecac05f..11dfdab734 100644 --- a/rclcpp/include/rclcpp/rclcpp.hpp +++ b/rclcpp/include/rclcpp/rclcpp.hpp @@ -49,7 +49,7 @@ * - rclcpp::Node::describe_parameters() * - rclcpp::Node::list_parameters() * - rclcpp::Node::register_param_change_callback() - * - rclcpp::parameter::ParameterVariant + * - rclcpp::Parameter * - rclcpp::AsyncParametersClient * - rclcpp::SyncParametersClient * - rclcpp/parameter.hpp diff --git a/rclcpp/src/rclcpp/node.cpp b/rclcpp/src/rclcpp/node.cpp index 5f798f4975..cb12a3e414 100644 --- a/rclcpp/src/rclcpp/node.cpp +++ b/rclcpp/src/rclcpp/node.cpp @@ -117,26 +117,26 @@ Node::group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr group) std::vector Node::set_parameters( - const std::vector & parameters) + const std::vector & parameters) { return node_parameters_->set_parameters(parameters); } rcl_interfaces::msg::SetParametersResult Node::set_parameters_atomically( - const std::vector & parameters) + const std::vector & parameters) { return node_parameters_->set_parameters_atomically(parameters); } -std::vector +std::vector Node::get_parameters( const std::vector & names) const { return node_parameters_->get_parameters(names); } -rclcpp::parameter::ParameterVariant +rclcpp::Parameter Node::get_parameter(const std::string & name) const { return node_parameters_->get_parameter(name); @@ -144,7 +144,7 @@ Node::get_parameter(const std::string & name) const bool Node::get_parameter( const std::string & name, - rclcpp::parameter::ParameterVariant & parameter) const + rclcpp::Parameter & parameter) const { return node_parameters_->get_parameter(name, parameter); } diff --git a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp index 6033c48f26..7e5d4a399e 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp @@ -57,7 +57,7 @@ NodeParameters::~NodeParameters() std::vector NodeParameters::set_parameters( - const std::vector & parameters) + const std::vector & parameters) { std::vector results; for (auto p : parameters) { @@ -69,10 +69,10 @@ NodeParameters::set_parameters( rcl_interfaces::msg::SetParametersResult NodeParameters::set_parameters_atomically( - const std::vector & parameters) + const std::vector & parameters) { std::lock_guard lock(mutex_); - std::map tmp_map; + std::map tmp_map; auto parameter_event = std::make_shared(); // TODO(jacquelinekay): handle parameter constraints @@ -101,7 +101,7 @@ NodeParameters::set_parameters_atomically( // therefore we will "unset" the previously set parameter // it is not necessary to erase the parameter from parameters_ // because the new value for this key (p.get_name()) will be a - // ParameterVariant with type "NOT_SET" + // Parameter with type "NOT_SET" parameter_event->deleted_parameters.push_back(p.to_parameter()); } tmp_map[p.get_name()] = p; @@ -116,15 +116,15 @@ NodeParameters::set_parameters_atomically( return result; } -std::vector +std::vector NodeParameters::get_parameters(const std::vector & names) const { std::lock_guard lock(mutex_); - std::vector results; + std::vector results; for (auto & name : names) { if (std::any_of(parameters_.cbegin(), parameters_.cend(), - [&name](const std::pair & kv) { + [&name](const std::pair & kv) { return name == kv.first; })) { @@ -134,10 +134,10 @@ NodeParameters::get_parameters(const std::vector & names) const return results; } -rclcpp::parameter::ParameterVariant +rclcpp::Parameter NodeParameters::get_parameter(const std::string & name) const { - rclcpp::parameter::ParameterVariant parameter; + rclcpp::Parameter parameter; if (get_parameter(name, parameter)) { return parameter; @@ -149,7 +149,7 @@ NodeParameters::get_parameter(const std::string & name) const bool NodeParameters::get_parameter( const std::string & name, - rclcpp::parameter::ParameterVariant & parameter) const + rclcpp::Parameter & parameter) const { std::lock_guard lock(mutex_); diff --git a/rclcpp/src/rclcpp/parameter.cpp b/rclcpp/src/rclcpp/parameter.cpp index fd085263ce..ca9dd8547c 100644 --- a/rclcpp/src/rclcpp/parameter.cpp +++ b/rclcpp/src/rclcpp/parameter.cpp @@ -21,104 +21,104 @@ #include "rclcpp/utilities.hpp" using rclcpp::ParameterType; -using rclcpp::parameter::ParameterVariant; +using rclcpp::Parameter; -ParameterVariant::ParameterVariant() +Parameter::Parameter() : name_("") { } -ParameterVariant::ParameterVariant(const std::string & name, const ParameterValue & value) +Parameter::Parameter(const std::string & name, const ParameterValue & value) : name_(name), value_(value) { } ParameterType -ParameterVariant::get_type() const +Parameter::get_type() const { return value_.get_type(); } std::string -ParameterVariant::get_type_name() const +Parameter::get_type_name() const { return rclcpp::to_string(get_type()); } const std::string & -ParameterVariant::get_name() const +Parameter::get_name() const { return name_; } rcl_interfaces::msg::ParameterValue -ParameterVariant::get_value_message() const +Parameter::get_value_message() const { return value_.get_message(); } bool -ParameterVariant::as_bool() const +Parameter::as_bool() const { return get_value(); } int64_t -ParameterVariant::as_int() const +Parameter::as_int() const { return get_value(); } double -ParameterVariant::as_double() const +Parameter::as_double() const { return get_value(); } const std::string & -ParameterVariant::as_string() const +Parameter::as_string() const { return get_value(); } const std::vector & -ParameterVariant::as_byte_array() const +Parameter::as_byte_array() const { return get_value(); } const std::vector & -ParameterVariant::as_bool_array() const +Parameter::as_bool_array() const { return get_value(); } const std::vector & -ParameterVariant::as_integer_array() const +Parameter::as_integer_array() const { return get_value(); } const std::vector & -ParameterVariant::as_double_array() const +Parameter::as_double_array() const { return get_value(); } const std::vector & -ParameterVariant::as_string_array() const +Parameter::as_string_array() const { return get_value(); } -ParameterVariant -ParameterVariant::from_parameter(const rcl_interfaces::msg::Parameter & parameter) +Parameter +Parameter::from_parameter(const rcl_interfaces::msg::Parameter & parameter) { - return ParameterVariant(parameter.name, parameter.value); + return Parameter(parameter.name, parameter.value); } rcl_interfaces::msg::Parameter -ParameterVariant::to_parameter() +Parameter::to_parameter() { rcl_interfaces::msg::Parameter parameter; parameter.name = name_; @@ -127,13 +127,13 @@ ParameterVariant::to_parameter() } std::string -ParameterVariant::value_to_string() const +Parameter::value_to_string() const { return rclcpp::to_string(value_); } std::string -rclcpp::parameter::_to_json_dict_entry(const ParameterVariant ¶m) +rclcpp::_to_json_dict_entry(const Parameter & param) { std::stringstream ss; ss << "\"" << param.get_name() << "\": "; @@ -143,21 +143,21 @@ rclcpp::parameter::_to_json_dict_entry(const ParameterVariant ¶m) } std::ostream & -rclcpp::parameter::operator<<(std::ostream & os, const rclcpp::parameter::ParameterVariant & pv) +rclcpp::operator<<(std::ostream & os, const rclcpp::Parameter & pv) { os << std::to_string(pv); return os; } std::ostream & -rclcpp::parameter::operator<<(std::ostream & os, const std::vector & parameters) +rclcpp::operator<<(std::ostream & os, const std::vector & parameters) { os << std::to_string(parameters); return os; } std::string -std::to_string(const rclcpp::parameter::ParameterVariant & param) +std::to_string(const rclcpp::Parameter & param) { std::stringstream ss; ss << "{\"name\": \"" << param.get_name() << "\", "; @@ -167,7 +167,7 @@ std::to_string(const rclcpp::parameter::ParameterVariant & param) } std::string -std::to_string(const std::vector & parameters) +std::to_string(const std::vector & parameters) { std::stringstream ss; ss << "{"; @@ -178,7 +178,7 @@ std::to_string(const std::vector & paramete } else { first = false; } - ss << rclcpp::parameter::_to_json_dict_entry(pv); + ss << rclcpp::_to_json_dict_entry(pv); } ss << "}"; return ss.str(); diff --git a/rclcpp/src/rclcpp/parameter_client.cpp b/rclcpp/src/rclcpp/parameter_client.cpp index d5d218b5de..144d897502 100644 --- a/rclcpp/src/rclcpp/parameter_client.cpp +++ b/rclcpp/src/rclcpp/parameter_client.cpp @@ -114,15 +114,15 @@ AsyncParametersClient::AsyncParametersClient( qos_profile) {} -std::shared_future> +std::shared_future> AsyncParametersClient::get_parameters( const std::vector & names, std::function< - void(std::shared_future>) + void(std::shared_future>) > callback) { auto promise_result = - std::make_shared>>(); + std::make_shared>>(); auto future_result = promise_result->get_future().share(); auto request = std::make_shared(); @@ -133,7 +133,7 @@ AsyncParametersClient::get_parameters( [request, promise_result, future_result, callback]( rclcpp::Client::SharedFuture cb_f) { - std::vector parameter_variants; + std::vector parameters; auto & pvalues = cb_f.get()->values; for (auto & pvalue : pvalues) { @@ -141,11 +141,11 @@ AsyncParametersClient::get_parameters( rcl_interfaces::msg::Parameter parameter; parameter.name = request->names[i]; parameter.value = pvalue; - parameter_variants.push_back(rclcpp::parameter::ParameterVariant::from_parameter( + parameters.push_back(rclcpp::Parameter::from_parameter( parameter)); } - promise_result->set_value(parameter_variants); + promise_result->set_value(parameters); if (callback != nullptr) { callback(future_result); } @@ -191,7 +191,7 @@ AsyncParametersClient::get_parameter_types( std::shared_future> AsyncParametersClient::set_parameters( - const std::vector & parameters, + const std::vector & parameters, std::function< void(std::shared_future>) > callback) @@ -203,7 +203,7 @@ AsyncParametersClient::set_parameters( auto request = std::make_shared(); std::transform(parameters.begin(), parameters.end(), std::back_inserter(request->parameters), - [](rclcpp::parameter::ParameterVariant p) { + [](rclcpp::Parameter p) { return p.to_parameter(); } ); @@ -225,7 +225,7 @@ AsyncParametersClient::set_parameters( std::shared_future AsyncParametersClient::set_parameters_atomically( - const std::vector & parameters, + const std::vector & parameters, std::function< void(std::shared_future) > callback) @@ -237,7 +237,7 @@ AsyncParametersClient::set_parameters_atomically( auto request = std::make_shared(); std::transform(parameters.begin(), parameters.end(), std::back_inserter(request->parameters), - [](rclcpp::parameter::ParameterVariant p) { + [](rclcpp::Parameter p) { return p.to_parameter(); } ); @@ -347,7 +347,7 @@ SyncParametersClient::SyncParametersClient( std::make_shared(node, remote_node_name, qos_profile); } -std::vector +std::vector SyncParametersClient::get_parameters(const std::vector & parameter_names) { auto f = async_parameters_client_->get_parameters(parameter_names); @@ -358,7 +358,7 @@ SyncParametersClient::get_parameters(const std::vector & parameter_ return f.get(); } // Return an empty vector if unsuccessful - return std::vector(); + return std::vector(); } bool @@ -386,7 +386,7 @@ SyncParametersClient::get_parameter_types(const std::vector & param std::vector SyncParametersClient::set_parameters( - const std::vector & parameters) + const std::vector & parameters) { auto f = async_parameters_client_->set_parameters(parameters); @@ -401,7 +401,7 @@ SyncParametersClient::set_parameters( rcl_interfaces::msg::SetParametersResult SyncParametersClient::set_parameters_atomically( - const std::vector & parameters) + const std::vector & parameters) { auto f = async_parameters_client_->set_parameters_atomically(parameters); diff --git a/rclcpp/src/rclcpp/parameter_service.cpp b/rclcpp/src/rclcpp/parameter_service.cpp index 4d8673d87a..fbe2c0a09e 100644 --- a/rclcpp/src/rclcpp/parameter_service.cpp +++ b/rclcpp/src/rclcpp/parameter_service.cpp @@ -70,9 +70,9 @@ ParameterService::ParameterService( const std::shared_ptr request, std::shared_ptr response) { - std::vector pvariants; + std::vector pvariants; for (auto & p : request->parameters) { - pvariants.push_back(rclcpp::parameter::ParameterVariant::from_parameter(p)); + pvariants.push_back(rclcpp::Parameter::from_parameter(p)); } auto results = node_params->set_parameters(pvariants); response->results = results; @@ -87,11 +87,11 @@ ParameterService::ParameterService( const std::shared_ptr request, std::shared_ptr response) { - std::vector pvariants; + std::vector pvariants; std::transform(request->parameters.cbegin(), request->parameters.cend(), std::back_inserter(pvariants), [](const rcl_interfaces::msg::Parameter & p) { - return rclcpp::parameter::ParameterVariant::from_parameter(p); + return rclcpp::Parameter::from_parameter(p); }); auto result = node_params->set_parameters_atomically(pvariants); response->result = result; diff --git a/rclcpp/test/test_parameter.cpp b/rclcpp/test/test_parameter.cpp index e927c079a7..e7e1ce634b 100644 --- a/rclcpp/test/test_parameter.cpp +++ b/rclcpp/test/test_parameter.cpp @@ -34,7 +34,7 @@ class TestParameter : public ::testing::Test TEST(TestParameter, not_set_variant) { // Direct instantiation - rclcpp::parameter::ParameterVariant not_set_variant; + rclcpp::Parameter not_set_variant; EXPECT_EQ(rclcpp::PARAMETER_NOT_SET, not_set_variant.get_type()); EXPECT_EQ("not set", not_set_variant.get_type_name()); @@ -53,13 +53,13 @@ TEST(TestParameter, not_set_variant) { EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET, not_set_param.value.type); // From parameter message - EXPECT_THROW(rclcpp::parameter::ParameterVariant::from_parameter(not_set_param), + EXPECT_THROW(rclcpp::Parameter::from_parameter(not_set_param), std::runtime_error); } TEST(TestParameter, bool_variant) { // Direct instantiation - rclcpp::parameter::ParameterVariant bool_variant_true("bool_param", true); + rclcpp::Parameter bool_variant_true("bool_param", true); EXPECT_EQ("bool_param", bool_variant_true.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BOOL, bool_variant_true.get_type()); EXPECT_EQ("bool", bool_variant_true.get_type_name()); @@ -80,7 +80,7 @@ TEST(TestParameter, bool_variant) { EXPECT_EQ("true", bool_variant_true.value_to_string()); - rclcpp::parameter::ParameterVariant bool_variant_false("bool_param", false); + rclcpp::Parameter bool_variant_false("bool_param", false); EXPECT_FALSE(bool_variant_false.get_value()); EXPECT_FALSE(bool_variant_false.get_value_message().bool_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, @@ -92,8 +92,8 @@ TEST(TestParameter, bool_variant) { EXPECT_TRUE(bool_param.value.bool_value); // From parameter message - rclcpp::parameter::ParameterVariant from_msg_true = - rclcpp::parameter::ParameterVariant::from_parameter(bool_param); + rclcpp::Parameter from_msg_true = + rclcpp::Parameter::from_parameter(bool_param); EXPECT_EQ("bool_param", from_msg_true.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BOOL, from_msg_true.get_type()); EXPECT_EQ("bool", from_msg_true.get_type_name()); @@ -103,8 +103,8 @@ TEST(TestParameter, bool_variant) { bool_variant_false.get_value_message().type); bool_param.value.bool_value = false; - rclcpp::parameter::ParameterVariant from_msg_false = - rclcpp::parameter::ParameterVariant::from_parameter(bool_param); + rclcpp::Parameter from_msg_false = + rclcpp::Parameter::from_parameter(bool_param); EXPECT_FALSE(from_msg_false.get_value()); EXPECT_FALSE(from_msg_false.get_value_message().bool_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, @@ -115,7 +115,7 @@ TEST(TestParameter, integer_variant) { const int TEST_VALUE {42}; // Direct instantiation - rclcpp::parameter::ParameterVariant integer_variant("integer_param", TEST_VALUE); + rclcpp::Parameter integer_variant("integer_param", TEST_VALUE); EXPECT_EQ("integer_param", integer_variant.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, integer_variant.get_type()); EXPECT_EQ("integer", integer_variant.get_type_name()); @@ -143,8 +143,8 @@ TEST(TestParameter, integer_variant) { EXPECT_EQ(TEST_VALUE, integer_param.value.integer_value); // From parameter message - rclcpp::parameter::ParameterVariant from_msg = - rclcpp::parameter::ParameterVariant::from_parameter(integer_param); + rclcpp::Parameter from_msg = + rclcpp::Parameter::from_parameter(integer_param); EXPECT_EQ("integer_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, from_msg.get_type()); EXPECT_EQ("integer", from_msg.get_type_name()); @@ -159,7 +159,7 @@ TEST(TestParameter, long_integer_variant) { const int64_t TEST_VALUE {std::numeric_limits::max()}; // Direct instantiation - rclcpp::parameter::ParameterVariant long_variant("long_integer_param", TEST_VALUE); + rclcpp::Parameter long_variant("long_integer_param", TEST_VALUE); EXPECT_EQ("long_integer_param", long_variant.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, long_variant.get_type()); EXPECT_EQ("integer", long_variant.get_type_name()); @@ -187,8 +187,8 @@ TEST(TestParameter, long_integer_variant) { EXPECT_EQ(TEST_VALUE, integer_param.value.integer_value); // From parameter message - rclcpp::parameter::ParameterVariant from_msg = - rclcpp::parameter::ParameterVariant::from_parameter(integer_param); + rclcpp::Parameter from_msg = + rclcpp::Parameter::from_parameter(integer_param); EXPECT_EQ("long_integer_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, from_msg.get_type()); EXPECT_EQ("integer", from_msg.get_type_name()); @@ -203,7 +203,7 @@ TEST(TestParameter, float_variant) { const float TEST_VALUE {42.0f}; // Direct instantiation - rclcpp::parameter::ParameterVariant float_variant("float_param", TEST_VALUE); + rclcpp::Parameter float_variant("float_param", TEST_VALUE); EXPECT_EQ("float_param", float_variant.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE, float_variant.get_type()); EXPECT_EQ("double", float_variant.get_type_name()); @@ -231,8 +231,8 @@ TEST(TestParameter, float_variant) { EXPECT_EQ(TEST_VALUE, float_param.value.double_value); // From parameter message - rclcpp::parameter::ParameterVariant from_msg = - rclcpp::parameter::ParameterVariant::from_parameter(float_param); + rclcpp::Parameter from_msg = + rclcpp::Parameter::from_parameter(float_param); EXPECT_EQ("float_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE, from_msg.get_type()); EXPECT_EQ("double", from_msg.get_type_name()); @@ -247,7 +247,7 @@ TEST(TestParameter, double_variant) { const double TEST_VALUE {-42.1}; // Direct instantiation - rclcpp::parameter::ParameterVariant double_variant("double_param", TEST_VALUE); + rclcpp::Parameter double_variant("double_param", TEST_VALUE); EXPECT_EQ("double_param", double_variant.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE, double_variant.get_type()); EXPECT_EQ("double", double_variant.get_type_name()); @@ -275,8 +275,8 @@ TEST(TestParameter, double_variant) { EXPECT_EQ(TEST_VALUE, double_param.value.double_value); // From parameter message - rclcpp::parameter::ParameterVariant from_msg = - rclcpp::parameter::ParameterVariant::from_parameter(double_param); + rclcpp::Parameter from_msg = + rclcpp::Parameter::from_parameter(double_param); EXPECT_EQ("double_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE, from_msg.get_type()); EXPECT_EQ("double", from_msg.get_type_name()); @@ -291,7 +291,7 @@ TEST(TestParameter, string_variant) { const std::string TEST_VALUE {"ROS2"}; // Direct instantiation - rclcpp::parameter::ParameterVariant string_variant("string_param", TEST_VALUE); + rclcpp::Parameter string_variant("string_param", TEST_VALUE); EXPECT_EQ("string_param", string_variant.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_STRING, string_variant.get_type()); EXPECT_EQ("string", string_variant.get_type_name()); @@ -319,8 +319,8 @@ TEST(TestParameter, string_variant) { EXPECT_EQ(TEST_VALUE, string_param.value.string_value); // From parameter message - rclcpp::parameter::ParameterVariant from_msg = - rclcpp::parameter::ParameterVariant::from_parameter(string_param); + rclcpp::Parameter from_msg = + rclcpp::Parameter::from_parameter(string_param); EXPECT_EQ("string_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_STRING, from_msg.get_type()); EXPECT_EQ("string", from_msg.get_type_name()); @@ -334,7 +334,7 @@ TEST(TestParameter, byte_array_variant) { const std::vector TEST_VALUE {0x52, 0x4f, 0x53, 0x32}; // Direct instantiation - rclcpp::parameter::ParameterVariant byte_array_variant("byte_array_param", TEST_VALUE); + rclcpp::Parameter byte_array_variant("byte_array_param", TEST_VALUE); EXPECT_EQ("byte_array_param", byte_array_variant.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BYTE_ARRAY, byte_array_variant.get_type()); EXPECT_EQ("byte_array", byte_array_variant.get_type_name()); @@ -362,8 +362,8 @@ TEST(TestParameter, byte_array_variant) { EXPECT_EQ(TEST_VALUE, byte_array_param.value.byte_array_value); // From parameter message - rclcpp::parameter::ParameterVariant from_msg = - rclcpp::parameter::ParameterVariant::from_parameter(byte_array_param); + rclcpp::Parameter from_msg = + rclcpp::Parameter::from_parameter(byte_array_param); EXPECT_EQ("byte_array_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BYTE_ARRAY, from_msg.get_type()); EXPECT_EQ("byte_array", from_msg.get_type_name()); @@ -378,7 +378,7 @@ TEST(TestParameter, bool_array_variant) { const std::vector TEST_VALUE {false, true, true, false, false, true}; // Direct instantiation - rclcpp::parameter::ParameterVariant bool_array_variant("bool_array_param", TEST_VALUE); + rclcpp::Parameter bool_array_variant("bool_array_param", TEST_VALUE); EXPECT_EQ("bool_array_param", bool_array_variant.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BOOL_ARRAY, bool_array_variant.get_type()); EXPECT_EQ("bool_array", bool_array_variant.get_type_name()); @@ -406,8 +406,8 @@ TEST(TestParameter, bool_array_variant) { EXPECT_EQ(TEST_VALUE, bool_array_param.value.bool_array_value); // From parameter message - rclcpp::parameter::ParameterVariant from_msg = - rclcpp::parameter::ParameterVariant::from_parameter(bool_array_param); + rclcpp::Parameter from_msg = + rclcpp::Parameter::from_parameter(bool_array_param); EXPECT_EQ("bool_array_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BOOL_ARRAY, from_msg.get_type()); EXPECT_EQ("bool_array", from_msg.get_type_name()); @@ -423,7 +423,7 @@ TEST(TestParameter, integer_array_variant) { {42, -99, std::numeric_limits::max(), std::numeric_limits::lowest(), 0}; // Direct instantiation - rclcpp::parameter::ParameterVariant integer_array_variant("integer_array_param", TEST_VALUE); + rclcpp::Parameter integer_array_variant("integer_array_param", TEST_VALUE); EXPECT_EQ("integer_array_param", integer_array_variant.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY, @@ -473,8 +473,8 @@ TEST(TestParameter, integer_array_variant) { EXPECT_EQ(param_value.end(), mismatches.second); // From parameter message - rclcpp::parameter::ParameterVariant from_msg = - rclcpp::parameter::ParameterVariant::from_parameter(integer_array_param); + rclcpp::Parameter from_msg = + rclcpp::Parameter::from_parameter(integer_array_param); EXPECT_EQ("integer_array_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY, from_msg.get_type()); EXPECT_EQ("integer_array", from_msg.get_type_name()); @@ -497,7 +497,7 @@ TEST(TestParameter, long_integer_array_variant) { const std::vector TEST_VALUE {42, -99, std::numeric_limits::max(), std::numeric_limits::lowest(), 0}; - rclcpp::parameter::ParameterVariant long_array_variant("long_integer_array_param", TEST_VALUE); + rclcpp::Parameter long_array_variant("long_integer_array_param", TEST_VALUE); EXPECT_EQ("long_integer_array_param", long_array_variant.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY, long_array_variant.get_type()); @@ -529,8 +529,8 @@ TEST(TestParameter, long_integer_array_variant) { EXPECT_EQ(TEST_VALUE, integer_array_param.value.integer_array_value); // From parameter message - rclcpp::parameter::ParameterVariant from_msg = - rclcpp::parameter::ParameterVariant::from_parameter(integer_array_param); + rclcpp::Parameter from_msg = + rclcpp::Parameter::from_parameter(integer_array_param); EXPECT_EQ("long_integer_array_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY, from_msg.get_type()); EXPECT_EQ("integer_array", from_msg.get_type_name()); @@ -546,7 +546,7 @@ TEST(TestParameter, float_array_variant) { {42.1f, -99.1f, std::numeric_limits::max(), std::numeric_limits::lowest(), 0.1f}; // Direct instantiation - rclcpp::parameter::ParameterVariant float_array_variant("float_array_param", TEST_VALUE); + rclcpp::Parameter float_array_variant("float_array_param", TEST_VALUE); EXPECT_EQ("float_array_param", float_array_variant.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY, @@ -596,8 +596,8 @@ TEST(TestParameter, float_array_variant) { EXPECT_EQ(param_value.end(), mismatches.second); // From parameter message - rclcpp::parameter::ParameterVariant from_msg = - rclcpp::parameter::ParameterVariant::from_parameter(float_array_param); + rclcpp::Parameter from_msg = + rclcpp::Parameter::from_parameter(float_array_param); EXPECT_EQ("float_array_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY, from_msg.get_type()); EXPECT_EQ("double_array", from_msg.get_type_name()); @@ -620,7 +620,7 @@ TEST(TestParameter, double_array_variant) { const std::vector TEST_VALUE {42.1, -99.1, std::numeric_limits::max(), std::numeric_limits::lowest(), 0.1}; - rclcpp::parameter::ParameterVariant double_array_variant("double_array_param", TEST_VALUE); + rclcpp::Parameter double_array_variant("double_array_param", TEST_VALUE); EXPECT_EQ("double_array_param", double_array_variant.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY, double_array_variant.get_type()); @@ -652,8 +652,8 @@ TEST(TestParameter, double_array_variant) { EXPECT_EQ(TEST_VALUE, double_array_param.value.double_array_value); // From parameter message - rclcpp::parameter::ParameterVariant from_msg = - rclcpp::parameter::ParameterVariant::from_parameter(double_array_param); + rclcpp::Parameter from_msg = + rclcpp::Parameter::from_parameter(double_array_param); EXPECT_EQ("double_array_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY, from_msg.get_type()); EXPECT_EQ("double_array", from_msg.get_type_name()); @@ -668,7 +668,7 @@ TEST(TestParameter, string_array_variant) { const std::vector TEST_VALUE {"R", "O", "S2"}; // Direct instantiation - rclcpp::parameter::ParameterVariant string_array_variant("string_array_param", TEST_VALUE); + rclcpp::Parameter string_array_variant("string_array_param", TEST_VALUE); EXPECT_EQ("string_array_param", string_array_variant.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_STRING_ARRAY, string_array_variant.get_type()); @@ -698,8 +698,8 @@ TEST(TestParameter, string_array_variant) { EXPECT_EQ(TEST_VALUE, string_array_param.value.string_array_value); // From parameter message - rclcpp::parameter::ParameterVariant from_msg = - rclcpp::parameter::ParameterVariant::from_parameter(string_array_param); + rclcpp::Parameter from_msg = + rclcpp::Parameter::from_parameter(string_array_param); EXPECT_EQ("string_array_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_STRING_ARRAY, from_msg.get_type()); EXPECT_EQ("string_array", from_msg.get_type_name()); diff --git a/rclcpp/test/test_time_source.cpp b/rclcpp/test/test_time_source.cpp index ff9e02cfbc..0edc35dbe7 100644 --- a/rclcpp/test/test_time_source.cpp +++ b/rclcpp/test/test_time_source.cpp @@ -339,7 +339,7 @@ TEST_F(TestTimeSource, parameter_activation) { using namespace std::chrono_literals; EXPECT_TRUE(parameters_client->wait_for_service(2s)); auto set_parameters_results = parameters_client->set_parameters({ - rclcpp::parameter::ParameterVariant("use_sim_time", true) + rclcpp::Parameter("use_sim_time", true) }); for (auto & result : set_parameters_results) { EXPECT_TRUE(result.successful); @@ -349,7 +349,7 @@ TEST_F(TestTimeSource, parameter_activation) { set_parameters_results = parameters_client->set_parameters({ - rclcpp::parameter::ParameterVariant("use_sim_time", rclcpp::ParameterType::PARAMETER_NOT_SET) + rclcpp::Parameter("use_sim_time", rclcpp::ParameterType::PARAMETER_NOT_SET) }); for (auto & result : set_parameters_results) { EXPECT_TRUE(result.successful); @@ -357,7 +357,7 @@ TEST_F(TestTimeSource, parameter_activation) { EXPECT_TRUE(ros_clock->ros_time_is_active()); set_parameters_results = parameters_client->set_parameters({ - rclcpp::parameter::ParameterVariant("use_sim_time", false) + rclcpp::Parameter("use_sim_time", false) }); for (auto & result : set_parameters_results) { EXPECT_TRUE(result.successful); @@ -365,7 +365,7 @@ TEST_F(TestTimeSource, parameter_activation) { EXPECT_FALSE(ros_clock->ros_time_is_active()); set_parameters_results = parameters_client->set_parameters({ - rclcpp::parameter::ParameterVariant("use_sim_time", rclcpp::ParameterType::PARAMETER_NOT_SET) + rclcpp::Parameter("use_sim_time", rclcpp::ParameterType::PARAMETER_NOT_SET) }); for (auto & result : set_parameters_results) { EXPECT_TRUE(result.successful); diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp index ace2f7c69a..695eb8ab6d 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp @@ -252,25 +252,25 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface, RCLCPP_LIFECYCLE_PUBLIC std::vector - set_parameters(const std::vector & parameters); + set_parameters(const std::vector & parameters); RCLCPP_LIFECYCLE_PUBLIC rcl_interfaces::msg::SetParametersResult - set_parameters_atomically(const std::vector & parameters); + set_parameters_atomically(const std::vector & parameters); RCLCPP_LIFECYCLE_PUBLIC - std::vector + std::vector get_parameters(const std::vector & names) const; RCLCPP_LIFECYCLE_PUBLIC - rclcpp::parameter::ParameterVariant + rclcpp::Parameter get_parameter(const std::string & name) const; RCLCPP_LIFECYCLE_PUBLIC bool get_parameter( const std::string & name, - rclcpp::parameter::ParameterVariant & parameter) const; + rclcpp::Parameter & parameter) const; template bool diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp index a47e0d4cc9..6b683e4a2a 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node_impl.hpp @@ -186,9 +186,9 @@ template bool LifecycleNode::get_parameter(const std::string & name, ParameterT & parameter) const { - rclcpp::parameter::ParameterVariant parameter_variant(name, parameter); - bool result = get_parameter(name, parameter_variant); - parameter = parameter_variant.get_value(); + rclcpp::Parameter param(name, parameter); + bool result = get_parameter(name, param); + parameter = param.get_value(); return result; } diff --git a/rclcpp_lifecycle/src/lifecycle_node.cpp b/rclcpp_lifecycle/src/lifecycle_node.cpp index c58d082272..fe1a31c61d 100644 --- a/rclcpp_lifecycle/src/lifecycle_node.cpp +++ b/rclcpp_lifecycle/src/lifecycle_node.cpp @@ -137,26 +137,26 @@ LifecycleNode::group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr gr std::vector LifecycleNode::set_parameters( - const std::vector & parameters) + const std::vector & parameters) { return node_parameters_->set_parameters(parameters); } rcl_interfaces::msg::SetParametersResult LifecycleNode::set_parameters_atomically( - const std::vector & parameters) + const std::vector & parameters) { return node_parameters_->set_parameters_atomically(parameters); } -std::vector +std::vector LifecycleNode::get_parameters( const std::vector & names) const { return node_parameters_->get_parameters(names); } -rclcpp::parameter::ParameterVariant +rclcpp::Parameter LifecycleNode::get_parameter(const std::string & name) const { return node_parameters_->get_parameter(name); @@ -164,7 +164,7 @@ LifecycleNode::get_parameter(const std::string & name) const bool LifecycleNode::get_parameter( const std::string & name, - rclcpp::parameter::ParameterVariant & parameter) const + rclcpp::Parameter & parameter) const { return node_parameters_->get_parameter(name, parameter); }