From 9e9f37cd8caa8e02496c6502551c10acf8dc8d79 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 25 May 2018 16:05:26 -0700 Subject: [PATCH 01/17] Moved ParameterType + started ParameterValue --- rclcpp/CMakeLists.txt | 1 + rclcpp/include/rclcpp/parameter.hpp | 15 +- rclcpp/include/rclcpp/parameter_client.hpp | 8 +- rclcpp/include/rclcpp/parameter_value.hpp | 356 ++++++++++++++++++ .../node_interfaces/node_parameters.cpp | 4 +- rclcpp/src/rclcpp/parameter.cpp | 50 +-- rclcpp/src/rclcpp/parameter_client.cpp | 14 +- rclcpp/src/rclcpp/parameter_service.cpp | 2 +- rclcpp/src/rclcpp/parameter_value.cpp | 278 ++++++++++++++ rclcpp/src/rclcpp/time_source.cpp | 2 +- rclcpp/test/test_parameter.cpp | 110 +++--- rclcpp/test/test_time_source.cpp | 4 +- 12 files changed, 720 insertions(+), 124 deletions(-) create mode 100644 rclcpp/include/rclcpp/parameter_value.hpp create mode 100644 rclcpp/src/rclcpp/parameter_value.cpp diff --git a/rclcpp/CMakeLists.txt b/rclcpp/CMakeLists.txt index 523ca3f7a8..aedd403f3f 100644 --- a/rclcpp/CMakeLists.txt +++ b/rclcpp/CMakeLists.txt @@ -58,6 +58,7 @@ set(${PROJECT_NAME}_SRCS src/rclcpp/node_interfaces/node_timers.cpp src/rclcpp/node_interfaces/node_topics.cpp src/rclcpp/parameter.cpp + src/rclcpp/parameter_value.cpp src/rclcpp/parameter_client.cpp src/rclcpp/parameter_events_filter.cpp src/rclcpp/parameter_service.cpp diff --git a/rclcpp/include/rclcpp/parameter.hpp b/rclcpp/include/rclcpp/parameter.hpp index e180203e55..bc61e61f65 100644 --- a/rclcpp/include/rclcpp/parameter.hpp +++ b/rclcpp/include/rclcpp/parameter.hpp @@ -24,6 +24,7 @@ #include "rcl_interfaces/msg/parameter.hpp" #include "rcl_interfaces/msg/parameter_type.hpp" #include "rcl_interfaces/msg/parameter_value.hpp" +#include "rclcpp/parameter_value.hpp" #include "rclcpp/visibility_control.hpp" #include "rmw/rmw.h" @@ -32,20 +33,6 @@ namespace rclcpp namespace parameter { -enum ParameterType -{ - PARAMETER_NOT_SET = rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET, - PARAMETER_BOOL = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, - PARAMETER_INTEGER = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, - PARAMETER_DOUBLE = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE, - PARAMETER_STRING = rcl_interfaces::msg::ParameterType::PARAMETER_STRING, - PARAMETER_BYTE_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY, - PARAMETER_BOOL_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY, - PARAMETER_INTEGER_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY, - PARAMETER_DOUBLE_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY, - PARAMETER_STRING_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY, -}; - // Structure to store an arbitrary parameter with templated get/set methods class ParameterVariant { diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 2e36aba87d..a9442b0173 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -76,11 +76,11 @@ class AsyncParametersClient > callback = nullptr); RCLCPP_PUBLIC - std::shared_future> + std::shared_future> get_parameter_types( const std::vector & names, std::function< - void(std::shared_future>) + void(std::shared_future>) > callback = nullptr); RCLCPP_PUBLIC @@ -200,7 +200,7 @@ class SyncParametersClient std::vector names; names.push_back(parameter_name); auto vars = get_parameters(names); - if ((vars.size() != 1) || (vars[0].get_type() == rclcpp::parameter::PARAMETER_NOT_SET)) { + if ((vars.size() != 1) || (vars[0].get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET)) { return parameter_not_found_handler(); } else { return static_cast(vars[0].get_value()); @@ -226,7 +226,7 @@ class SyncParametersClient } RCLCPP_PUBLIC - std::vector + std::vector get_parameter_types(const std::vector & parameter_names); RCLCPP_PUBLIC diff --git a/rclcpp/include/rclcpp/parameter_value.hpp b/rclcpp/include/rclcpp/parameter_value.hpp new file mode 100644 index 0000000000..d02f3b84ae --- /dev/null +++ b/rclcpp/include/rclcpp/parameter_value.hpp @@ -0,0 +1,356 @@ +// Copyright 2018 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef RCLCPP__PARAMETER_VALUE_HPP_ +#define RCLCPP__PARAMETER_VALUE_HPP_ + +#include +#include +#include +#include +#include +#include + +#include "rcl_interfaces/msg/parameter_type.hpp" +#include "rcl_interfaces/msg/parameter_value.hpp" +#include "rclcpp/visibility_control.hpp" +#include "rmw/rmw.h" + +namespace rclcpp +{ +enum ParameterType +{ + PARAMETER_NOT_SET = rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET, + PARAMETER_BOOL = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, + PARAMETER_INTEGER = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, + PARAMETER_DOUBLE = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE, + PARAMETER_STRING = rcl_interfaces::msg::ParameterType::PARAMETER_STRING, + PARAMETER_BYTE_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY, + PARAMETER_BOOL_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY, + PARAMETER_INTEGER_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY, + PARAMETER_DOUBLE_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY, + PARAMETER_STRING_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY, +}; + +/// Return the name of a parameter type +RCLCPP_PUBLIC +std::string +to_string(const ParameterType type); + +RCLCPP_PUBLIC +std::ostream & +operator<<(std::ostream & os, const ParameterType type); + +/// Indicate the parameter type does not match the expected type. +class ParameterTypeException : public std::exception +{ +public: + /// Construct an instance. + /// \param[in] expected the expected parameter type. + /// \param[in] actual the actual parameter type. + ParameterTypeException(ParameterType expected, ParameterType actual); + + ~ParameterTypeException(); + + const char * + what() const noexcept override; + +private: + const std::string msg_; +}; + +/// Store the type and value of a parameter. +class ParameterValue +{ +public: + /// Construct a parameter value with type PARAMETER_NOT_SET. + RCLCPP_PUBLIC + ParameterValue(); + /// Construct a parameter value from a message. + RCLCPP_PUBLIC + explicit ParameterValue(const rcl_interfaces::msg::ParameterValue & value); + /// Construct a parameter value with type PARAMETER_BOOL. + RCLCPP_PUBLIC + explicit ParameterValue(const bool bool_value); + /// Construct a parameter value with type PARAMETER_INTEGER. + RCLCPP_PUBLIC + explicit ParameterValue(const int int_value); + /// Construct a parameter value with type PARAMETER_INTEGER. + RCLCPP_PUBLIC + explicit ParameterValue(const int64_t int_value); + /// Construct a parameter value with type PARAMETER_DOUBLE. + RCLCPP_PUBLIC + explicit ParameterValue(const float double_value); + /// Construct a parameter value with type PARAMETER_DOUBLE. + RCLCPP_PUBLIC + explicit ParameterValue(const double double_value); + /// Construct a parameter value with type PARAMETER_STRING. + RCLCPP_PUBLIC + explicit ParameterValue(const std::string & string_value); + /// Construct a parameter value with type PARAMETER_STRING. + RCLCPP_PUBLIC + explicit ParameterValue(const char * string_value); + /// Construct a parameter value with type PARAMETER_BYTE_ARRAY. + RCLCPP_PUBLIC + explicit ParameterValue(const std::vector & byte_array_value); + /// Construct a parameter value with type PARAMETER_BOOL_ARRAY. + RCLCPP_PUBLIC + explicit ParameterValue(const std::vector & bool_array_value); + /// Construct a parameter value with type PARAMETER_INTEGER_ARRAY. + RCLCPP_PUBLIC + explicit ParameterValue(const std::vector & int_array_value); + /// Construct a parameter value with type PARAMETER_INTEGER_ARRAY. + RCLCPP_PUBLIC + explicit ParameterValue(const std::vector & int_array_value); + /// Construct a parameter value with type PARAMETER_DOUBLE_ARRAY. + RCLCPP_PUBLIC + explicit ParameterValue(const std::vector & double_array_value); + /// Construct a parameter value with type PARAMETER_DOUBLE_ARRAY. + RCLCPP_PUBLIC + explicit ParameterValue(const std::vector & double_array_value); + /// Construct a parameter value with type PARAMETER_STRING_ARRAY. + RCLCPP_PUBLIC + explicit ParameterValue(const std::vector & string_array_value); + + /// Return an enum indicating the type of the set value. + RCLCPP_PUBLIC + ParameterType + get_type() const; + + /// Return a message populated with the parameter value + RCLCPP_PUBLIC + rcl_interfaces::msg::ParameterValue + get_value_message() const; + + // The following get() variants require the use of ParameterType + + template + typename std::enable_if::type + get() const + { + if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) { + throw ParameterTypeException(ParameterType::PARAMETER_BOOL, get_type()); + } + return value_.bool_value; + } + + template + typename std::enable_if::type + get() const + { + if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER) { + throw ParameterTypeException(ParameterType::PARAMETER_INTEGER, get_type()); + } + return value_.integer_value; + } + + template + typename std::enable_if::type + get() const + { + if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) { + throw ParameterTypeException(ParameterType::PARAMETER_DOUBLE, get_type()); + } + return value_.double_value; + } + + template + typename std::enable_if::type + get() const + { + if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_STRING) { + throw ParameterTypeException(ParameterType::PARAMETER_STRING, get_type()); + } + return value_.string_value; + } + + template + typename std::enable_if< + type == ParameterType::PARAMETER_BYTE_ARRAY, const std::vector &>::type + get() const + { + if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY) { + throw ParameterTypeException(ParameterType::PARAMETER_BYTE_ARRAY, get_type()); + } + return value_.byte_array_value; + } + + template + typename std::enable_if< + type == ParameterType::PARAMETER_BOOL_ARRAY, const std::vector &>::type + get() const + { + if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY) { + throw ParameterTypeException(ParameterType::PARAMETER_BOOL_ARRAY, get_type()); + } + return value_.bool_array_value; + } + + template + typename std::enable_if< + type == ParameterType::PARAMETER_INTEGER_ARRAY, const std::vector &>::type + get() const + { + if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY) { + throw ParameterTypeException(ParameterType::PARAMETER_INTEGER_ARRAY, get_type()); + } + return value_.integer_array_value; + } + + template + typename std::enable_if< + type == ParameterType::PARAMETER_DOUBLE_ARRAY, const std::vector &>::type + get() const + { + if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY) { + throw ParameterTypeException(ParameterType::PARAMETER_DOUBLE_ARRAY, get_type()); + } + return value_.double_array_value; + } + + template + typename std::enable_if< + type == ParameterType::PARAMETER_STRING_ARRAY, const std::vector &>::type + get() const + { + if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY) { + throw ParameterTypeException(ParameterType::PARAMETER_STRING_ARRAY, get_type()); + } + return value_.string_array_value; + } + + // The following get() variants allow the use of primitive types + + template + typename std::enable_if::value, bool>::type + get() const + { + return get(); + } + + template + typename std::enable_if< + std::is_integral::value && !std::is_same::value, int64_t>::type + get() const + { + return get(); + } + + template + typename std::enable_if::value, double>::type + get() const + { + return get(); + } + + template + typename std::enable_if::value, const std::string &>::type + get() const + { + return get(); + } + + template + typename std::enable_if< + std::is_convertible< + type, const std::vector &>::value, const std::vector &>::type + get() const + { + return get(); + } + + template + typename std::enable_if< + std::is_convertible< + type, const std::vector &>::value, const std::vector &>::type + get() const + { + return get(); + } + + template + typename std::enable_if< + std::is_convertible< + type, const std::vector &>::value, const std::vector &>::type + get() const + { + return get(); + } + + template + typename std::enable_if< + std::is_convertible< + type, const std::vector &>::value, const std::vector &>::type + get() const + { + return get(); + } + + template + typename std::enable_if< + std::is_convertible< + type, const std::vector &>::value, const std::vector &>::type + get() const + { + return get(); + } + + RCLCPP_PUBLIC + bool + as_bool() const; + + RCLCPP_PUBLIC + int64_t + as_int() const; + + RCLCPP_PUBLIC + double + as_double() const; + + RCLCPP_PUBLIC + const std::string & + as_string() const; + + RCLCPP_PUBLIC + const std::vector & + as_byte_array() const; + + RCLCPP_PUBLIC + const std::vector & + as_bool_array() const; + + RCLCPP_PUBLIC + const std::vector & + as_integer_array() const; + + RCLCPP_PUBLIC + const std::vector & + as_double_array() const; + + RCLCPP_PUBLIC + const std::vector & + as_string_array() const; + +private: + rcl_interfaces::msg::ParameterValue value_; +}; + +/// Return the value of a parameter as a string +RCLCPP_PUBLIC +std::string +to_string(const ParameterType type); + +} // namespace rclcpp + +#endif // RCLCPP__PARAMETER_VALUE_HPP_ diff --git a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp index 2fd4605032..6033c48f26 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp @@ -89,11 +89,11 @@ NodeParameters::set_parameters_atomically( for (auto p : parameters) { if (parameters_.find(p.get_name()) == parameters_.end()) { - if (p.get_type() != rclcpp::parameter::ParameterType::PARAMETER_NOT_SET) { + if (p.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET) { // case: parameter not set before, and input is something other than "NOT_SET" parameter_event->new_parameters.push_back(p.to_parameter()); } - } else if (p.get_type() != rclcpp::parameter::ParameterType::PARAMETER_NOT_SET) { + } else if (p.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET) { // case: parameter was set before, and input is something other than "NOT_SET" parameter_event->changed_parameters.push_back(p.to_parameter()); } else { diff --git a/rclcpp/src/rclcpp/parameter.cpp b/rclcpp/src/rclcpp/parameter.cpp index 0adcef77f0..8409d3484c 100644 --- a/rclcpp/src/rclcpp/parameter.cpp +++ b/rclcpp/src/rclcpp/parameter.cpp @@ -20,7 +20,7 @@ #include "rclcpp/parameter.hpp" #include "rclcpp/utilities.hpp" -using rclcpp::parameter::ParameterType; +using rclcpp::ParameterType; using rclcpp::parameter::ParameterVariant; ParameterVariant::ParameterVariant() @@ -140,33 +140,7 @@ ParameterVariant::get_type() const std::string ParameterVariant::get_type_name() const { - switch (get_type()) { - case rclcpp::parameter::ParameterType::PARAMETER_NOT_SET: - return "not set"; - case rclcpp::parameter::ParameterType::PARAMETER_BOOL: - return "bool"; - case rclcpp::parameter::ParameterType::PARAMETER_INTEGER: - return "integer"; - case rclcpp::parameter::ParameterType::PARAMETER_DOUBLE: - return "double"; - case rclcpp::parameter::ParameterType::PARAMETER_STRING: - return "string"; - case rclcpp::parameter::ParameterType::PARAMETER_BYTE_ARRAY: - return "byte_array"; - case rclcpp::parameter::ParameterType::PARAMETER_BOOL_ARRAY: - return "bool_array"; - case rclcpp::parameter::ParameterType::PARAMETER_INTEGER_ARRAY: - return "integer_array"; - case rclcpp::parameter::ParameterType::PARAMETER_DOUBLE_ARRAY: - return "double_array"; - case rclcpp::parameter::ParameterType::PARAMETER_STRING_ARRAY: - return "string_array"; - default: - // *INDENT-OFF* (prevent uncrustify from making unnecessary indents here) - throw std::runtime_error( - "Unexpected type from ParameterVariant: " + std::to_string(get_type())); - // *INDENT-ON* - } + return rclcpp::to_string(get_type()); } const std::string & @@ -281,25 +255,25 @@ std::string ParameterVariant::value_to_string() const { switch (get_type()) { - case rclcpp::parameter::ParameterType::PARAMETER_NOT_SET: + case ParameterType::PARAMETER_NOT_SET: return "not set"; - case rclcpp::parameter::ParameterType::PARAMETER_BOOL: + case ParameterType::PARAMETER_BOOL: return as_bool() ? "true" : "false"; - case rclcpp::parameter::ParameterType::PARAMETER_INTEGER: + case ParameterType::PARAMETER_INTEGER: return std::to_string(as_int()); - case rclcpp::parameter::ParameterType::PARAMETER_DOUBLE: + case ParameterType::PARAMETER_DOUBLE: return std::to_string(as_double()); - case rclcpp::parameter::ParameterType::PARAMETER_STRING: + case ParameterType::PARAMETER_STRING: return as_string(); - case rclcpp::parameter::ParameterType::PARAMETER_BYTE_ARRAY: + case ParameterType::PARAMETER_BYTE_ARRAY: return array_to_string(as_byte_array(), std::ios::hex); - case rclcpp::parameter::ParameterType::PARAMETER_BOOL_ARRAY: + case ParameterType::PARAMETER_BOOL_ARRAY: return array_to_string(as_bool_array(), std::ios::boolalpha); - case rclcpp::parameter::ParameterType::PARAMETER_INTEGER_ARRAY: + case ParameterType::PARAMETER_INTEGER_ARRAY: return array_to_string(as_integer_array()); - case rclcpp::parameter::ParameterType::PARAMETER_DOUBLE_ARRAY: + case ParameterType::PARAMETER_DOUBLE_ARRAY: return array_to_string(as_double_array()); - case rclcpp::parameter::ParameterType::PARAMETER_STRING_ARRAY: + case ParameterType::PARAMETER_STRING_ARRAY: return array_to_string(as_string_array()); default: // *INDENT-OFF* (prevent uncrustify from making unnecessary indents here) diff --git a/rclcpp/src/rclcpp/parameter_client.cpp b/rclcpp/src/rclcpp/parameter_client.cpp index 18dad919b3..d5d218b5de 100644 --- a/rclcpp/src/rclcpp/parameter_client.cpp +++ b/rclcpp/src/rclcpp/parameter_client.cpp @@ -155,15 +155,15 @@ AsyncParametersClient::get_parameters( return future_result; } -std::shared_future> +std::shared_future> AsyncParametersClient::get_parameter_types( 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(); @@ -174,10 +174,10 @@ AsyncParametersClient::get_parameter_types( [promise_result, future_result, callback]( rclcpp::Client::SharedFuture cb_f) { - std::vector types; + std::vector types; auto & pts = cb_f.get()->types; for (auto & pt : pts) { - pts.push_back(static_cast(pt)); + pts.push_back(static_cast(pt)); } promise_result->set_value(types); if (callback != nullptr) { @@ -370,7 +370,7 @@ SyncParametersClient::has_parameter(const std::string & parameter_name) return vars.names.size() > 0; } -std::vector +std::vector SyncParametersClient::get_parameter_types(const std::vector & parameter_names) { auto f = async_parameters_client_->get_parameter_types(parameter_names); @@ -381,7 +381,7 @@ SyncParametersClient::get_parameter_types(const std::vector & param { return f.get(); } - return std::vector(); + return std::vector(); } std::vector diff --git a/rclcpp/src/rclcpp/parameter_service.cpp b/rclcpp/src/rclcpp/parameter_service.cpp index 97a268c3ae..c4e224e5d2 100644 --- a/rclcpp/src/rclcpp/parameter_service.cpp +++ b/rclcpp/src/rclcpp/parameter_service.cpp @@ -57,7 +57,7 @@ ParameterService::ParameterService( auto types = node_params->get_parameter_types(request->names); std::transform(types.cbegin(), types.cend(), std::back_inserter(response->types), [](const uint8_t & type) { - return static_cast(type); + return static_cast(type); }); }, qos_profile, nullptr); diff --git a/rclcpp/src/rclcpp/parameter_value.cpp b/rclcpp/src/rclcpp/parameter_value.cpp new file mode 100644 index 0000000000..339931379b --- /dev/null +++ b/rclcpp/src/rclcpp/parameter_value.cpp @@ -0,0 +1,278 @@ +// Copyright 2018 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "rclcpp/parameter_value.hpp" + +#include +#include + +using rclcpp::ParameterType; +using rclcpp::ParameterTypeException; +using rclcpp::ParameterValue; + +std::string +rclcpp::to_string(const ParameterType type) +{ + switch (type) { + case ParameterType::PARAMETER_NOT_SET: + return "not set"; + case ParameterType::PARAMETER_BOOL: + return "bool"; + case ParameterType::PARAMETER_INTEGER: + return "integer"; + case ParameterType::PARAMETER_DOUBLE: + return "double"; + case ParameterType::PARAMETER_STRING: + return "string"; + case ParameterType::PARAMETER_BYTE_ARRAY: + return "byte_array"; + case ParameterType::PARAMETER_BOOL_ARRAY: + return "bool_array"; + case ParameterType::PARAMETER_INTEGER_ARRAY: + return "integer_array"; + case ParameterType::PARAMETER_DOUBLE_ARRAY: + return "double_array"; + case ParameterType::PARAMETER_STRING_ARRAY: + return "string_array"; + default: + return "unknown type"; + } +} + +std::ostream & +rclcpp::operator<<(std::ostream & os, const ParameterType type) +{ + os << rclcpp::to_string(type); + return os; +} + +ParameterTypeException::ParameterTypeException(ParameterType expected, ParameterType actual) +: msg_("expected [" + rclcpp::to_string(expected) + "] got [" + rclcpp::to_string(actual) + "]") +{ +} + +ParameterTypeException::~ParameterTypeException() +{ +} + +const char * +ParameterTypeException::what() const throw () +{ + return msg_.c_str(); +} + +template +std::string +array_to_string( + const std::vector & array, + const std::ios::fmtflags format_flags = std::ios::dec) +{ + std::stringstream type_array; + bool first_item = true; + type_array << "["; + type_array.setf(format_flags, std::ios_base::basefield | std::ios::boolalpha); + type_array << std::showbase; + for (const ValType value : array) { + if (!first_item) { + type_array << ", "; + } else { + first_item = false; + } + type_array << static_cast(value); + } + type_array << "]"; + return type_array.str(); +} + +std::string +to_string(const ParameterValue & value) +{ + switch (value.get_type()) { + case ParameterType::PARAMETER_NOT_SET: + return "not set"; + case ParameterType::PARAMETER_BOOL: + return value.as_bool() ? "true" : "false"; + case ParameterType::PARAMETER_INTEGER: + return std::to_string(value.as_int()); + case ParameterType::PARAMETER_DOUBLE: + return std::to_string(value.as_double()); + case ParameterType::PARAMETER_STRING: + return value.as_string(); + case ParameterType::PARAMETER_BYTE_ARRAY: + return array_to_string(value.as_byte_array(), std::ios::hex); + case ParameterType::PARAMETER_BOOL_ARRAY: + return array_to_string(value.as_bool_array(), std::ios::boolalpha); + case ParameterType::PARAMETER_INTEGER_ARRAY: + return array_to_string(value.as_integer_array()); + case ParameterType::PARAMETER_DOUBLE_ARRAY: + return array_to_string(value.as_double_array()); + case ParameterType::PARAMETER_STRING_ARRAY: + return array_to_string(value.as_string_array()); + default: + return "unknown type"; + } +} + +ParameterValue::ParameterValue() +{ + value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET; +} + +ParameterValue::ParameterValue(const bool bool_value) +{ + value_.bool_value = bool_value; + value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; +} + +ParameterValue::ParameterValue(const int int_value) +{ + value_.integer_value = int_value; + value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; +} + +ParameterValue::ParameterValue(const int64_t int_value) +{ + value_.integer_value = int_value; + value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; +} + +ParameterValue::ParameterValue(const float double_value) +{ + value_.double_value = double_value; + value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; +} + +ParameterValue::ParameterValue(const double double_value) +{ + value_.double_value = double_value; + value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; +} + +ParameterValue::ParameterValue(const std::string & string_value) +{ + value_.string_value = string_value; + value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; +} + +ParameterValue::ParameterValue(const char * string_value) +: ParameterValue(std::string(string_value)) +{} + +ParameterValue::ParameterValue(const std::vector & byte_array_value) +{ + value_.byte_array_value = byte_array_value; + value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY; +} + +ParameterValue::ParameterValue(const std::vector & bool_array_value) +{ + value_.bool_array_value = bool_array_value; + value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY; +} + +ParameterValue::ParameterValue(const std::vector & int_array_value) +{ + value_.integer_array_value.assign(int_array_value.cbegin(), int_array_value.cend()); + value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY; +} + +ParameterValue::ParameterValue(const std::vector & int_array_value) +{ + value_.integer_array_value = int_array_value; + value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY; +} + +ParameterValue::ParameterValue(const std::vector & double_array_value) +{ + value_.integer_array_value.assign(double_array_value.cbegin(), double_array_value.cend()); + value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY; +} + +ParameterValue::ParameterValue(const std::vector & double_array_value) +{ + value_.double_array_value = double_array_value; + value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY; +} + +ParameterValue::ParameterValue(const std::vector & string_array_value) +{ + value_.string_array_value = string_array_value; + value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY; +} + +ParameterType +ParameterValue::get_type() const +{ + return static_cast(value_.type); +} + +rcl_interfaces::msg::ParameterValue +ParameterValue::get_value_message() const +{ + return value_; +} + +bool +ParameterValue::as_bool() const +{ + return get(); +} + +int64_t +ParameterValue::as_int() const +{ + return get(); +} + +double +ParameterValue::as_double() const +{ + return get(); +} + +const std::string & +ParameterValue::as_string() const +{ + return get(); +} + +const std::vector & +ParameterValue::as_byte_array() const +{ + return get(); +} + +const std::vector & +ParameterValue::as_bool_array() const +{ + return get(); +} + +const std::vector & +ParameterValue::as_integer_array() const +{ + return get(); +} + +const std::vector & +ParameterValue::as_double_array() const +{ + return get(); +} + +const std::vector & +ParameterValue::as_string_array() const +{ + return get(); +} diff --git a/rclcpp/src/rclcpp/time_source.cpp b/rclcpp/src/rclcpp/time_source.cpp index 54c72dbdc4..543e98a94b 100644 --- a/rclcpp/src/rclcpp/time_source.cpp +++ b/rclcpp/src/rclcpp/time_source.cpp @@ -215,7 +215,7 @@ void TimeSource::on_parameter_event(const rcl_interfaces::msg::ParameterEvent::S {rclcpp::ParameterEventsFilter::EventType::NEW, rclcpp::ParameterEventsFilter::EventType::CHANGED}); for (auto & it : filter.get_events()) { - if (it.second->value.type != parameter::ParameterType::PARAMETER_BOOL) { + if (it.second->value.type != ParameterType::PARAMETER_BOOL) { RCUTILS_LOG_ERROR("use_sim_time parameter set to something besides a bool"); continue; } diff --git a/rclcpp/test/test_parameter.cpp b/rclcpp/test/test_parameter.cpp index bcac352bdc..3ee85e7d0c 100644 --- a/rclcpp/test/test_parameter.cpp +++ b/rclcpp/test/test_parameter.cpp @@ -35,7 +35,7 @@ class TestParameter : public ::testing::Test TEST(TestParameter, not_set_variant) { // Direct instantiation rclcpp::parameter::ParameterVariant not_set_variant; - EXPECT_EQ(rclcpp::parameter::PARAMETER_NOT_SET, not_set_variant.get_type()); + EXPECT_EQ(rclcpp::PARAMETER_NOT_SET, not_set_variant.get_type()); EXPECT_EQ("not set", not_set_variant.get_type_name()); EXPECT_THROW(not_set_variant.as_bool(), std::runtime_error); @@ -61,9 +61,9 @@ TEST(TestParameter, bool_variant) { // Direct instantiation rclcpp::parameter::ParameterVariant bool_variant_true("bool_param", true); EXPECT_EQ("bool_param", bool_variant_true.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_BOOL, bool_variant_true.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BOOL, bool_variant_true.get_type()); EXPECT_EQ("bool", bool_variant_true.get_type_name()); - EXPECT_TRUE(bool_variant_true.get_value()); + EXPECT_TRUE(bool_variant_true.get_value()); EXPECT_TRUE(bool_variant_true.get_parameter_value().bool_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, bool_variant_true.get_parameter_value().type); @@ -81,7 +81,7 @@ TEST(TestParameter, bool_variant) { EXPECT_EQ("true", bool_variant_true.value_to_string()); rclcpp::parameter::ParameterVariant bool_variant_false("bool_param", false); - EXPECT_FALSE(bool_variant_false.get_value()); + EXPECT_FALSE(bool_variant_false.get_value()); EXPECT_FALSE(bool_variant_false.get_parameter_value().bool_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, bool_variant_false.get_parameter_value().type); @@ -95,9 +95,9 @@ TEST(TestParameter, bool_variant) { rclcpp::parameter::ParameterVariant from_msg_true = rclcpp::parameter::ParameterVariant::from_parameter(bool_param); EXPECT_EQ("bool_param", from_msg_true.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_BOOL, from_msg_true.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BOOL, from_msg_true.get_type()); EXPECT_EQ("bool", from_msg_true.get_type_name()); - EXPECT_TRUE(from_msg_true.get_value()); + EXPECT_TRUE(from_msg_true.get_value()); EXPECT_TRUE(from_msg_true.get_parameter_value().bool_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, bool_variant_false.get_parameter_value().type); @@ -105,7 +105,7 @@ TEST(TestParameter, bool_variant) { bool_param.value.bool_value = false; rclcpp::parameter::ParameterVariant from_msg_false = rclcpp::parameter::ParameterVariant::from_parameter(bool_param); - EXPECT_FALSE(from_msg_false.get_value()); + EXPECT_FALSE(from_msg_false.get_value()); EXPECT_FALSE(from_msg_false.get_parameter_value().bool_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, bool_variant_false.get_parameter_value().type); @@ -117,10 +117,10 @@ TEST(TestParameter, integer_variant) { // Direct instantiation rclcpp::parameter::ParameterVariant integer_variant("integer_param", TEST_VALUE); EXPECT_EQ("integer_param", integer_variant.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_INTEGER, integer_variant.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, integer_variant.get_type()); EXPECT_EQ("integer", integer_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, - integer_variant.get_value()); + integer_variant.get_value()); EXPECT_EQ(TEST_VALUE, integer_variant.get_parameter_value().integer_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, integer_variant.get_parameter_value().type); @@ -146,10 +146,10 @@ TEST(TestParameter, integer_variant) { rclcpp::parameter::ParameterVariant from_msg = rclcpp::parameter::ParameterVariant::from_parameter(integer_param); EXPECT_EQ("integer_param", from_msg.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_INTEGER, from_msg.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, from_msg.get_type()); EXPECT_EQ("integer", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, - from_msg.get_value()); + from_msg.get_value()); EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().integer_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, from_msg.get_parameter_value().type); @@ -161,10 +161,10 @@ TEST(TestParameter, long_integer_variant) { // Direct instantiation rclcpp::parameter::ParameterVariant long_variant("long_integer_param", TEST_VALUE); EXPECT_EQ("long_integer_param", long_variant.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_INTEGER, long_variant.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, long_variant.get_type()); EXPECT_EQ("integer", long_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, - long_variant.get_value()); + long_variant.get_value()); EXPECT_EQ(TEST_VALUE, long_variant.get_parameter_value().integer_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, long_variant.get_parameter_value().type); @@ -190,10 +190,10 @@ TEST(TestParameter, long_integer_variant) { rclcpp::parameter::ParameterVariant from_msg = rclcpp::parameter::ParameterVariant::from_parameter(integer_param); EXPECT_EQ("long_integer_param", from_msg.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_INTEGER, from_msg.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, from_msg.get_type()); EXPECT_EQ("integer", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, - from_msg.get_value()); + from_msg.get_value()); EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().integer_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, from_msg.get_parameter_value().type); @@ -205,10 +205,10 @@ TEST(TestParameter, float_variant) { // Direct instantiation rclcpp::parameter::ParameterVariant float_variant("float_param", TEST_VALUE); EXPECT_EQ("float_param", float_variant.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_DOUBLE, float_variant.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE, float_variant.get_type()); EXPECT_EQ("double", float_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, - float_variant.get_value()); + float_variant.get_value()); EXPECT_EQ(TEST_VALUE, float_variant.get_parameter_value().double_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE, float_variant.get_parameter_value().type); @@ -234,10 +234,10 @@ TEST(TestParameter, float_variant) { rclcpp::parameter::ParameterVariant from_msg = rclcpp::parameter::ParameterVariant::from_parameter(float_param); EXPECT_EQ("float_param", from_msg.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_DOUBLE, from_msg.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE, from_msg.get_type()); EXPECT_EQ("double", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, - from_msg.get_value()); + from_msg.get_value()); EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().double_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE, from_msg.get_parameter_value().type); @@ -249,10 +249,10 @@ TEST(TestParameter, double_variant) { // Direct instantiation rclcpp::parameter::ParameterVariant double_variant("double_param", TEST_VALUE); EXPECT_EQ("double_param", double_variant.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_DOUBLE, double_variant.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE, double_variant.get_type()); EXPECT_EQ("double", double_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, - double_variant.get_value()); + double_variant.get_value()); EXPECT_EQ(TEST_VALUE, double_variant.get_parameter_value().double_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE, double_variant.get_parameter_value().type); @@ -278,10 +278,10 @@ TEST(TestParameter, double_variant) { rclcpp::parameter::ParameterVariant from_msg = rclcpp::parameter::ParameterVariant::from_parameter(double_param); EXPECT_EQ("double_param", from_msg.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_DOUBLE, from_msg.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE, from_msg.get_type()); EXPECT_EQ("double", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, - from_msg.get_value()); + from_msg.get_value()); EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().double_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE, from_msg.get_parameter_value().type); @@ -293,10 +293,10 @@ TEST(TestParameter, string_variant) { // Direct instantiation rclcpp::parameter::ParameterVariant string_variant("string_param", TEST_VALUE); EXPECT_EQ("string_param", string_variant.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_STRING, string_variant.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_STRING, string_variant.get_type()); EXPECT_EQ("string", string_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, - string_variant.get_value()); + string_variant.get_value()); EXPECT_EQ(TEST_VALUE, string_variant.get_parameter_value().string_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_STRING, string_variant.get_parameter_value().type); @@ -322,9 +322,9 @@ TEST(TestParameter, string_variant) { rclcpp::parameter::ParameterVariant from_msg = rclcpp::parameter::ParameterVariant::from_parameter(string_param); EXPECT_EQ("string_param", from_msg.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_STRING, from_msg.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_STRING, from_msg.get_type()); EXPECT_EQ("string", from_msg.get_type_name()); - EXPECT_EQ(TEST_VALUE, from_msg.get_value()); + EXPECT_EQ(TEST_VALUE, from_msg.get_value()); EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().string_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_STRING, from_msg.get_parameter_value().type); @@ -336,10 +336,10 @@ TEST(TestParameter, byte_array_variant) { // Direct instantiation rclcpp::parameter::ParameterVariant byte_array_variant("byte_array_param", TEST_VALUE); EXPECT_EQ("byte_array_param", byte_array_variant.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_BYTE_ARRAY, byte_array_variant.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BYTE_ARRAY, byte_array_variant.get_type()); EXPECT_EQ("byte_array", byte_array_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, - byte_array_variant.get_value()); + byte_array_variant.get_value()); EXPECT_EQ(TEST_VALUE, byte_array_variant.get_parameter_value().byte_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY, byte_array_variant.get_parameter_value().type); @@ -365,10 +365,10 @@ TEST(TestParameter, byte_array_variant) { rclcpp::parameter::ParameterVariant from_msg = rclcpp::parameter::ParameterVariant::from_parameter(byte_array_param); EXPECT_EQ("byte_array_param", from_msg.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_BYTE_ARRAY, from_msg.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BYTE_ARRAY, from_msg.get_type()); EXPECT_EQ("byte_array", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, - from_msg.get_value()); + from_msg.get_value()); EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().byte_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY, from_msg.get_parameter_value().type); @@ -380,10 +380,10 @@ TEST(TestParameter, bool_array_variant) { // Direct instantiation rclcpp::parameter::ParameterVariant bool_array_variant("bool_array_param", TEST_VALUE); EXPECT_EQ("bool_array_param", bool_array_variant.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_BOOL_ARRAY, bool_array_variant.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BOOL_ARRAY, bool_array_variant.get_type()); EXPECT_EQ("bool_array", bool_array_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, - bool_array_variant.get_value()); + bool_array_variant.get_value()); EXPECT_EQ(TEST_VALUE, bool_array_variant.get_parameter_value().bool_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY, bool_array_variant.get_parameter_value().type); @@ -409,10 +409,10 @@ TEST(TestParameter, bool_array_variant) { rclcpp::parameter::ParameterVariant from_msg = rclcpp::parameter::ParameterVariant::from_parameter(bool_array_param); EXPECT_EQ("bool_array_param", from_msg.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_BOOL_ARRAY, from_msg.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BOOL_ARRAY, from_msg.get_type()); EXPECT_EQ("bool_array", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, - from_msg.get_value()); + from_msg.get_value()); EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().bool_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY, from_msg.get_parameter_value().type); @@ -426,7 +426,7 @@ TEST(TestParameter, integer_array_variant) { rclcpp::parameter::ParameterVariant integer_array_variant("integer_array_param", TEST_VALUE); EXPECT_EQ("integer_array_param", integer_array_variant.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_INTEGER_ARRAY, + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY, integer_array_variant.get_type()); EXPECT_EQ("integer_array", integer_array_variant.get_type_name()); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY, @@ -434,7 +434,7 @@ TEST(TestParameter, integer_array_variant) { // No direct comparison of vectors of ints and long ints const auto & param_value_ref = - integer_array_variant.get_value(); + integer_array_variant.get_value(); auto mismatches = std::mismatch(TEST_VALUE.begin(), TEST_VALUE.end(), param_value_ref.begin()); EXPECT_EQ(TEST_VALUE.end(), mismatches.first); EXPECT_EQ(param_value_ref.end(), mismatches.second); @@ -476,10 +476,10 @@ TEST(TestParameter, integer_array_variant) { rclcpp::parameter::ParameterVariant from_msg = rclcpp::parameter::ParameterVariant::from_parameter(integer_array_param); EXPECT_EQ("integer_array_param", from_msg.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_INTEGER_ARRAY, from_msg.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY, from_msg.get_type()); EXPECT_EQ("integer_array", from_msg.get_type_name()); - param_value = from_msg.get_value(); + param_value = from_msg.get_value(); mismatches = std::mismatch(TEST_VALUE.begin(), TEST_VALUE.end(), param_value.begin()); EXPECT_EQ(TEST_VALUE.end(), mismatches.first); EXPECT_EQ(param_value.end(), mismatches.second); @@ -499,13 +499,13 @@ TEST(TestParameter, long_integer_array_variant) { rclcpp::parameter::ParameterVariant long_array_variant("long_integer_array_param", TEST_VALUE); EXPECT_EQ("long_integer_array_param", long_array_variant.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_INTEGER_ARRAY, + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY, long_array_variant.get_type()); EXPECT_EQ("integer_array", long_array_variant.get_type_name()); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY, long_array_variant.get_parameter_value().type); EXPECT_EQ(TEST_VALUE, - long_array_variant.get_value()); + long_array_variant.get_value()); EXPECT_EQ(TEST_VALUE, long_array_variant.get_parameter_value().integer_array_value); EXPECT_EQ(TEST_VALUE, long_array_variant.as_integer_array()); @@ -532,10 +532,10 @@ TEST(TestParameter, long_integer_array_variant) { rclcpp::parameter::ParameterVariant from_msg = rclcpp::parameter::ParameterVariant::from_parameter(integer_array_param); EXPECT_EQ("long_integer_array_param", from_msg.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_INTEGER_ARRAY, from_msg.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY, from_msg.get_type()); EXPECT_EQ("integer_array", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, - from_msg.get_value()); + from_msg.get_value()); EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().integer_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY, from_msg.get_parameter_value().type); @@ -549,7 +549,7 @@ TEST(TestParameter, float_array_variant) { rclcpp::parameter::ParameterVariant float_array_variant("float_array_param", TEST_VALUE); EXPECT_EQ("float_array_param", float_array_variant.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_DOUBLE_ARRAY, + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY, float_array_variant.get_type()); EXPECT_EQ("double_array", float_array_variant.get_type_name()); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY, @@ -557,7 +557,7 @@ TEST(TestParameter, float_array_variant) { // No direct comparison of vectors of floats and doubles const auto & param_value_ref = - float_array_variant.get_value(); + float_array_variant.get_value(); auto mismatches = std::mismatch(TEST_VALUE.begin(), TEST_VALUE.end(), param_value_ref.begin()); EXPECT_EQ(TEST_VALUE.end(), mismatches.first); EXPECT_EQ(param_value_ref.end(), mismatches.second); @@ -599,10 +599,10 @@ TEST(TestParameter, float_array_variant) { rclcpp::parameter::ParameterVariant from_msg = rclcpp::parameter::ParameterVariant::from_parameter(float_array_param); EXPECT_EQ("float_array_param", from_msg.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_DOUBLE_ARRAY, from_msg.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY, from_msg.get_type()); EXPECT_EQ("double_array", from_msg.get_type_name()); - param_value = from_msg.get_value(); + param_value = from_msg.get_value(); mismatches = std::mismatch(TEST_VALUE.begin(), TEST_VALUE.end(), param_value.begin()); EXPECT_EQ(TEST_VALUE.end(), mismatches.first); EXPECT_EQ(param_value.end(), mismatches.second); @@ -622,13 +622,13 @@ TEST(TestParameter, double_array_variant) { rclcpp::parameter::ParameterVariant double_array_variant("double_array_param", TEST_VALUE); EXPECT_EQ("double_array_param", double_array_variant.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_DOUBLE_ARRAY, + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY, double_array_variant.get_type()); EXPECT_EQ("double_array", double_array_variant.get_type_name()); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY, double_array_variant.get_parameter_value().type); EXPECT_EQ(TEST_VALUE, - double_array_variant.get_value()); + double_array_variant.get_value()); EXPECT_EQ(TEST_VALUE, double_array_variant.get_parameter_value().double_array_value); EXPECT_EQ(TEST_VALUE, double_array_variant.as_double_array()); @@ -655,10 +655,10 @@ TEST(TestParameter, double_array_variant) { rclcpp::parameter::ParameterVariant from_msg = rclcpp::parameter::ParameterVariant::from_parameter(double_array_param); EXPECT_EQ("double_array_param", from_msg.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_DOUBLE_ARRAY, from_msg.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY, from_msg.get_type()); EXPECT_EQ("double_array", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, - from_msg.get_value()); + from_msg.get_value()); EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().double_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY, from_msg.get_parameter_value().type); @@ -670,11 +670,11 @@ TEST(TestParameter, string_array_variant) { // Direct instantiation rclcpp::parameter::ParameterVariant string_array_variant("string_array_param", TEST_VALUE); EXPECT_EQ("string_array_param", string_array_variant.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_STRING_ARRAY, + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_STRING_ARRAY, string_array_variant.get_type()); EXPECT_EQ("string_array", string_array_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, - string_array_variant.get_value()); + string_array_variant.get_value()); EXPECT_EQ(TEST_VALUE, string_array_variant.get_parameter_value().string_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY, string_array_variant.get_parameter_value().type); @@ -701,10 +701,10 @@ TEST(TestParameter, string_array_variant) { rclcpp::parameter::ParameterVariant from_msg = rclcpp::parameter::ParameterVariant::from_parameter(string_array_param); EXPECT_EQ("string_array_param", from_msg.get_name()); - EXPECT_EQ(rclcpp::parameter::ParameterType::PARAMETER_STRING_ARRAY, from_msg.get_type()); + EXPECT_EQ(rclcpp::ParameterType::PARAMETER_STRING_ARRAY, from_msg.get_type()); EXPECT_EQ("string_array", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, - from_msg.get_value()); + from_msg.get_value()); EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().string_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY, from_msg.get_parameter_value().type); diff --git a/rclcpp/test/test_time_source.cpp b/rclcpp/test/test_time_source.cpp index 28f675bf5b..ff9e02cfbc 100644 --- a/rclcpp/test/test_time_source.cpp +++ b/rclcpp/test/test_time_source.cpp @@ -349,7 +349,7 @@ TEST_F(TestTimeSource, parameter_activation) { set_parameters_results = parameters_client->set_parameters({ - rclcpp::parameter::ParameterVariant("use_sim_time", rclcpp::parameter::PARAMETER_NOT_SET) + rclcpp::parameter::ParameterVariant("use_sim_time", rclcpp::ParameterType::PARAMETER_NOT_SET) }); 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::parameter::PARAMETER_NOT_SET) + rclcpp::parameter::ParameterVariant("use_sim_time", rclcpp::ParameterType::PARAMETER_NOT_SET) }); for (auto & result : set_parameters_results) { EXPECT_TRUE(result.successful); From ee1230a0033bf1a6ec8104ac16189d8dd8ef24e7 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 29 May 2018 11:34:24 -0700 Subject: [PATCH 02/17] Delegate get_value() to ParameterValue Test expects ParameterTypeException --- rclcpp/include/rclcpp/parameter.hpp | 238 ++-------------------- rclcpp/include/rclcpp/parameter_value.hpp | 18 +- rclcpp/src/rclcpp/parameter.cpp | 165 +-------------- rclcpp/src/rclcpp/parameter_value.cpp | 28 ++- rclcpp/test/test_parameter.cpp | 226 ++++++++++---------- 5 files changed, 171 insertions(+), 504 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter.hpp b/rclcpp/include/rclcpp/parameter.hpp index bc61e61f65..8c6afa022d 100644 --- a/rclcpp/include/rclcpp/parameter.hpp +++ b/rclcpp/include/rclcpp/parameter.hpp @@ -39,48 +39,16 @@ class ParameterVariant public: RCLCPP_PUBLIC ParameterVariant(); + RCLCPP_PUBLIC - explicit ParameterVariant(const std::string & name, const bool bool_value); - RCLCPP_PUBLIC - explicit ParameterVariant(const std::string & name, const int int_value); - RCLCPP_PUBLIC - explicit ParameterVariant(const std::string & name, const int64_t int_value); - RCLCPP_PUBLIC - explicit ParameterVariant(const std::string & name, const float double_value); - RCLCPP_PUBLIC - explicit ParameterVariant(const std::string & name, const double double_value); - RCLCPP_PUBLIC - explicit ParameterVariant(const std::string & name, const std::string & string_value); - RCLCPP_PUBLIC - explicit ParameterVariant(const std::string & name, const char * string_value); - RCLCPP_PUBLIC - explicit ParameterVariant( - const std::string & name, - const std::vector & byte_array_value); - RCLCPP_PUBLIC - explicit ParameterVariant( - const std::string & name, - const std::vector & bool_array_value); - RCLCPP_PUBLIC - explicit ParameterVariant( - const std::string & name, - const std::vector & int_array_value); - RCLCPP_PUBLIC - explicit ParameterVariant( - const std::string & name, - const std::vector & int_array_value); - RCLCPP_PUBLIC - explicit ParameterVariant( - const std::string & name, - const std::vector & double_array_value); - RCLCPP_PUBLIC - explicit ParameterVariant( - const std::string & name, - const std::vector & double_array_value); + ParameterVariant(const std::string & name, const ParameterValue & value); + + template RCLCPP_PUBLIC - explicit ParameterVariant( - const std::string & name, - const std::vector & string_array_value); + explicit ParameterVariant(const std::string & name, ValueTypeT value) + : ParameterVariant(name, ParameterValue(value)) + { + } RCLCPP_PUBLIC ParameterType @@ -98,186 +66,20 @@ class ParameterVariant rcl_interfaces::msg::ParameterValue get_parameter_value() const; - // The following get_value() variants require the use of ParameterType - - template - typename std::enable_if::type - get_value() const - { - if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) { - // TODO(wjwwood): use custom exception - throw std::runtime_error("Invalid type"); - } - return value_.bool_value; - } - - template - typename std::enable_if::type - get_value() const - { - if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER) { - // TODO(wjwwood): use custom exception - throw std::runtime_error("Invalid type"); - } - return value_.integer_value; - } - - template - typename std::enable_if::type - get_value() const - { - if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) { - // TODO(wjwwood): use custom exception - throw std::runtime_error("Invalid type"); - } - return value_.double_value; - } - - template - typename std::enable_if::type - get_value() const - { - if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_STRING) { - // TODO(wjwwood): use custom exception - throw std::runtime_error("Invalid type"); - } - return value_.string_value; - } - - template - typename std::enable_if< - type == ParameterType::PARAMETER_BYTE_ARRAY, const std::vector &>::type - get_value() const - { - if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY) { - // TODO(wjwwood): use custom exception - throw std::runtime_error("Invalid type"); - } - return value_.byte_array_value; - } - - template - typename std::enable_if< - type == ParameterType::PARAMETER_BOOL_ARRAY, const std::vector &>::type - get_value() const - { - if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY) { - // TODO(wjwwood): use custom exception - throw std::runtime_error("Invalid type"); - } - return value_.bool_array_value; - } - - template - typename std::enable_if< - type == ParameterType::PARAMETER_INTEGER_ARRAY, const std::vector &>::type + /// Get value of parameter using rclcpp::ParameterType as template argument. + template + decltype(ParameterValue().get()) get_value() const { - if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY) { - // TODO(wjwwood): use custom exception - throw std::runtime_error("Invalid type"); - } - return value_.integer_array_value; - } - - template - typename std::enable_if< - type == ParameterType::PARAMETER_DOUBLE_ARRAY, const std::vector &>::type - get_value() const - { - if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY) { - // TODO(wjwwood): use custom exception - throw std::runtime_error("Invalid type"); - } - return value_.double_array_value; - } - - template - typename std::enable_if< - type == ParameterType::PARAMETER_STRING_ARRAY, const std::vector &>::type - get_value() const - { - if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY) { - // TODO(wjwwood): use custom exception - throw std::runtime_error("Invalid type"); - } - return value_.string_array_value; - } - - // The following get_value() variants allow the use of primitive types - - template - typename std::enable_if::value, bool>::type - get_value() const - { - return get_value(); - } - - template - typename std::enable_if< - std::is_integral::value && !std::is_same::value, int64_t>::type - get_value() const - { - return get_value(); - } - - template - typename std::enable_if::value, double>::type - get_value() const - { - return get_value(); + return value_.get(); } - template - typename std::enable_if::value, const std::string &>::type + /// Get value of parameter using c++ types as template argument + template + decltype(ParameterValue().get()) get_value() const { - return get_value(); - } - - template - typename std::enable_if< - std::is_convertible< - type, const std::vector &>::value, const std::vector &>::type - get_value() const - { - return get_value(); - } - - template - typename std::enable_if< - std::is_convertible< - type, const std::vector &>::value, const std::vector &>::type - get_value() const - { - return get_value(); - } - - template - typename std::enable_if< - std::is_convertible< - type, const std::vector &>::value, const std::vector &>::type - get_value() const - { - return get_value(); - } - - template - typename std::enable_if< - std::is_convertible< - type, const std::vector &>::value, const std::vector &>::type - get_value() const - { - return get_value(); - } - - template - typename std::enable_if< - std::is_convertible< - type, const std::vector &>::value, const std::vector &>::type - get_value() const - { - return get_value(); + return value_.get(); } RCLCPP_PUBLIC @@ -352,14 +154,8 @@ class ParameterVariant return type_array.str(); } - template - void vector_assign(OutputType & output, const InputType & input) - { - output.assign(input.begin(), input.end()); - } - std::string name_; - rcl_interfaces::msg::ParameterValue value_; + ParameterValue value_; }; /// Return a json encoded version of the parameter intended for a dict. diff --git a/rclcpp/include/rclcpp/parameter_value.hpp b/rclcpp/include/rclcpp/parameter_value.hpp index d02f3b84ae..eb8b03923b 100644 --- a/rclcpp/include/rclcpp/parameter_value.hpp +++ b/rclcpp/include/rclcpp/parameter_value.hpp @@ -43,15 +43,6 @@ enum ParameterType PARAMETER_STRING_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY, }; -/// Return the name of a parameter type -RCLCPP_PUBLIC -std::string -to_string(const ParameterType type); - -RCLCPP_PUBLIC -std::ostream & -operator<<(std::ostream & os, const ParameterType type); - /// Indicate the parameter type does not match the expected type. class ParameterTypeException : public std::exception { @@ -349,8 +340,17 @@ class ParameterValue /// Return the value of a parameter as a string RCLCPP_PUBLIC std::string +to_string(const ParameterValue & type); + +/// Return the name of a parameter type +RCLCPP_PUBLIC +std::string to_string(const ParameterType type); +RCLCPP_PUBLIC +std::ostream & +operator<<(std::ostream & os, const ParameterType type); + } // namespace rclcpp #endif // RCLCPP__PARAMETER_VALUE_HPP_ diff --git a/rclcpp/src/rclcpp/parameter.cpp b/rclcpp/src/rclcpp/parameter.cpp index 8409d3484c..470a195d73 100644 --- a/rclcpp/src/rclcpp/parameter.cpp +++ b/rclcpp/src/rclcpp/parameter.cpp @@ -26,115 +26,17 @@ using rclcpp::parameter::ParameterVariant; ParameterVariant::ParameterVariant() : name_("") { - value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET; } -ParameterVariant::ParameterVariant(const std::string & name, const bool bool_value) -: name_(name) +ParameterVariant::ParameterVariant(const std::string & name, const ParameterValue & value) +: name_(name), value_(value) { - value_.bool_value = bool_value; - value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL; -} - -ParameterVariant::ParameterVariant(const std::string & name, const int int_value) -: name_(name) -{ - value_.integer_value = int_value; - value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; -} - -ParameterVariant::ParameterVariant(const std::string & name, const int64_t int_value) -: name_(name) -{ - value_.integer_value = int_value; - value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER; -} - -ParameterVariant::ParameterVariant(const std::string & name, const float double_value) -: name_(name) -{ - value_.double_value = double_value; - value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; -} - -ParameterVariant::ParameterVariant(const std::string & name, const double double_value) -: name_(name) -{ - value_.double_value = double_value; - value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE; -} - -ParameterVariant::ParameterVariant(const std::string & name, const std::string & string_value) -: name_(name) -{ - value_.string_value = string_value; - value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING; -} - -ParameterVariant::ParameterVariant(const std::string & name, const char * string_value) -: ParameterVariant(name, std::string(string_value)) -{} - -ParameterVariant::ParameterVariant( - const std::string & name, const std::vector & byte_array_value) -: name_(name) -{ - value_.byte_array_value = byte_array_value; - value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY; -} - -ParameterVariant::ParameterVariant( - const std::string & name, const std::vector & bool_array_value) -: name_(name) -{ - value_.bool_array_value = bool_array_value; - value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY; -} - -ParameterVariant::ParameterVariant( - const std::string & name, const std::vector & int_array_value) -: name_(name) -{ - vector_assign(value_.integer_array_value, int_array_value); - value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY; -} - -ParameterVariant::ParameterVariant( - const std::string & name, const std::vector & int_array_value) -: name_(name) -{ - value_.integer_array_value = int_array_value; - value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY; -} - -ParameterVariant::ParameterVariant( - const std::string & name, const std::vector & double_array_value) -: name_(name) -{ - vector_assign(value_.double_array_value, double_array_value); - value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY; -} - -ParameterVariant::ParameterVariant( - const std::string & name, const std::vector & double_array_value) -: name_(name) -{ - value_.double_array_value = double_array_value; - value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY; -} - -ParameterVariant::ParameterVariant( - const std::string & name, const std::vector & string_array_value) -: name_(name) -{ - value_.string_array_value = string_array_value; - value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY; } ParameterType ParameterVariant::get_type() const { - return static_cast(value_.type); + return value_.get_type(); } std::string @@ -152,7 +54,7 @@ ParameterVariant::get_name() const rcl_interfaces::msg::ParameterValue ParameterVariant::get_parameter_value() const { - return value_; + return value_.get_value_message(); } bool @@ -212,34 +114,7 @@ ParameterVariant::as_string_array() const ParameterVariant ParameterVariant::from_parameter(const rcl_interfaces::msg::Parameter & parameter) { - switch (parameter.value.type) { - case PARAMETER_NOT_SET: - throw std::runtime_error("Type from ParameterValue is not set"); - case PARAMETER_BOOL: - return ParameterVariant(parameter.name, parameter.value.bool_value); - case PARAMETER_INTEGER: - return ParameterVariant(parameter.name, parameter.value.integer_value); - case PARAMETER_DOUBLE: - return ParameterVariant(parameter.name, parameter.value.double_value); - case PARAMETER_STRING: - return ParameterVariant(parameter.name, parameter.value.string_value); - case PARAMETER_BYTE_ARRAY: - return ParameterVariant(parameter.name, parameter.value.byte_array_value); - case PARAMETER_BOOL_ARRAY: - return ParameterVariant(parameter.name, parameter.value.bool_array_value); - case PARAMETER_INTEGER_ARRAY: - return ParameterVariant(parameter.name, parameter.value.integer_array_value); - case PARAMETER_DOUBLE_ARRAY: - return ParameterVariant(parameter.name, parameter.value.double_array_value); - case PARAMETER_STRING_ARRAY: - return ParameterVariant(parameter.name, parameter.value.string_array_value); - default: - // TODO(wjwwood): use custom exception - // *INDENT-OFF* (prevent uncrustify from making unnecessary indents here) - throw std::runtime_error( - "Unexpected type from ParameterVariant: " + std::to_string(parameter.value.type)); - // *INDENT-ON* - } + return ParameterVariant(parameter.name, parameter.value); } rcl_interfaces::msg::Parameter @@ -247,40 +122,14 @@ ParameterVariant::to_parameter() { rcl_interfaces::msg::Parameter parameter; parameter.name = name_; - parameter.value = value_; + parameter.value = value_.get_value_message(); return parameter; } std::string ParameterVariant::value_to_string() const { - switch (get_type()) { - case ParameterType::PARAMETER_NOT_SET: - return "not set"; - case ParameterType::PARAMETER_BOOL: - return as_bool() ? "true" : "false"; - case ParameterType::PARAMETER_INTEGER: - return std::to_string(as_int()); - case ParameterType::PARAMETER_DOUBLE: - return std::to_string(as_double()); - case ParameterType::PARAMETER_STRING: - return as_string(); - case ParameterType::PARAMETER_BYTE_ARRAY: - return array_to_string(as_byte_array(), std::ios::hex); - case ParameterType::PARAMETER_BOOL_ARRAY: - return array_to_string(as_bool_array(), std::ios::boolalpha); - case ParameterType::PARAMETER_INTEGER_ARRAY: - return array_to_string(as_integer_array()); - case ParameterType::PARAMETER_DOUBLE_ARRAY: - return array_to_string(as_double_array()); - case ParameterType::PARAMETER_STRING_ARRAY: - return array_to_string(as_string_array()); - default: - // *INDENT-OFF* (prevent uncrustify from making unnecessary indents here) - throw std::runtime_error( - "Unexpected type from ParameterVariant: " + std::to_string(get_type())); - // *INDENT-ON* - } + return rclcpp::to_string(value_); } std::string diff --git a/rclcpp/src/rclcpp/parameter_value.cpp b/rclcpp/src/rclcpp/parameter_value.cpp index 339931379b..10c53bb7e2 100644 --- a/rclcpp/src/rclcpp/parameter_value.cpp +++ b/rclcpp/src/rclcpp/parameter_value.cpp @@ -96,7 +96,7 @@ array_to_string( } std::string -to_string(const ParameterValue & value) +rclcpp::to_string(const ParameterValue & value) { switch (value.get_type()) { case ParameterType::PARAMETER_NOT_SET: @@ -129,6 +129,28 @@ ParameterValue::ParameterValue() value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET; } +ParameterValue::ParameterValue(const rcl_interfaces::msg::ParameterValue & value) +{ + value_ = value; + switch (value.type) { + case PARAMETER_BOOL: + case PARAMETER_INTEGER: + case PARAMETER_DOUBLE: + case PARAMETER_STRING: + case PARAMETER_BYTE_ARRAY: + case PARAMETER_BOOL_ARRAY: + case PARAMETER_INTEGER_ARRAY: + case PARAMETER_DOUBLE_ARRAY: + case PARAMETER_STRING_ARRAY: + break; + case PARAMETER_NOT_SET: + throw std::runtime_error("Type from ParameterValue is not set"); + default: + // TODO(wjwwood): use custom exception + throw std::runtime_error("Unknown type: " + std::to_string(value.type)); + } +} + ParameterValue::ParameterValue(const bool bool_value) { value_.bool_value = bool_value; @@ -193,9 +215,9 @@ ParameterValue::ParameterValue(const std::vector & int_array_value) value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY; } -ParameterValue::ParameterValue(const std::vector & double_array_value) +ParameterValue::ParameterValue(const std::vector & float_array_value) { - value_.integer_array_value.assign(double_array_value.cbegin(), double_array_value.cend()); + value_.double_array_value.assign(float_array_value.cbegin(), float_array_value.cend()); value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY; } diff --git a/rclcpp/test/test_parameter.cpp b/rclcpp/test/test_parameter.cpp index 3ee85e7d0c..6a10f0adca 100644 --- a/rclcpp/test/test_parameter.cpp +++ b/rclcpp/test/test_parameter.cpp @@ -38,15 +38,15 @@ TEST(TestParameter, not_set_variant) { EXPECT_EQ(rclcpp::PARAMETER_NOT_SET, not_set_variant.get_type()); EXPECT_EQ("not set", not_set_variant.get_type_name()); - EXPECT_THROW(not_set_variant.as_bool(), std::runtime_error); - EXPECT_THROW(not_set_variant.as_int(), std::runtime_error); - EXPECT_THROW(not_set_variant.as_double(), std::runtime_error); - EXPECT_THROW(not_set_variant.as_string(), std::runtime_error); - EXPECT_THROW(not_set_variant.as_byte_array(), std::runtime_error); - EXPECT_THROW(not_set_variant.as_bool_array(), std::runtime_error); - EXPECT_THROW(not_set_variant.as_integer_array(), std::runtime_error); - EXPECT_THROW(not_set_variant.as_double_array(), std::runtime_error); - EXPECT_THROW(not_set_variant.as_string_array(), std::runtime_error); + EXPECT_THROW(not_set_variant.as_bool(), rclcpp::ParameterTypeException); + EXPECT_THROW(not_set_variant.as_int(), rclcpp::ParameterTypeException); + EXPECT_THROW(not_set_variant.as_double(), rclcpp::ParameterTypeException); + EXPECT_THROW(not_set_variant.as_string(), rclcpp::ParameterTypeException); + EXPECT_THROW(not_set_variant.as_byte_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(not_set_variant.as_bool_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(not_set_variant.as_integer_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(not_set_variant.as_double_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(not_set_variant.as_string_array(), rclcpp::ParameterTypeException); rcl_interfaces::msg::Parameter not_set_param = not_set_variant.to_parameter(); EXPECT_EQ("", not_set_param.name); @@ -69,14 +69,14 @@ TEST(TestParameter, bool_variant) { bool_variant_true.get_parameter_value().type); EXPECT_TRUE(bool_variant_true.as_bool()); - EXPECT_THROW(bool_variant_true.as_int(), std::runtime_error); - EXPECT_THROW(bool_variant_true.as_double(), std::runtime_error); - EXPECT_THROW(bool_variant_true.as_string(), std::runtime_error); - EXPECT_THROW(bool_variant_true.as_byte_array(), std::runtime_error); - EXPECT_THROW(bool_variant_true.as_bool_array(), std::runtime_error); - EXPECT_THROW(bool_variant_true.as_integer_array(), std::runtime_error); - EXPECT_THROW(bool_variant_true.as_double_array(), std::runtime_error); - EXPECT_THROW(bool_variant_true.as_string_array(), std::runtime_error); + EXPECT_THROW(bool_variant_true.as_int(), rclcpp::ParameterTypeException); + EXPECT_THROW(bool_variant_true.as_double(), rclcpp::ParameterTypeException); + EXPECT_THROW(bool_variant_true.as_string(), rclcpp::ParameterTypeException); + EXPECT_THROW(bool_variant_true.as_byte_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(bool_variant_true.as_bool_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(bool_variant_true.as_integer_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(bool_variant_true.as_double_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(bool_variant_true.as_string_array(), rclcpp::ParameterTypeException); EXPECT_EQ("true", bool_variant_true.value_to_string()); @@ -126,14 +126,14 @@ TEST(TestParameter, integer_variant) { integer_variant.get_parameter_value().type); EXPECT_EQ(TEST_VALUE, integer_variant.as_int()); - EXPECT_THROW(integer_variant.as_bool(), std::runtime_error); - EXPECT_THROW(integer_variant.as_double(), std::runtime_error); - EXPECT_THROW(integer_variant.as_string(), std::runtime_error); - EXPECT_THROW(integer_variant.as_byte_array(), std::runtime_error); - EXPECT_THROW(integer_variant.as_bool_array(), std::runtime_error); - EXPECT_THROW(integer_variant.as_integer_array(), std::runtime_error); - EXPECT_THROW(integer_variant.as_double_array(), std::runtime_error); - EXPECT_THROW(integer_variant.as_string_array(), std::runtime_error); + EXPECT_THROW(integer_variant.as_bool(), rclcpp::ParameterTypeException); + EXPECT_THROW(integer_variant.as_double(), rclcpp::ParameterTypeException); + EXPECT_THROW(integer_variant.as_string(), rclcpp::ParameterTypeException); + EXPECT_THROW(integer_variant.as_byte_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(integer_variant.as_bool_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(integer_variant.as_integer_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(integer_variant.as_double_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(integer_variant.as_string_array(), rclcpp::ParameterTypeException); EXPECT_EQ("42", integer_variant.value_to_string()); @@ -170,14 +170,14 @@ TEST(TestParameter, long_integer_variant) { long_variant.get_parameter_value().type); EXPECT_EQ(TEST_VALUE, long_variant.as_int()); - EXPECT_THROW(long_variant.as_bool(), std::runtime_error); - EXPECT_THROW(long_variant.as_double(), std::runtime_error); - EXPECT_THROW(long_variant.as_string(), std::runtime_error); - EXPECT_THROW(long_variant.as_byte_array(), std::runtime_error); - EXPECT_THROW(long_variant.as_bool_array(), std::runtime_error); - EXPECT_THROW(long_variant.as_integer_array(), std::runtime_error); - EXPECT_THROW(long_variant.as_double_array(), std::runtime_error); - EXPECT_THROW(long_variant.as_string_array(), std::runtime_error); + EXPECT_THROW(long_variant.as_bool(), rclcpp::ParameterTypeException); + EXPECT_THROW(long_variant.as_double(), rclcpp::ParameterTypeException); + EXPECT_THROW(long_variant.as_string(), rclcpp::ParameterTypeException); + EXPECT_THROW(long_variant.as_byte_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(long_variant.as_bool_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(long_variant.as_integer_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(long_variant.as_double_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(long_variant.as_string_array(), rclcpp::ParameterTypeException); EXPECT_EQ("9223372036854775807", long_variant.value_to_string()); @@ -214,14 +214,14 @@ TEST(TestParameter, float_variant) { float_variant.get_parameter_value().type); EXPECT_EQ(TEST_VALUE, float_variant.as_double()); - EXPECT_THROW(float_variant.as_bool(), std::runtime_error); - EXPECT_THROW(float_variant.as_int(), std::runtime_error); - EXPECT_THROW(float_variant.as_string(), std::runtime_error); - EXPECT_THROW(float_variant.as_byte_array(), std::runtime_error); - EXPECT_THROW(float_variant.as_bool_array(), std::runtime_error); - EXPECT_THROW(float_variant.as_integer_array(), std::runtime_error); - EXPECT_THROW(float_variant.as_double_array(), std::runtime_error); - EXPECT_THROW(float_variant.as_string_array(), std::runtime_error); + EXPECT_THROW(float_variant.as_bool(), rclcpp::ParameterTypeException); + EXPECT_THROW(float_variant.as_int(), rclcpp::ParameterTypeException); + EXPECT_THROW(float_variant.as_string(), rclcpp::ParameterTypeException); + EXPECT_THROW(float_variant.as_byte_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(float_variant.as_bool_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(float_variant.as_integer_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(float_variant.as_double_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(float_variant.as_string_array(), rclcpp::ParameterTypeException); EXPECT_EQ("42.000000", float_variant.value_to_string()); @@ -258,14 +258,14 @@ TEST(TestParameter, double_variant) { double_variant.get_parameter_value().type); EXPECT_EQ(TEST_VALUE, double_variant.as_double()); - EXPECT_THROW(double_variant.as_bool(), std::runtime_error); - EXPECT_THROW(double_variant.as_int(), std::runtime_error); - EXPECT_THROW(double_variant.as_string(), std::runtime_error); - EXPECT_THROW(double_variant.as_byte_array(), std::runtime_error); - EXPECT_THROW(double_variant.as_bool_array(), std::runtime_error); - EXPECT_THROW(double_variant.as_integer_array(), std::runtime_error); - EXPECT_THROW(double_variant.as_double_array(), std::runtime_error); - EXPECT_THROW(double_variant.as_string_array(), std::runtime_error); + EXPECT_THROW(double_variant.as_bool(), rclcpp::ParameterTypeException); + EXPECT_THROW(double_variant.as_int(), rclcpp::ParameterTypeException); + EXPECT_THROW(double_variant.as_string(), rclcpp::ParameterTypeException); + EXPECT_THROW(double_variant.as_byte_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(double_variant.as_bool_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(double_variant.as_integer_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(double_variant.as_double_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(double_variant.as_string_array(), rclcpp::ParameterTypeException); EXPECT_EQ("-42.100000", double_variant.value_to_string()); @@ -302,14 +302,14 @@ TEST(TestParameter, string_variant) { string_variant.get_parameter_value().type); EXPECT_EQ(TEST_VALUE, string_variant.as_string()); - EXPECT_THROW(string_variant.as_bool(), std::runtime_error); - EXPECT_THROW(string_variant.as_int(), std::runtime_error); - EXPECT_THROW(string_variant.as_double(), std::runtime_error); - EXPECT_THROW(string_variant.as_byte_array(), std::runtime_error); - EXPECT_THROW(string_variant.as_bool_array(), std::runtime_error); - EXPECT_THROW(string_variant.as_integer_array(), std::runtime_error); - EXPECT_THROW(string_variant.as_double_array(), std::runtime_error); - EXPECT_THROW(string_variant.as_string_array(), std::runtime_error); + EXPECT_THROW(string_variant.as_bool(), rclcpp::ParameterTypeException); + EXPECT_THROW(string_variant.as_int(), rclcpp::ParameterTypeException); + EXPECT_THROW(string_variant.as_double(), rclcpp::ParameterTypeException); + EXPECT_THROW(string_variant.as_byte_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(string_variant.as_bool_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(string_variant.as_integer_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(string_variant.as_double_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(string_variant.as_string_array(), rclcpp::ParameterTypeException); EXPECT_EQ(TEST_VALUE, string_variant.value_to_string()); @@ -345,14 +345,14 @@ TEST(TestParameter, byte_array_variant) { byte_array_variant.get_parameter_value().type); EXPECT_EQ(TEST_VALUE, byte_array_variant.as_byte_array()); - EXPECT_THROW(byte_array_variant.as_bool(), std::runtime_error); - EXPECT_THROW(byte_array_variant.as_int(), std::runtime_error); - EXPECT_THROW(byte_array_variant.as_double(), std::runtime_error); - EXPECT_THROW(byte_array_variant.as_string(), std::runtime_error); - EXPECT_THROW(byte_array_variant.as_bool_array(), std::runtime_error); - EXPECT_THROW(byte_array_variant.as_integer_array(), std::runtime_error); - EXPECT_THROW(byte_array_variant.as_double_array(), std::runtime_error); - EXPECT_THROW(byte_array_variant.as_string_array(), std::runtime_error); + EXPECT_THROW(byte_array_variant.as_bool(), rclcpp::ParameterTypeException); + EXPECT_THROW(byte_array_variant.as_int(), rclcpp::ParameterTypeException); + EXPECT_THROW(byte_array_variant.as_double(), rclcpp::ParameterTypeException); + EXPECT_THROW(byte_array_variant.as_string(), rclcpp::ParameterTypeException); + EXPECT_THROW(byte_array_variant.as_bool_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(byte_array_variant.as_integer_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(byte_array_variant.as_double_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(byte_array_variant.as_string_array(), rclcpp::ParameterTypeException); EXPECT_EQ("[0x52, 0x4f, 0x53, 0x32]", byte_array_variant.value_to_string()); @@ -389,14 +389,14 @@ TEST(TestParameter, bool_array_variant) { bool_array_variant.get_parameter_value().type); EXPECT_EQ(TEST_VALUE, bool_array_variant.as_bool_array()); - EXPECT_THROW(bool_array_variant.as_bool(), std::runtime_error); - EXPECT_THROW(bool_array_variant.as_int(), std::runtime_error); - EXPECT_THROW(bool_array_variant.as_double(), std::runtime_error); - EXPECT_THROW(bool_array_variant.as_string(), std::runtime_error); - EXPECT_THROW(bool_array_variant.as_byte_array(), std::runtime_error); - EXPECT_THROW(bool_array_variant.as_integer_array(), std::runtime_error); - EXPECT_THROW(bool_array_variant.as_double_array(), std::runtime_error); - EXPECT_THROW(bool_array_variant.as_string_array(), std::runtime_error); + EXPECT_THROW(bool_array_variant.as_bool(), rclcpp::ParameterTypeException); + EXPECT_THROW(bool_array_variant.as_int(), rclcpp::ParameterTypeException); + EXPECT_THROW(bool_array_variant.as_double(), rclcpp::ParameterTypeException); + EXPECT_THROW(bool_array_variant.as_string(), rclcpp::ParameterTypeException); + EXPECT_THROW(bool_array_variant.as_byte_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(bool_array_variant.as_integer_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(bool_array_variant.as_double_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(bool_array_variant.as_string_array(), rclcpp::ParameterTypeException); EXPECT_EQ("[false, true, true, false, false, true]", bool_array_variant.value_to_string()); @@ -449,14 +449,14 @@ TEST(TestParameter, integer_array_variant) { EXPECT_EQ(TEST_VALUE.end(), mismatches.first); EXPECT_EQ(param_value.end(), mismatches.second); - EXPECT_THROW(integer_array_variant.as_bool(), std::runtime_error); - EXPECT_THROW(integer_array_variant.as_int(), std::runtime_error); - EXPECT_THROW(integer_array_variant.as_double(), std::runtime_error); - EXPECT_THROW(integer_array_variant.as_string(), std::runtime_error); - EXPECT_THROW(integer_array_variant.as_byte_array(), std::runtime_error); - EXPECT_THROW(integer_array_variant.as_bool_array(), std::runtime_error); - EXPECT_THROW(integer_array_variant.as_double_array(), std::runtime_error); - EXPECT_THROW(integer_array_variant.as_string_array(), std::runtime_error); + EXPECT_THROW(integer_array_variant.as_bool(), rclcpp::ParameterTypeException); + EXPECT_THROW(integer_array_variant.as_int(), rclcpp::ParameterTypeException); + EXPECT_THROW(integer_array_variant.as_double(), rclcpp::ParameterTypeException); + EXPECT_THROW(integer_array_variant.as_string(), rclcpp::ParameterTypeException); + EXPECT_THROW(integer_array_variant.as_byte_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(integer_array_variant.as_bool_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(integer_array_variant.as_double_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(integer_array_variant.as_string_array(), rclcpp::ParameterTypeException); EXPECT_EQ( "[42, -99, 2147483647, -2147483648, 0]", @@ -509,14 +509,14 @@ TEST(TestParameter, long_integer_array_variant) { EXPECT_EQ(TEST_VALUE, long_array_variant.get_parameter_value().integer_array_value); EXPECT_EQ(TEST_VALUE, long_array_variant.as_integer_array()); - EXPECT_THROW(long_array_variant.as_bool(), std::runtime_error); - EXPECT_THROW(long_array_variant.as_int(), std::runtime_error); - EXPECT_THROW(long_array_variant.as_double(), std::runtime_error); - EXPECT_THROW(long_array_variant.as_string(), std::runtime_error); - EXPECT_THROW(long_array_variant.as_byte_array(), std::runtime_error); - EXPECT_THROW(long_array_variant.as_bool_array(), std::runtime_error); - EXPECT_THROW(long_array_variant.as_double_array(), std::runtime_error); - EXPECT_THROW(long_array_variant.as_string_array(), std::runtime_error); + EXPECT_THROW(long_array_variant.as_bool(), rclcpp::ParameterTypeException); + EXPECT_THROW(long_array_variant.as_int(), rclcpp::ParameterTypeException); + EXPECT_THROW(long_array_variant.as_double(), rclcpp::ParameterTypeException); + EXPECT_THROW(long_array_variant.as_string(), rclcpp::ParameterTypeException); + EXPECT_THROW(long_array_variant.as_byte_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(long_array_variant.as_bool_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(long_array_variant.as_double_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(long_array_variant.as_string_array(), rclcpp::ParameterTypeException); EXPECT_EQ( "[42, -99, 9223372036854775807, -9223372036854775808, 0]", @@ -572,14 +572,14 @@ TEST(TestParameter, float_array_variant) { EXPECT_EQ(TEST_VALUE.end(), mismatches.first); EXPECT_EQ(param_value.end(), mismatches.second); - EXPECT_THROW(float_array_variant.as_bool(), std::runtime_error); - EXPECT_THROW(float_array_variant.as_int(), std::runtime_error); - EXPECT_THROW(float_array_variant.as_double(), std::runtime_error); - EXPECT_THROW(float_array_variant.as_string(), std::runtime_error); - EXPECT_THROW(float_array_variant.as_byte_array(), std::runtime_error); - EXPECT_THROW(float_array_variant.as_bool_array(), std::runtime_error); - EXPECT_THROW(float_array_variant.as_integer_array(), std::runtime_error); - EXPECT_THROW(float_array_variant.as_string_array(), std::runtime_error); + EXPECT_THROW(float_array_variant.as_bool(), rclcpp::ParameterTypeException); + EXPECT_THROW(float_array_variant.as_int(), rclcpp::ParameterTypeException); + EXPECT_THROW(float_array_variant.as_double(), rclcpp::ParameterTypeException); + EXPECT_THROW(float_array_variant.as_string(), rclcpp::ParameterTypeException); + EXPECT_THROW(float_array_variant.as_byte_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(float_array_variant.as_bool_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(float_array_variant.as_integer_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(float_array_variant.as_string_array(), rclcpp::ParameterTypeException); EXPECT_EQ( "[42.1, -99.1, 3.40282e+38, -3.40282e+38, 0.1]", @@ -632,14 +632,14 @@ TEST(TestParameter, double_array_variant) { EXPECT_EQ(TEST_VALUE, double_array_variant.get_parameter_value().double_array_value); EXPECT_EQ(TEST_VALUE, double_array_variant.as_double_array()); - EXPECT_THROW(double_array_variant.as_bool(), std::runtime_error); - EXPECT_THROW(double_array_variant.as_int(), std::runtime_error); - EXPECT_THROW(double_array_variant.as_double(), std::runtime_error); - EXPECT_THROW(double_array_variant.as_string(), std::runtime_error); - EXPECT_THROW(double_array_variant.as_byte_array(), std::runtime_error); - EXPECT_THROW(double_array_variant.as_bool_array(), std::runtime_error); - EXPECT_THROW(double_array_variant.as_integer_array(), std::runtime_error); - EXPECT_THROW(double_array_variant.as_string_array(), std::runtime_error); + EXPECT_THROW(double_array_variant.as_bool(), rclcpp::ParameterTypeException); + EXPECT_THROW(double_array_variant.as_int(), rclcpp::ParameterTypeException); + EXPECT_THROW(double_array_variant.as_double(), rclcpp::ParameterTypeException); + EXPECT_THROW(double_array_variant.as_string(), rclcpp::ParameterTypeException); + EXPECT_THROW(double_array_variant.as_byte_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(double_array_variant.as_bool_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(double_array_variant.as_integer_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(double_array_variant.as_string_array(), rclcpp::ParameterTypeException); EXPECT_EQ( "[42.1, -99.1, 1.79769e+308, -1.79769e+308, 0.1]", @@ -680,14 +680,14 @@ TEST(TestParameter, string_array_variant) { string_array_variant.get_parameter_value().type); EXPECT_EQ(TEST_VALUE, string_array_variant.as_string_array()); - EXPECT_THROW(string_array_variant.as_bool(), std::runtime_error); - EXPECT_THROW(string_array_variant.as_int(), std::runtime_error); - EXPECT_THROW(string_array_variant.as_double(), std::runtime_error); - EXPECT_THROW(string_array_variant.as_string(), std::runtime_error); - EXPECT_THROW(string_array_variant.as_byte_array(), std::runtime_error); - EXPECT_THROW(string_array_variant.as_bool_array(), std::runtime_error); - EXPECT_THROW(string_array_variant.as_integer_array(), std::runtime_error); - EXPECT_THROW(string_array_variant.as_double_array(), std::runtime_error); + EXPECT_THROW(string_array_variant.as_bool(), rclcpp::ParameterTypeException); + EXPECT_THROW(string_array_variant.as_int(), rclcpp::ParameterTypeException); + EXPECT_THROW(string_array_variant.as_double(), rclcpp::ParameterTypeException); + EXPECT_THROW(string_array_variant.as_string(), rclcpp::ParameterTypeException); + EXPECT_THROW(string_array_variant.as_byte_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(string_array_variant.as_bool_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(string_array_variant.as_integer_array(), rclcpp::ParameterTypeException); + EXPECT_THROW(string_array_variant.as_double_array(), rclcpp::ParameterTypeException); EXPECT_EQ("[R, O, S2]", string_array_variant.value_to_string()); From fa8f19e1832517a2b01bf6ca3e63f7467d57c0e1 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 29 May 2018 12:14:39 -0700 Subject: [PATCH 03/17] Remove as_*() from ParameterValue --- rclcpp/include/rclcpp/parameter_value.hpp | 36 ------------ rclcpp/src/rclcpp/parameter_value.cpp | 72 +++-------------------- 2 files changed, 9 insertions(+), 99 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter_value.hpp b/rclcpp/include/rclcpp/parameter_value.hpp index eb8b03923b..c97bf1c80e 100644 --- a/rclcpp/include/rclcpp/parameter_value.hpp +++ b/rclcpp/include/rclcpp/parameter_value.hpp @@ -297,42 +297,6 @@ class ParameterValue return get(); } - RCLCPP_PUBLIC - bool - as_bool() const; - - RCLCPP_PUBLIC - int64_t - as_int() const; - - RCLCPP_PUBLIC - double - as_double() const; - - RCLCPP_PUBLIC - const std::string & - as_string() const; - - RCLCPP_PUBLIC - const std::vector & - as_byte_array() const; - - RCLCPP_PUBLIC - const std::vector & - as_bool_array() const; - - RCLCPP_PUBLIC - const std::vector & - as_integer_array() const; - - RCLCPP_PUBLIC - const std::vector & - as_double_array() const; - - RCLCPP_PUBLIC - const std::vector & - as_string_array() const; - private: rcl_interfaces::msg::ParameterValue value_; }; diff --git a/rclcpp/src/rclcpp/parameter_value.cpp b/rclcpp/src/rclcpp/parameter_value.cpp index 10c53bb7e2..02fcf1304e 100644 --- a/rclcpp/src/rclcpp/parameter_value.cpp +++ b/rclcpp/src/rclcpp/parameter_value.cpp @@ -102,23 +102,23 @@ rclcpp::to_string(const ParameterValue & value) case ParameterType::PARAMETER_NOT_SET: return "not set"; case ParameterType::PARAMETER_BOOL: - return value.as_bool() ? "true" : "false"; + return value.get() ? "true" : "false"; case ParameterType::PARAMETER_INTEGER: - return std::to_string(value.as_int()); + return std::to_string(value.get()); case ParameterType::PARAMETER_DOUBLE: - return std::to_string(value.as_double()); + return std::to_string(value.get()); case ParameterType::PARAMETER_STRING: - return value.as_string(); + return value.get(); case ParameterType::PARAMETER_BYTE_ARRAY: - return array_to_string(value.as_byte_array(), std::ios::hex); + return array_to_string(value.get>(), std::ios::hex); case ParameterType::PARAMETER_BOOL_ARRAY: - return array_to_string(value.as_bool_array(), std::ios::boolalpha); + return array_to_string(value.get>(), std::ios::boolalpha); case ParameterType::PARAMETER_INTEGER_ARRAY: - return array_to_string(value.as_integer_array()); + return array_to_string(value.get>()); case ParameterType::PARAMETER_DOUBLE_ARRAY: - return array_to_string(value.as_double_array()); + return array_to_string(value.get>()); case ParameterType::PARAMETER_STRING_ARRAY: - return array_to_string(value.as_string_array()); + return array_to_string(value.get>()); default: return "unknown type"; } @@ -244,57 +244,3 @@ ParameterValue::get_value_message() const { return value_; } - -bool -ParameterValue::as_bool() const -{ - return get(); -} - -int64_t -ParameterValue::as_int() const -{ - return get(); -} - -double -ParameterValue::as_double() const -{ - return get(); -} - -const std::string & -ParameterValue::as_string() const -{ - return get(); -} - -const std::vector & -ParameterValue::as_byte_array() const -{ - return get(); -} - -const std::vector & -ParameterValue::as_bool_array() const -{ - return get(); -} - -const std::vector & -ParameterValue::as_integer_array() const -{ - return get(); -} - -const std::vector & -ParameterValue::as_double_array() const -{ - return get(); -} - -const std::vector & -ParameterValue::as_string_array() const -{ - return get(); -} From 6d51a66b53582a2dd9986e3da91e56d1415b1919 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 29 May 2018 12:14:55 -0700 Subject: [PATCH 04/17] Remove unused includes --- rclcpp/include/rclcpp/parameter.hpp | 3 --- rclcpp/include/rclcpp/parameter_value.hpp | 1 - 2 files changed, 4 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter.hpp b/rclcpp/include/rclcpp/parameter.hpp index 8c6afa022d..9a419d24eb 100644 --- a/rclcpp/include/rclcpp/parameter.hpp +++ b/rclcpp/include/rclcpp/parameter.hpp @@ -22,11 +22,8 @@ #include #include "rcl_interfaces/msg/parameter.hpp" -#include "rcl_interfaces/msg/parameter_type.hpp" -#include "rcl_interfaces/msg/parameter_value.hpp" #include "rclcpp/parameter_value.hpp" #include "rclcpp/visibility_control.hpp" -#include "rmw/rmw.h" namespace rclcpp { diff --git a/rclcpp/include/rclcpp/parameter_value.hpp b/rclcpp/include/rclcpp/parameter_value.hpp index c97bf1c80e..03ce51350d 100644 --- a/rclcpp/include/rclcpp/parameter_value.hpp +++ b/rclcpp/include/rclcpp/parameter_value.hpp @@ -25,7 +25,6 @@ #include "rcl_interfaces/msg/parameter_type.hpp" #include "rcl_interfaces/msg/parameter_value.hpp" #include "rclcpp/visibility_control.hpp" -#include "rmw/rmw.h" namespace rclcpp { From a79730e1159f770d58a4432b003cecda5582a176 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 29 May 2018 13:22:42 -0700 Subject: [PATCH 05/17] get_parameter_value() -> get_value_message() --- rclcpp/include/rclcpp/parameter.hpp | 2 +- rclcpp/include/rclcpp/parameter_value.hpp | 2 +- rclcpp/src/rclcpp/parameter.cpp | 6 +- rclcpp/src/rclcpp/parameter_service.cpp | 2 +- rclcpp/src/rclcpp/parameter_value.cpp | 2 +- rclcpp/test/test_parameter.cpp | 112 +++++++++++----------- 6 files changed, 63 insertions(+), 63 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter.hpp b/rclcpp/include/rclcpp/parameter.hpp index 9a419d24eb..ba2a66aa8a 100644 --- a/rclcpp/include/rclcpp/parameter.hpp +++ b/rclcpp/include/rclcpp/parameter.hpp @@ -61,7 +61,7 @@ class ParameterVariant RCLCPP_PUBLIC rcl_interfaces::msg::ParameterValue - get_parameter_value() const; + get_value_message() const; /// Get value of parameter using rclcpp::ParameterType as template argument. template diff --git a/rclcpp/include/rclcpp/parameter_value.hpp b/rclcpp/include/rclcpp/parameter_value.hpp index 03ce51350d..1f7f527850 100644 --- a/rclcpp/include/rclcpp/parameter_value.hpp +++ b/rclcpp/include/rclcpp/parameter_value.hpp @@ -121,7 +121,7 @@ class ParameterValue /// Return a message populated with the parameter value RCLCPP_PUBLIC rcl_interfaces::msg::ParameterValue - get_value_message() const; + get_message() const; // The following get() variants require the use of ParameterType diff --git a/rclcpp/src/rclcpp/parameter.cpp b/rclcpp/src/rclcpp/parameter.cpp index 470a195d73..fd085263ce 100644 --- a/rclcpp/src/rclcpp/parameter.cpp +++ b/rclcpp/src/rclcpp/parameter.cpp @@ -52,9 +52,9 @@ ParameterVariant::get_name() const } rcl_interfaces::msg::ParameterValue -ParameterVariant::get_parameter_value() const +ParameterVariant::get_value_message() const { - return value_.get_value_message(); + return value_.get_message(); } bool @@ -122,7 +122,7 @@ ParameterVariant::to_parameter() { rcl_interfaces::msg::Parameter parameter; parameter.name = name_; - parameter.value = value_.get_value_message(); + parameter.value = value_.get_message(); return parameter; } diff --git a/rclcpp/src/rclcpp/parameter_service.cpp b/rclcpp/src/rclcpp/parameter_service.cpp index c4e224e5d2..4d8673d87a 100644 --- a/rclcpp/src/rclcpp/parameter_service.cpp +++ b/rclcpp/src/rclcpp/parameter_service.cpp @@ -41,7 +41,7 @@ ParameterService::ParameterService( { auto values = node_params->get_parameters(request->names); for (auto & pvariant : values) { - response->values.push_back(pvariant.get_parameter_value()); + response->values.push_back(pvariant.get_value_message()); } }, qos_profile, nullptr); diff --git a/rclcpp/src/rclcpp/parameter_value.cpp b/rclcpp/src/rclcpp/parameter_value.cpp index 02fcf1304e..c65da5bb3c 100644 --- a/rclcpp/src/rclcpp/parameter_value.cpp +++ b/rclcpp/src/rclcpp/parameter_value.cpp @@ -240,7 +240,7 @@ ParameterValue::get_type() const } rcl_interfaces::msg::ParameterValue -ParameterValue::get_value_message() const +ParameterValue::get_message() const { return value_; } diff --git a/rclcpp/test/test_parameter.cpp b/rclcpp/test/test_parameter.cpp index 6a10f0adca..e927c079a7 100644 --- a/rclcpp/test/test_parameter.cpp +++ b/rclcpp/test/test_parameter.cpp @@ -64,9 +64,9 @@ TEST(TestParameter, bool_variant) { EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BOOL, bool_variant_true.get_type()); EXPECT_EQ("bool", bool_variant_true.get_type_name()); EXPECT_TRUE(bool_variant_true.get_value()); - EXPECT_TRUE(bool_variant_true.get_parameter_value().bool_value); + EXPECT_TRUE(bool_variant_true.get_value_message().bool_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, - bool_variant_true.get_parameter_value().type); + bool_variant_true.get_value_message().type); EXPECT_TRUE(bool_variant_true.as_bool()); EXPECT_THROW(bool_variant_true.as_int(), rclcpp::ParameterTypeException); @@ -82,9 +82,9 @@ TEST(TestParameter, bool_variant) { rclcpp::parameter::ParameterVariant bool_variant_false("bool_param", false); EXPECT_FALSE(bool_variant_false.get_value()); - EXPECT_FALSE(bool_variant_false.get_parameter_value().bool_value); + EXPECT_FALSE(bool_variant_false.get_value_message().bool_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, - bool_variant_false.get_parameter_value().type); + bool_variant_false.get_value_message().type); rcl_interfaces::msg::Parameter bool_param = bool_variant_true.to_parameter(); EXPECT_EQ("bool_param", bool_param.name); @@ -98,17 +98,17 @@ TEST(TestParameter, bool_variant) { EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BOOL, from_msg_true.get_type()); EXPECT_EQ("bool", from_msg_true.get_type_name()); EXPECT_TRUE(from_msg_true.get_value()); - EXPECT_TRUE(from_msg_true.get_parameter_value().bool_value); + EXPECT_TRUE(from_msg_true.get_value_message().bool_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, - bool_variant_false.get_parameter_value().type); + 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); EXPECT_FALSE(from_msg_false.get_value()); - EXPECT_FALSE(from_msg_false.get_parameter_value().bool_value); + EXPECT_FALSE(from_msg_false.get_value_message().bool_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, - bool_variant_false.get_parameter_value().type); + bool_variant_false.get_value_message().type); } TEST(TestParameter, integer_variant) { @@ -121,9 +121,9 @@ TEST(TestParameter, integer_variant) { EXPECT_EQ("integer", integer_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, integer_variant.get_value()); - EXPECT_EQ(TEST_VALUE, integer_variant.get_parameter_value().integer_value); + EXPECT_EQ(TEST_VALUE, integer_variant.get_value_message().integer_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, - integer_variant.get_parameter_value().type); + integer_variant.get_value_message().type); EXPECT_EQ(TEST_VALUE, integer_variant.as_int()); EXPECT_THROW(integer_variant.as_bool(), rclcpp::ParameterTypeException); @@ -150,9 +150,9 @@ TEST(TestParameter, integer_variant) { EXPECT_EQ("integer", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, from_msg.get_value()); - EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().integer_value); + EXPECT_EQ(TEST_VALUE, from_msg.get_value_message().integer_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, - from_msg.get_parameter_value().type); + from_msg.get_value_message().type); } TEST(TestParameter, long_integer_variant) { @@ -165,9 +165,9 @@ TEST(TestParameter, long_integer_variant) { EXPECT_EQ("integer", long_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, long_variant.get_value()); - EXPECT_EQ(TEST_VALUE, long_variant.get_parameter_value().integer_value); + EXPECT_EQ(TEST_VALUE, long_variant.get_value_message().integer_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, - long_variant.get_parameter_value().type); + long_variant.get_value_message().type); EXPECT_EQ(TEST_VALUE, long_variant.as_int()); EXPECT_THROW(long_variant.as_bool(), rclcpp::ParameterTypeException); @@ -194,9 +194,9 @@ TEST(TestParameter, long_integer_variant) { EXPECT_EQ("integer", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, from_msg.get_value()); - EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().integer_value); + EXPECT_EQ(TEST_VALUE, from_msg.get_value_message().integer_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, - from_msg.get_parameter_value().type); + from_msg.get_value_message().type); } TEST(TestParameter, float_variant) { @@ -209,9 +209,9 @@ TEST(TestParameter, float_variant) { EXPECT_EQ("double", float_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, float_variant.get_value()); - EXPECT_EQ(TEST_VALUE, float_variant.get_parameter_value().double_value); + EXPECT_EQ(TEST_VALUE, float_variant.get_value_message().double_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE, - float_variant.get_parameter_value().type); + float_variant.get_value_message().type); EXPECT_EQ(TEST_VALUE, float_variant.as_double()); EXPECT_THROW(float_variant.as_bool(), rclcpp::ParameterTypeException); @@ -238,9 +238,9 @@ TEST(TestParameter, float_variant) { EXPECT_EQ("double", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, from_msg.get_value()); - EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().double_value); + EXPECT_EQ(TEST_VALUE, from_msg.get_value_message().double_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE, - from_msg.get_parameter_value().type); + from_msg.get_value_message().type); } TEST(TestParameter, double_variant) { @@ -253,9 +253,9 @@ TEST(TestParameter, double_variant) { EXPECT_EQ("double", double_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, double_variant.get_value()); - EXPECT_EQ(TEST_VALUE, double_variant.get_parameter_value().double_value); + EXPECT_EQ(TEST_VALUE, double_variant.get_value_message().double_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE, - double_variant.get_parameter_value().type); + double_variant.get_value_message().type); EXPECT_EQ(TEST_VALUE, double_variant.as_double()); EXPECT_THROW(double_variant.as_bool(), rclcpp::ParameterTypeException); @@ -282,9 +282,9 @@ TEST(TestParameter, double_variant) { EXPECT_EQ("double", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, from_msg.get_value()); - EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().double_value); + EXPECT_EQ(TEST_VALUE, from_msg.get_value_message().double_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE, - from_msg.get_parameter_value().type); + from_msg.get_value_message().type); } TEST(TestParameter, string_variant) { @@ -297,9 +297,9 @@ TEST(TestParameter, string_variant) { EXPECT_EQ("string", string_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, string_variant.get_value()); - EXPECT_EQ(TEST_VALUE, string_variant.get_parameter_value().string_value); + EXPECT_EQ(TEST_VALUE, string_variant.get_value_message().string_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_STRING, - string_variant.get_parameter_value().type); + string_variant.get_value_message().type); EXPECT_EQ(TEST_VALUE, string_variant.as_string()); EXPECT_THROW(string_variant.as_bool(), rclcpp::ParameterTypeException); @@ -325,9 +325,9 @@ TEST(TestParameter, string_variant) { EXPECT_EQ(rclcpp::ParameterType::PARAMETER_STRING, from_msg.get_type()); EXPECT_EQ("string", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, from_msg.get_value()); - EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().string_value); + EXPECT_EQ(TEST_VALUE, from_msg.get_value_message().string_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_STRING, - from_msg.get_parameter_value().type); + from_msg.get_value_message().type); } TEST(TestParameter, byte_array_variant) { @@ -340,9 +340,9 @@ TEST(TestParameter, byte_array_variant) { EXPECT_EQ("byte_array", byte_array_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, byte_array_variant.get_value()); - EXPECT_EQ(TEST_VALUE, byte_array_variant.get_parameter_value().byte_array_value); + EXPECT_EQ(TEST_VALUE, byte_array_variant.get_value_message().byte_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY, - byte_array_variant.get_parameter_value().type); + byte_array_variant.get_value_message().type); EXPECT_EQ(TEST_VALUE, byte_array_variant.as_byte_array()); EXPECT_THROW(byte_array_variant.as_bool(), rclcpp::ParameterTypeException); @@ -369,9 +369,9 @@ TEST(TestParameter, byte_array_variant) { EXPECT_EQ("byte_array", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, from_msg.get_value()); - EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().byte_array_value); + EXPECT_EQ(TEST_VALUE, from_msg.get_value_message().byte_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY, - from_msg.get_parameter_value().type); + from_msg.get_value_message().type); } TEST(TestParameter, bool_array_variant) { @@ -384,9 +384,9 @@ TEST(TestParameter, bool_array_variant) { EXPECT_EQ("bool_array", bool_array_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, bool_array_variant.get_value()); - EXPECT_EQ(TEST_VALUE, bool_array_variant.get_parameter_value().bool_array_value); + EXPECT_EQ(TEST_VALUE, bool_array_variant.get_value_message().bool_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY, - bool_array_variant.get_parameter_value().type); + bool_array_variant.get_value_message().type); EXPECT_EQ(TEST_VALUE, bool_array_variant.as_bool_array()); EXPECT_THROW(bool_array_variant.as_bool(), rclcpp::ParameterTypeException); @@ -413,9 +413,9 @@ TEST(TestParameter, bool_array_variant) { EXPECT_EQ("bool_array", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, from_msg.get_value()); - EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().bool_array_value); + EXPECT_EQ(TEST_VALUE, from_msg.get_value_message().bool_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY, - from_msg.get_parameter_value().type); + from_msg.get_value_message().type); } TEST(TestParameter, integer_array_variant) { @@ -430,7 +430,7 @@ TEST(TestParameter, integer_array_variant) { integer_array_variant.get_type()); EXPECT_EQ("integer_array", integer_array_variant.get_type_name()); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY, - integer_array_variant.get_parameter_value().type); + integer_array_variant.get_value_message().type); // No direct comparison of vectors of ints and long ints const auto & param_value_ref = @@ -439,7 +439,7 @@ TEST(TestParameter, integer_array_variant) { EXPECT_EQ(TEST_VALUE.end(), mismatches.first); EXPECT_EQ(param_value_ref.end(), mismatches.second); - auto param_value = integer_array_variant.get_parameter_value().integer_array_value; + auto param_value = integer_array_variant.get_value_message().integer_array_value; mismatches = std::mismatch(TEST_VALUE.begin(), TEST_VALUE.end(), param_value.begin()); EXPECT_EQ(TEST_VALUE.end(), mismatches.first); EXPECT_EQ(param_value.end(), mismatches.second); @@ -484,12 +484,12 @@ TEST(TestParameter, integer_array_variant) { EXPECT_EQ(TEST_VALUE.end(), mismatches.first); EXPECT_EQ(param_value.end(), mismatches.second); - param_value = from_msg.get_parameter_value().integer_array_value; + param_value = from_msg.get_value_message().integer_array_value; mismatches = std::mismatch(TEST_VALUE.begin(), TEST_VALUE.end(), param_value.begin()); EXPECT_EQ(TEST_VALUE.end(), mismatches.first); EXPECT_EQ(param_value.end(), mismatches.second); - EXPECT_EQ(from_msg.get_parameter_value().type, + EXPECT_EQ(from_msg.get_value_message().type, rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY); } @@ -503,10 +503,10 @@ TEST(TestParameter, long_integer_array_variant) { long_array_variant.get_type()); EXPECT_EQ("integer_array", long_array_variant.get_type_name()); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY, - long_array_variant.get_parameter_value().type); + long_array_variant.get_value_message().type); EXPECT_EQ(TEST_VALUE, long_array_variant.get_value()); - EXPECT_EQ(TEST_VALUE, long_array_variant.get_parameter_value().integer_array_value); + EXPECT_EQ(TEST_VALUE, long_array_variant.get_value_message().integer_array_value); EXPECT_EQ(TEST_VALUE, long_array_variant.as_integer_array()); EXPECT_THROW(long_array_variant.as_bool(), rclcpp::ParameterTypeException); @@ -536,9 +536,9 @@ TEST(TestParameter, long_integer_array_variant) { EXPECT_EQ("integer_array", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, from_msg.get_value()); - EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().integer_array_value); + EXPECT_EQ(TEST_VALUE, from_msg.get_value_message().integer_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY, - from_msg.get_parameter_value().type); + from_msg.get_value_message().type); } TEST(TestParameter, float_array_variant) { @@ -553,7 +553,7 @@ TEST(TestParameter, float_array_variant) { float_array_variant.get_type()); EXPECT_EQ("double_array", float_array_variant.get_type_name()); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY, - float_array_variant.get_parameter_value().type); + float_array_variant.get_value_message().type); // No direct comparison of vectors of floats and doubles const auto & param_value_ref = @@ -562,7 +562,7 @@ TEST(TestParameter, float_array_variant) { EXPECT_EQ(TEST_VALUE.end(), mismatches.first); EXPECT_EQ(param_value_ref.end(), mismatches.second); - auto param_value = float_array_variant.get_parameter_value().double_array_value; + auto param_value = float_array_variant.get_value_message().double_array_value; mismatches = std::mismatch(TEST_VALUE.begin(), TEST_VALUE.end(), param_value.begin()); EXPECT_EQ(TEST_VALUE.end(), mismatches.first); EXPECT_EQ(param_value.end(), mismatches.second); @@ -607,13 +607,13 @@ TEST(TestParameter, float_array_variant) { EXPECT_EQ(TEST_VALUE.end(), mismatches.first); EXPECT_EQ(param_value.end(), mismatches.second); - param_value = from_msg.get_parameter_value().double_array_value; + param_value = from_msg.get_value_message().double_array_value; mismatches = std::mismatch(TEST_VALUE.begin(), TEST_VALUE.end(), param_value.begin()); EXPECT_EQ(TEST_VALUE.end(), mismatches.first); EXPECT_EQ(param_value.end(), mismatches.second); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY, - from_msg.get_parameter_value().type); + from_msg.get_value_message().type); } TEST(TestParameter, double_array_variant) { @@ -626,10 +626,10 @@ TEST(TestParameter, double_array_variant) { double_array_variant.get_type()); EXPECT_EQ("double_array", double_array_variant.get_type_name()); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY, - double_array_variant.get_parameter_value().type); + double_array_variant.get_value_message().type); EXPECT_EQ(TEST_VALUE, double_array_variant.get_value()); - EXPECT_EQ(TEST_VALUE, double_array_variant.get_parameter_value().double_array_value); + EXPECT_EQ(TEST_VALUE, double_array_variant.get_value_message().double_array_value); EXPECT_EQ(TEST_VALUE, double_array_variant.as_double_array()); EXPECT_THROW(double_array_variant.as_bool(), rclcpp::ParameterTypeException); @@ -659,9 +659,9 @@ TEST(TestParameter, double_array_variant) { EXPECT_EQ("double_array", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, from_msg.get_value()); - EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().double_array_value); + EXPECT_EQ(TEST_VALUE, from_msg.get_value_message().double_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY, - from_msg.get_parameter_value().type); + from_msg.get_value_message().type); } TEST(TestParameter, string_array_variant) { @@ -675,9 +675,9 @@ TEST(TestParameter, string_array_variant) { EXPECT_EQ("string_array", string_array_variant.get_type_name()); EXPECT_EQ(TEST_VALUE, string_array_variant.get_value()); - EXPECT_EQ(TEST_VALUE, string_array_variant.get_parameter_value().string_array_value); + EXPECT_EQ(TEST_VALUE, string_array_variant.get_value_message().string_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY, - string_array_variant.get_parameter_value().type); + string_array_variant.get_value_message().type); EXPECT_EQ(TEST_VALUE, string_array_variant.as_string_array()); EXPECT_THROW(string_array_variant.as_bool(), rclcpp::ParameterTypeException); @@ -705,7 +705,7 @@ TEST(TestParameter, string_array_variant) { EXPECT_EQ("string_array", from_msg.get_type_name()); EXPECT_EQ(TEST_VALUE, from_msg.get_value()); - EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().string_array_value); + EXPECT_EQ(TEST_VALUE, from_msg.get_value_message().string_array_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY, - from_msg.get_parameter_value().type); + from_msg.get_value_message().type); } From 6c441ca62c769f123fcde52a22ffcb76c4cb4f68 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 29 May 2018 15:03:15 -0700 Subject: [PATCH 06/17] 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); } From e182a0bf5d2c9edf5e4883914ae9e6d09e458294 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 29 May 2018 16:04:06 -0700 Subject: [PATCH 07/17] Add missing rclcpp:: --- rclcpp/src/rclcpp/parameter.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rclcpp/src/rclcpp/parameter.cpp b/rclcpp/src/rclcpp/parameter.cpp index ca9dd8547c..e15133bde2 100644 --- a/rclcpp/src/rclcpp/parameter.cpp +++ b/rclcpp/src/rclcpp/parameter.cpp @@ -28,7 +28,7 @@ Parameter::Parameter() { } -Parameter::Parameter(const std::string & name, const ParameterValue & value) +Parameter::Parameter(const std::string & name, const rclcpp::ParameterValue & value) : name_(name), value_(value) { } From 798880b705595559ce2bdc0f61b20185bc45b921 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 29 May 2018 16:23:58 -0700 Subject: [PATCH 08/17] array_to_string exists on ParameterValue --- rclcpp/include/rclcpp/parameter.hpp | 23 ----------------------- 1 file changed, 23 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter.hpp b/rclcpp/include/rclcpp/parameter.hpp index 26c8c0e261..b886cfe17e 100644 --- a/rclcpp/include/rclcpp/parameter.hpp +++ b/rclcpp/include/rclcpp/parameter.hpp @@ -126,29 +126,6 @@ class Parameter value_to_string() const; private: - template - std::string - array_to_string( - const std::vector & array, - const std::ios::fmtflags format_flags = std::ios::dec) const - { - std::stringstream type_array; - bool first_item = true; - type_array << "["; - type_array.setf(format_flags, std::ios_base::basefield | std::ios::boolalpha); - type_array << std::showbase; - for (const ValType value : array) { - if (!first_item) { - type_array << ", "; - } else { - first_item = false; - } - type_array << static_cast(value); - } - type_array << "]"; - return type_array.str(); - } - std::string name_; ParameterValue value_; }; From 69f3421f58a255f204ddb486e3d6cc0d4c9b5853 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 29 May 2018 16:26:54 -0700 Subject: [PATCH 09/17] Make to_parameter() const --- rclcpp/include/rclcpp/parameter.hpp | 2 +- rclcpp/src/rclcpp/parameter.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter.hpp b/rclcpp/include/rclcpp/parameter.hpp index b886cfe17e..e2d3dfde07 100644 --- a/rclcpp/include/rclcpp/parameter.hpp +++ b/rclcpp/include/rclcpp/parameter.hpp @@ -119,7 +119,7 @@ class Parameter RCLCPP_PUBLIC rcl_interfaces::msg::Parameter - to_parameter(); + to_parameter() const; RCLCPP_PUBLIC std::string diff --git a/rclcpp/src/rclcpp/parameter.cpp b/rclcpp/src/rclcpp/parameter.cpp index e15133bde2..4b86b343d0 100644 --- a/rclcpp/src/rclcpp/parameter.cpp +++ b/rclcpp/src/rclcpp/parameter.cpp @@ -118,7 +118,7 @@ Parameter::from_parameter(const rcl_interfaces::msg::Parameter & parameter) } rcl_interfaces::msg::Parameter -Parameter::to_parameter() +Parameter::to_parameter() const { rcl_interfaces::msg::Parameter parameter; parameter.name = name_; From 895bd4c8a4e8db657fdad4fae0b8ee1c992cc6ba Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 29 May 2018 17:08:56 -0700 Subject: [PATCH 10/17] Remove RCLCPP_PUBLIC before definition --- rclcpp/include/rclcpp/parameter.hpp | 1 - 1 file changed, 1 deletion(-) diff --git a/rclcpp/include/rclcpp/parameter.hpp b/rclcpp/include/rclcpp/parameter.hpp index e2d3dfde07..154303ae22 100644 --- a/rclcpp/include/rclcpp/parameter.hpp +++ b/rclcpp/include/rclcpp/parameter.hpp @@ -39,7 +39,6 @@ class Parameter Parameter(const std::string & name, const ParameterValue & value); template - RCLCPP_PUBLIC explicit Parameter(const std::string & name, ValueTypeT value) : Parameter(name, ParameterValue(value)) { From f0026290fe8cdddc8aa5e3966c13a139f401c51f Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 29 May 2018 17:50:39 -0700 Subject: [PATCH 11/17] Add RCLCPP_PUBLIC to methods --- rclcpp/include/rclcpp/parameter_value.hpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/rclcpp/include/rclcpp/parameter_value.hpp b/rclcpp/include/rclcpp/parameter_value.hpp index 1f7f527850..9a6a737fc4 100644 --- a/rclcpp/include/rclcpp/parameter_value.hpp +++ b/rclcpp/include/rclcpp/parameter_value.hpp @@ -49,10 +49,13 @@ class ParameterTypeException : public std::exception /// Construct an instance. /// \param[in] expected the expected parameter type. /// \param[in] actual the actual parameter type. + RCLCPP_PUBLIC ParameterTypeException(ParameterType expected, ParameterType actual); + RCLCPP_PUBLIC ~ParameterTypeException(); + RCLCPP_PUBLIC const char * what() const noexcept override; From a289f6302cfc84fa0e0c216a006517bfaf697a32 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 31 May 2018 16:10:43 -0700 Subject: [PATCH 12/17] ParameterTypeException inherit from runtime_error --- rclcpp/include/rclcpp/parameter_value.hpp | 34 +++++++++-------------- rclcpp/src/rclcpp/parameter_value.cpp | 16 ----------- 2 files changed, 13 insertions(+), 37 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter_value.hpp b/rclcpp/include/rclcpp/parameter_value.hpp index 9a6a737fc4..120f3619d1 100644 --- a/rclcpp/include/rclcpp/parameter_value.hpp +++ b/rclcpp/include/rclcpp/parameter_value.hpp @@ -42,25 +42,26 @@ enum ParameterType PARAMETER_STRING_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY, }; +/// Return the name of a parameter type +RCLCPP_PUBLIC +std::string +to_string(const ParameterType type); + +RCLCPP_PUBLIC +std::ostream & +operator<<(std::ostream & os, const ParameterType type); + /// Indicate the parameter type does not match the expected type. -class ParameterTypeException : public std::exception +class ParameterTypeException : public std::runtime_error { public: /// Construct an instance. /// \param[in] expected the expected parameter type. /// \param[in] actual the actual parameter type. RCLCPP_PUBLIC - ParameterTypeException(ParameterType expected, ParameterType actual); - - RCLCPP_PUBLIC - ~ParameterTypeException(); - - RCLCPP_PUBLIC - const char * - what() const noexcept override; - -private: - const std::string msg_; + ParameterTypeException(ParameterType expected, ParameterType actual) + : std::runtime_error("expected [" + to_string(expected) + "] got [" + to_string(actual) + "]") + {} }; /// Store the type and value of a parameter. @@ -308,15 +309,6 @@ RCLCPP_PUBLIC std::string to_string(const ParameterValue & type); -/// Return the name of a parameter type -RCLCPP_PUBLIC -std::string -to_string(const ParameterType type); - -RCLCPP_PUBLIC -std::ostream & -operator<<(std::ostream & os, const ParameterType type); - } // namespace rclcpp #endif // RCLCPP__PARAMETER_VALUE_HPP_ diff --git a/rclcpp/src/rclcpp/parameter_value.cpp b/rclcpp/src/rclcpp/parameter_value.cpp index c65da5bb3c..0bd5518ed0 100644 --- a/rclcpp/src/rclcpp/parameter_value.cpp +++ b/rclcpp/src/rclcpp/parameter_value.cpp @@ -18,7 +18,6 @@ #include using rclcpp::ParameterType; -using rclcpp::ParameterTypeException; using rclcpp::ParameterValue; std::string @@ -57,21 +56,6 @@ rclcpp::operator<<(std::ostream & os, const ParameterType type) return os; } -ParameterTypeException::ParameterTypeException(ParameterType expected, ParameterType actual) -: msg_("expected [" + rclcpp::to_string(expected) + "] got [" + rclcpp::to_string(actual) + "]") -{ -} - -ParameterTypeException::~ParameterTypeException() -{ -} - -const char * -ParameterTypeException::what() const throw () -{ - return msg_.c_str(); -} - template std::string array_to_string( From f8646d018123a1af062ac1f3c6cb9343871308ac Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 31 May 2018 16:17:06 -0700 Subject: [PATCH 13/17] decltype(auto) return type --- rclcpp/include/rclcpp/parameter.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter.hpp b/rclcpp/include/rclcpp/parameter.hpp index 154303ae22..8168c3c64f 100644 --- a/rclcpp/include/rclcpp/parameter.hpp +++ b/rclcpp/include/rclcpp/parameter.hpp @@ -62,7 +62,7 @@ class Parameter /// Get value of parameter using rclcpp::ParameterType as template argument. template - decltype(ParameterValue().get()) + decltype(auto) get_value() const { return value_.get(); @@ -70,7 +70,7 @@ class Parameter /// Get value of parameter using c++ types as template argument template - decltype(ParameterValue().get()) + decltype(auto) get_value() const { return value_.get(); From bea1335644d9a8c1b27d2c952a78c59b183581ef Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 31 May 2018 16:25:10 -0700 Subject: [PATCH 14/17] consistent doc block --- rclcpp/include/rclcpp/parameter_value.hpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter_value.hpp b/rclcpp/include/rclcpp/parameter_value.hpp index 120f3619d1..d6c6765400 100644 --- a/rclcpp/include/rclcpp/parameter_value.hpp +++ b/rclcpp/include/rclcpp/parameter_value.hpp @@ -56,8 +56,10 @@ class ParameterTypeException : public std::runtime_error { public: /// Construct an instance. - /// \param[in] expected the expected parameter type. - /// \param[in] actual the actual parameter type. + /** + * \param[in] expected the expected parameter type. + * \param[in] actual the actual parameter type. + */ RCLCPP_PUBLIC ParameterTypeException(ParameterType expected, ParameterType actual) : std::runtime_error("expected [" + to_string(expected) + "] got [" + to_string(actual) + "]") From 374b81a65b3a0a892b236a2813904463521a29bc Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 31 May 2018 16:26:13 -0700 Subject: [PATCH 15/17] Minor comment fixes --- rclcpp/include/rclcpp/parameter.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter.hpp b/rclcpp/include/rclcpp/parameter.hpp index 8168c3c64f..49332ae99a 100644 --- a/rclcpp/include/rclcpp/parameter.hpp +++ b/rclcpp/include/rclcpp/parameter.hpp @@ -28,7 +28,7 @@ namespace rclcpp { -// Structure to store an arbitrary parameter with templated get/set methods +/// Structure to store an arbitrary parameter with templated get/set methods. class Parameter { public: @@ -68,7 +68,7 @@ class Parameter return value_.get(); } - /// Get value of parameter using c++ types as template argument + /// Get value of parameter using c++ types as template argument. template decltype(auto) get_value() const From 18555dc06925e186d0eeae315288794581beec8c Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 31 May 2018 16:27:27 -0700 Subject: [PATCH 16/17] Add ParameterValue to main API comment --- rclcpp/include/rclcpp/rclcpp.hpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/rclcpp/include/rclcpp/rclcpp.hpp b/rclcpp/include/rclcpp/rclcpp.hpp index 11dfdab734..9465603148 100644 --- a/rclcpp/include/rclcpp/rclcpp.hpp +++ b/rclcpp/include/rclcpp/rclcpp.hpp @@ -50,9 +50,11 @@ * - rclcpp::Node::list_parameters() * - rclcpp::Node::register_param_change_callback() * - rclcpp::Parameter + * - rclcpp::ParameterValue * - rclcpp::AsyncParametersClient * - rclcpp::SyncParametersClient * - rclcpp/parameter.hpp + * - rclcpp/parameter_value.hpp * - rclcpp/parameter_client.hpp * - rclcpp/parameter_service.hpp * - Rate: From 22d89b9ba05bbfb38b389fb120ee31e76034f65b Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 31 May 2018 16:58:57 -0700 Subject: [PATCH 17/17] to_parameter_msg() from_parameter_msg() to_value_msg() --- rclcpp/include/rclcpp/parameter.hpp | 4 +- rclcpp/include/rclcpp/parameter_value.hpp | 2 +- .../node_interfaces/node_parameters.cpp | 6 +- rclcpp/src/rclcpp/parameter.cpp | 8 +-- rclcpp/src/rclcpp/parameter_client.cpp | 6 +- rclcpp/src/rclcpp/parameter_service.cpp | 4 +- rclcpp/src/rclcpp/parameter_value.cpp | 2 +- rclcpp/test/test_parameter.cpp | 58 +++++++++---------- 8 files changed, 45 insertions(+), 45 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter.hpp b/rclcpp/include/rclcpp/parameter.hpp index 49332ae99a..2da788061c 100644 --- a/rclcpp/include/rclcpp/parameter.hpp +++ b/rclcpp/include/rclcpp/parameter.hpp @@ -114,11 +114,11 @@ class Parameter RCLCPP_PUBLIC static Parameter - from_parameter(const rcl_interfaces::msg::Parameter & parameter); + from_parameter_msg(const rcl_interfaces::msg::Parameter & parameter); RCLCPP_PUBLIC rcl_interfaces::msg::Parameter - to_parameter() const; + to_parameter_msg() const; RCLCPP_PUBLIC std::string diff --git a/rclcpp/include/rclcpp/parameter_value.hpp b/rclcpp/include/rclcpp/parameter_value.hpp index d6c6765400..197cbdf4a7 100644 --- a/rclcpp/include/rclcpp/parameter_value.hpp +++ b/rclcpp/include/rclcpp/parameter_value.hpp @@ -127,7 +127,7 @@ class ParameterValue /// Return a message populated with the parameter value RCLCPP_PUBLIC rcl_interfaces::msg::ParameterValue - get_message() const; + to_value_msg() const; // The following get() variants require the use of ParameterType diff --git a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp index 7e5d4a399e..698330f4c6 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp @@ -91,18 +91,18 @@ NodeParameters::set_parameters_atomically( if (parameters_.find(p.get_name()) == parameters_.end()) { if (p.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET) { // case: parameter not set before, and input is something other than "NOT_SET" - parameter_event->new_parameters.push_back(p.to_parameter()); + parameter_event->new_parameters.push_back(p.to_parameter_msg()); } } else if (p.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET) { // case: parameter was set before, and input is something other than "NOT_SET" - parameter_event->changed_parameters.push_back(p.to_parameter()); + parameter_event->changed_parameters.push_back(p.to_parameter_msg()); } else { // case: parameter was set before, and input is "NOT_SET" // 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 // Parameter with type "NOT_SET" - parameter_event->deleted_parameters.push_back(p.to_parameter()); + parameter_event->deleted_parameters.push_back(p.to_parameter_msg()); } tmp_map[p.get_name()] = p; } diff --git a/rclcpp/src/rclcpp/parameter.cpp b/rclcpp/src/rclcpp/parameter.cpp index 4b86b343d0..374a1ff550 100644 --- a/rclcpp/src/rclcpp/parameter.cpp +++ b/rclcpp/src/rclcpp/parameter.cpp @@ -54,7 +54,7 @@ Parameter::get_name() const rcl_interfaces::msg::ParameterValue Parameter::get_value_message() const { - return value_.get_message(); + return value_.to_value_msg(); } bool @@ -112,17 +112,17 @@ Parameter::as_string_array() const } Parameter -Parameter::from_parameter(const rcl_interfaces::msg::Parameter & parameter) +Parameter::from_parameter_msg(const rcl_interfaces::msg::Parameter & parameter) { return Parameter(parameter.name, parameter.value); } rcl_interfaces::msg::Parameter -Parameter::to_parameter() const +Parameter::to_parameter_msg() const { rcl_interfaces::msg::Parameter parameter; parameter.name = name_; - parameter.value = value_.get_message(); + parameter.value = value_.to_value_msg(); return parameter; } diff --git a/rclcpp/src/rclcpp/parameter_client.cpp b/rclcpp/src/rclcpp/parameter_client.cpp index 144d897502..d3b3287a62 100644 --- a/rclcpp/src/rclcpp/parameter_client.cpp +++ b/rclcpp/src/rclcpp/parameter_client.cpp @@ -141,7 +141,7 @@ AsyncParametersClient::get_parameters( rcl_interfaces::msg::Parameter parameter; parameter.name = request->names[i]; parameter.value = pvalue; - parameters.push_back(rclcpp::Parameter::from_parameter( + parameters.push_back(rclcpp::Parameter::from_parameter_msg( parameter)); } @@ -204,7 +204,7 @@ AsyncParametersClient::set_parameters( std::transform(parameters.begin(), parameters.end(), std::back_inserter(request->parameters), [](rclcpp::Parameter p) { - return p.to_parameter(); + return p.to_parameter_msg(); } ); @@ -238,7 +238,7 @@ AsyncParametersClient::set_parameters_atomically( std::transform(parameters.begin(), parameters.end(), std::back_inserter(request->parameters), [](rclcpp::Parameter p) { - return p.to_parameter(); + return p.to_parameter_msg(); } ); diff --git a/rclcpp/src/rclcpp/parameter_service.cpp b/rclcpp/src/rclcpp/parameter_service.cpp index fbe2c0a09e..b978524ade 100644 --- a/rclcpp/src/rclcpp/parameter_service.cpp +++ b/rclcpp/src/rclcpp/parameter_service.cpp @@ -72,7 +72,7 @@ ParameterService::ParameterService( { std::vector pvariants; for (auto & p : request->parameters) { - pvariants.push_back(rclcpp::Parameter::from_parameter(p)); + pvariants.push_back(rclcpp::Parameter::from_parameter_msg(p)); } auto results = node_params->set_parameters(pvariants); response->results = results; @@ -91,7 +91,7 @@ ParameterService::ParameterService( std::transform(request->parameters.cbegin(), request->parameters.cend(), std::back_inserter(pvariants), [](const rcl_interfaces::msg::Parameter & p) { - return rclcpp::Parameter::from_parameter(p); + return rclcpp::Parameter::from_parameter_msg(p); }); auto result = node_params->set_parameters_atomically(pvariants); response->result = result; diff --git a/rclcpp/src/rclcpp/parameter_value.cpp b/rclcpp/src/rclcpp/parameter_value.cpp index 0bd5518ed0..be3ecbe763 100644 --- a/rclcpp/src/rclcpp/parameter_value.cpp +++ b/rclcpp/src/rclcpp/parameter_value.cpp @@ -224,7 +224,7 @@ ParameterValue::get_type() const } rcl_interfaces::msg::ParameterValue -ParameterValue::get_message() const +ParameterValue::to_value_msg() const { return value_; } diff --git a/rclcpp/test/test_parameter.cpp b/rclcpp/test/test_parameter.cpp index e7e1ce634b..6f7a120d80 100644 --- a/rclcpp/test/test_parameter.cpp +++ b/rclcpp/test/test_parameter.cpp @@ -48,12 +48,12 @@ TEST(TestParameter, not_set_variant) { EXPECT_THROW(not_set_variant.as_double_array(), rclcpp::ParameterTypeException); EXPECT_THROW(not_set_variant.as_string_array(), rclcpp::ParameterTypeException); - rcl_interfaces::msg::Parameter not_set_param = not_set_variant.to_parameter(); + rcl_interfaces::msg::Parameter not_set_param = not_set_variant.to_parameter_msg(); EXPECT_EQ("", not_set_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET, not_set_param.value.type); // From parameter message - EXPECT_THROW(rclcpp::Parameter::from_parameter(not_set_param), + EXPECT_THROW(rclcpp::Parameter::from_parameter_msg(not_set_param), std::runtime_error); } @@ -86,14 +86,14 @@ TEST(TestParameter, bool_variant) { EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, bool_variant_false.get_value_message().type); - rcl_interfaces::msg::Parameter bool_param = bool_variant_true.to_parameter(); + rcl_interfaces::msg::Parameter bool_param = bool_variant_true.to_parameter_msg(); EXPECT_EQ("bool_param", bool_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, bool_param.value.type); EXPECT_TRUE(bool_param.value.bool_value); // From parameter message rclcpp::Parameter from_msg_true = - rclcpp::Parameter::from_parameter(bool_param); + rclcpp::Parameter::from_parameter_msg(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()); @@ -104,7 +104,7 @@ TEST(TestParameter, bool_variant) { bool_param.value.bool_value = false; rclcpp::Parameter from_msg_false = - rclcpp::Parameter::from_parameter(bool_param); + rclcpp::Parameter::from_parameter_msg(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, @@ -137,14 +137,14 @@ TEST(TestParameter, integer_variant) { EXPECT_EQ("42", integer_variant.value_to_string()); - rcl_interfaces::msg::Parameter integer_param = integer_variant.to_parameter(); + rcl_interfaces::msg::Parameter integer_param = integer_variant.to_parameter_msg(); EXPECT_EQ("integer_param", integer_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, integer_param.value.type); EXPECT_EQ(TEST_VALUE, integer_param.value.integer_value); // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(integer_param); + rclcpp::Parameter::from_parameter_msg(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()); @@ -181,14 +181,14 @@ TEST(TestParameter, long_integer_variant) { EXPECT_EQ("9223372036854775807", long_variant.value_to_string()); - rcl_interfaces::msg::Parameter integer_param = long_variant.to_parameter(); + rcl_interfaces::msg::Parameter integer_param = long_variant.to_parameter_msg(); EXPECT_EQ("long_integer_param", integer_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, integer_param.value.type); EXPECT_EQ(TEST_VALUE, integer_param.value.integer_value); // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(integer_param); + rclcpp::Parameter::from_parameter_msg(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()); @@ -225,14 +225,14 @@ TEST(TestParameter, float_variant) { EXPECT_EQ("42.000000", float_variant.value_to_string()); - rcl_interfaces::msg::Parameter float_param = float_variant.to_parameter(); + rcl_interfaces::msg::Parameter float_param = float_variant.to_parameter_msg(); EXPECT_EQ("float_param", float_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE, float_param.value.type); EXPECT_EQ(TEST_VALUE, float_param.value.double_value); // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(float_param); + rclcpp::Parameter::from_parameter_msg(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()); @@ -269,14 +269,14 @@ TEST(TestParameter, double_variant) { EXPECT_EQ("-42.100000", double_variant.value_to_string()); - rcl_interfaces::msg::Parameter double_param = double_variant.to_parameter(); + rcl_interfaces::msg::Parameter double_param = double_variant.to_parameter_msg(); EXPECT_EQ("double_param", double_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE, double_param.value.type); EXPECT_EQ(TEST_VALUE, double_param.value.double_value); // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(double_param); + rclcpp::Parameter::from_parameter_msg(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()); @@ -313,14 +313,14 @@ TEST(TestParameter, string_variant) { EXPECT_EQ(TEST_VALUE, string_variant.value_to_string()); - rcl_interfaces::msg::Parameter string_param = string_variant.to_parameter(); + rcl_interfaces::msg::Parameter string_param = string_variant.to_parameter_msg(); EXPECT_EQ("string_param", string_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_STRING, string_param.value.type); EXPECT_EQ(TEST_VALUE, string_param.value.string_value); // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(string_param); + rclcpp::Parameter::from_parameter_msg(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()); @@ -356,14 +356,14 @@ TEST(TestParameter, byte_array_variant) { EXPECT_EQ("[0x52, 0x4f, 0x53, 0x32]", byte_array_variant.value_to_string()); - rcl_interfaces::msg::Parameter byte_array_param = byte_array_variant.to_parameter(); + rcl_interfaces::msg::Parameter byte_array_param = byte_array_variant.to_parameter_msg(); EXPECT_EQ("byte_array_param", byte_array_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY, byte_array_param.value.type); EXPECT_EQ(TEST_VALUE, byte_array_param.value.byte_array_value); // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(byte_array_param); + rclcpp::Parameter::from_parameter_msg(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()); @@ -400,14 +400,14 @@ TEST(TestParameter, bool_array_variant) { EXPECT_EQ("[false, true, true, false, false, true]", bool_array_variant.value_to_string()); - rcl_interfaces::msg::Parameter bool_array_param = bool_array_variant.to_parameter(); + rcl_interfaces::msg::Parameter bool_array_param = bool_array_variant.to_parameter_msg(); EXPECT_EQ("bool_array_param", bool_array_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY, bool_array_param.value.type); EXPECT_EQ(TEST_VALUE, bool_array_param.value.bool_array_value); // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(bool_array_param); + rclcpp::Parameter::from_parameter_msg(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()); @@ -462,7 +462,7 @@ TEST(TestParameter, integer_array_variant) { "[42, -99, 2147483647, -2147483648, 0]", integer_array_variant.value_to_string()); - rcl_interfaces::msg::Parameter integer_array_param = integer_array_variant.to_parameter(); + rcl_interfaces::msg::Parameter integer_array_param = integer_array_variant.to_parameter_msg(); EXPECT_EQ("integer_array_param", integer_array_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY, integer_array_param.value.type); @@ -474,7 +474,7 @@ TEST(TestParameter, integer_array_variant) { // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(integer_array_param); + rclcpp::Parameter::from_parameter_msg(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()); @@ -522,7 +522,7 @@ TEST(TestParameter, long_integer_array_variant) { "[42, -99, 9223372036854775807, -9223372036854775808, 0]", long_array_variant.value_to_string()); - rcl_interfaces::msg::Parameter integer_array_param = long_array_variant.to_parameter(); + rcl_interfaces::msg::Parameter integer_array_param = long_array_variant.to_parameter_msg(); EXPECT_EQ("long_integer_array_param", integer_array_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY, integer_array_param.value.type); @@ -530,7 +530,7 @@ TEST(TestParameter, long_integer_array_variant) { // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(integer_array_param); + rclcpp::Parameter::from_parameter_msg(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()); @@ -585,7 +585,7 @@ TEST(TestParameter, float_array_variant) { "[42.1, -99.1, 3.40282e+38, -3.40282e+38, 0.1]", float_array_variant.value_to_string()); - rcl_interfaces::msg::Parameter float_array_param = float_array_variant.to_parameter(); + rcl_interfaces::msg::Parameter float_array_param = float_array_variant.to_parameter_msg(); EXPECT_EQ("float_array_param", float_array_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY, float_array_param.value.type); @@ -597,7 +597,7 @@ TEST(TestParameter, float_array_variant) { // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(float_array_param); + rclcpp::Parameter::from_parameter_msg(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()); @@ -645,7 +645,7 @@ TEST(TestParameter, double_array_variant) { "[42.1, -99.1, 1.79769e+308, -1.79769e+308, 0.1]", double_array_variant.value_to_string()); - rcl_interfaces::msg::Parameter double_array_param = double_array_variant.to_parameter(); + rcl_interfaces::msg::Parameter double_array_param = double_array_variant.to_parameter_msg(); EXPECT_EQ("double_array_param", double_array_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY, double_array_param.value.type); @@ -653,7 +653,7 @@ TEST(TestParameter, double_array_variant) { // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(double_array_param); + rclcpp::Parameter::from_parameter_msg(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()); @@ -691,7 +691,7 @@ TEST(TestParameter, string_array_variant) { EXPECT_EQ("[R, O, S2]", string_array_variant.value_to_string()); - rcl_interfaces::msg::Parameter string_array_param = string_array_variant.to_parameter(); + rcl_interfaces::msg::Parameter string_array_param = string_array_variant.to_parameter_msg(); EXPECT_EQ("string_array_param", string_array_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY, string_array_param.value.type); @@ -699,7 +699,7 @@ TEST(TestParameter, string_array_variant) { // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(string_array_param); + rclcpp::Parameter::from_parameter_msg(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());