Split ParameterVariant into Parameter and ParameterValue (#481)

* Split ParametrVariant into Parameter and ParameterValue
* Test expects ParameterTypeException
* get_parameter_value() -> get_value_message()
* Make to_parameter() const and rename to to_parameter_msg()
This commit is contained in:
Shane Loretz 2018-06-01 11:48:56 -07:00 committed by GitHub
parent 97575fd59b
commit d298fa4445
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
21 changed files with 997 additions and 872 deletions

View file

@ -59,6 +59,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

View file

@ -256,11 +256,11 @@ public:
RCLCPP_PUBLIC
std::vector<rcl_interfaces::msg::SetParametersResult>
set_parameters(const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
set_parameters(const std::vector<rclcpp::Parameter> & parameters);
RCLCPP_PUBLIC
rcl_interfaces::msg::SetParametersResult
set_parameters_atomically(const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters);
template<typename ParameterT>
void
@ -269,18 +269,18 @@ public:
const ParameterT & value);
RCLCPP_PUBLIC
std::vector<rclcpp::parameter::ParameterVariant>
std::vector<rclcpp::Parameter>
get_parameters(const std::vector<std::string> & 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.
/**

View file

@ -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<typename ParameterT>
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<ParameterT>();
value = parameter.get_value<ParameterT>();
}
return result;

View file

@ -62,22 +62,22 @@ public:
virtual
std::vector<rcl_interfaces::msg::SetParametersResult>
set_parameters(
const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
const std::vector<rclcpp::Parameter> & parameters);
RCLCPP_PUBLIC
virtual
rcl_interfaces::msg::SetParametersResult
set_parameters_atomically(
const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
const std::vector<rclcpp::Parameter> & parameters);
RCLCPP_PUBLIC
virtual
std::vector<rclcpp::parameter::ParameterVariant>
std::vector<rclcpp::Parameter>
get_parameters(const std::vector<std::string> & names) const;
RCLCPP_PUBLIC
virtual
rclcpp::parameter::ParameterVariant
rclcpp::Parameter
get_parameter(const std::string & name) const;
RCLCPP_PUBLIC
@ -85,7 +85,7 @@ public:
bool
get_parameter(
const std::string & name,
rclcpp::parameter::ParameterVariant & parameter) const;
rclcpp::Parameter & parameter) const;
RCLCPP_PUBLIC
virtual
@ -114,7 +114,7 @@ private:
ParametersCallbackFunction parameters_callback_ = nullptr;
std::map<std::string, rclcpp::parameter::ParameterVariant> parameters_;
std::map<std::string, rclcpp::Parameter> parameters_;
Publisher<rcl_interfaces::msg::ParameterEvent>::SharedPtr events_publisher_;

View file

@ -41,22 +41,22 @@ public:
virtual
std::vector<rcl_interfaces::msg::SetParametersResult>
set_parameters(
const std::vector<rclcpp::parameter::ParameterVariant> & parameters) = 0;
const std::vector<rclcpp::Parameter> & parameters) = 0;
RCLCPP_PUBLIC
virtual
rcl_interfaces::msg::SetParametersResult
set_parameters_atomically(
const std::vector<rclcpp::parameter::ParameterVariant> & parameters) = 0;
const std::vector<rclcpp::Parameter> & parameters) = 0;
RCLCPP_PUBLIC
virtual
std::vector<rclcpp::parameter::ParameterVariant>
std::vector<rclcpp::Parameter>
get_parameters(const std::vector<std::string> & 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 @@ public:
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 @@ public:
using ParametersCallbackFunction = std::function<
rcl_interfaces::msg::SetParametersResult(
const std::vector<rclcpp::parameter::ParameterVariant> &)>;
const std::vector<rclcpp::Parameter> &)>;
RCLCPP_PUBLIC
virtual

View file

@ -22,78 +22,27 @@
#include <vector>
#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
{
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
/// Structure to store an arbitrary parameter with templated get/set methods.
class Parameter
{
public:
RCLCPP_PUBLIC
ParameterVariant();
Parameter();
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<uint8_t> & byte_array_value);
RCLCPP_PUBLIC
explicit ParameterVariant(
const std::string & name,
const std::vector<bool> & bool_array_value);
RCLCPP_PUBLIC
explicit ParameterVariant(
const std::string & name,
const std::vector<int> & int_array_value);
RCLCPP_PUBLIC
explicit ParameterVariant(
const std::string & name,
const std::vector<int64_t> & int_array_value);
RCLCPP_PUBLIC
explicit ParameterVariant(
const std::string & name,
const std::vector<float> & double_array_value);
RCLCPP_PUBLIC
explicit ParameterVariant(
const std::string & name,
const std::vector<double> & double_array_value);
RCLCPP_PUBLIC
explicit ParameterVariant(
const std::string & name,
const std::vector<std::string> & string_array_value);
Parameter(const std::string & name, const ParameterValue & value);
template<typename ValueTypeT>
explicit Parameter(const std::string & name, ValueTypeT value)
: Parameter(name, ParameterValue(value))
{
}
RCLCPP_PUBLIC
ParameterType
@ -109,188 +58,22 @@ public:
RCLCPP_PUBLIC
rcl_interfaces::msg::ParameterValue
get_parameter_value() const;
get_value_message() const;
// The following get_value() variants require the use of ParameterType
template<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_BOOL, bool>::type
/// Get value of parameter using rclcpp::ParameterType as template argument.
template<ParameterType ParamT>
decltype(auto)
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;
return value_.get<ParamT>();
}
template<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_INTEGER, int64_t>::type
/// Get value of parameter using c++ types as template argument.
template<typename T>
decltype(auto)
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<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_DOUBLE, double>::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<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_STRING, const std::string &>::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<ParameterType type>
typename std::enable_if<
type == ParameterType::PARAMETER_BYTE_ARRAY, const std::vector<uint8_t> &>::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<ParameterType type>
typename std::enable_if<
type == ParameterType::PARAMETER_BOOL_ARRAY, const std::vector<bool> &>::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<ParameterType type>
typename std::enable_if<
type == ParameterType::PARAMETER_INTEGER_ARRAY, const std::vector<int64_t> &>::type
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<ParameterType type>
typename std::enable_if<
type == ParameterType::PARAMETER_DOUBLE_ARRAY, const std::vector<double> &>::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<ParameterType type>
typename std::enable_if<
type == ParameterType::PARAMETER_STRING_ARRAY, const std::vector<std::string> &>::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 type>
typename std::enable_if<std::is_same<type, bool>::value, bool>::type
get_value() const
{
return get_value<ParameterType::PARAMETER_BOOL>();
}
template<typename type>
typename std::enable_if<
std::is_integral<type>::value && !std::is_same<type, bool>::value, int64_t>::type
get_value() const
{
return get_value<ParameterType::PARAMETER_INTEGER>();
}
template<typename type>
typename std::enable_if<std::is_floating_point<type>::value, double>::type
get_value() const
{
return get_value<ParameterType::PARAMETER_DOUBLE>();
}
template<typename type>
typename std::enable_if<std::is_convertible<type, std::string>::value, const std::string &>::type
get_value() const
{
return get_value<ParameterType::PARAMETER_STRING>();
}
template<typename type>
typename std::enable_if<
std::is_convertible<
type, const std::vector<uint8_t> &>::value, const std::vector<uint8_t> &>::type
get_value() const
{
return get_value<ParameterType::PARAMETER_BYTE_ARRAY>();
}
template<typename type>
typename std::enable_if<
std::is_convertible<
type, const std::vector<bool> &>::value, const std::vector<bool> &>::type
get_value() const
{
return get_value<ParameterType::PARAMETER_BOOL_ARRAY>();
}
template<typename type>
typename std::enable_if<
std::is_convertible<
type, const std::vector<int64_t> &>::value, const std::vector<int64_t> &>::type
get_value() const
{
return get_value<ParameterType::PARAMETER_INTEGER_ARRAY>();
}
template<typename type>
typename std::enable_if<
std::is_convertible<
type, const std::vector<double> &>::value, const std::vector<double> &>::type
get_value() const
{
return get_value<ParameterType::PARAMETER_DOUBLE_ARRAY>();
}
template<typename type>
typename std::enable_if<
std::is_convertible<
type, const std::vector<std::string> &>::value, const std::vector<std::string> &>::type
get_value() const
{
return get_value<ParameterType::PARAMETER_STRING_ARRAY>();
return value_.get<T>();
}
RCLCPP_PUBLIC
@ -330,65 +113,35 @@ public:
as_string_array() const;
RCLCPP_PUBLIC
static ParameterVariant
from_parameter(const rcl_interfaces::msg::Parameter & parameter);
static Parameter
from_parameter_msg(const rcl_interfaces::msg::Parameter & parameter);
RCLCPP_PUBLIC
rcl_interfaces::msg::Parameter
to_parameter();
to_parameter_msg() const;
RCLCPP_PUBLIC
std::string
value_to_string() const;
private:
template<typename ValType, typename PrintType = ValType>
std::string
array_to_string(
const std::vector<ValType> & 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<PrintType>(value);
}
type_array << "]";
return type_array.str();
}
template<typename OutputType, typename InputType>
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.
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<ParameterVariant> & parameters);
operator<<(std::ostream & os, const std::vector<Parameter> & parameters);
} // namespace parameter
} // namespace rclcpp
namespace std
@ -397,12 +150,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<rclcpp::parameter::ParameterVariant> & parameters);
to_string(const std::vector<rclcpp::Parameter> & parameters);
} // namespace std

View file

@ -68,25 +68,25 @@ public:
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
RCLCPP_PUBLIC
std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>>
std::shared_future<std::vector<rclcpp::Parameter>>
get_parameters(
const std::vector<std::string> & names,
std::function<
void(std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>>)
void(std::shared_future<std::vector<rclcpp::Parameter>>)
> callback = nullptr);
RCLCPP_PUBLIC
std::shared_future<std::vector<rclcpp::parameter::ParameterType>>
std::shared_future<std::vector<rclcpp::ParameterType>>
get_parameter_types(
const std::vector<std::string> & names,
std::function<
void(std::shared_future<std::vector<rclcpp::parameter::ParameterType>>)
void(std::shared_future<std::vector<rclcpp::ParameterType>>)
> callback = nullptr);
RCLCPP_PUBLIC
std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
set_parameters(
const std::vector<rclcpp::parameter::ParameterVariant> & parameters,
const std::vector<rclcpp::Parameter> & parameters,
std::function<
void(std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>)
> callback = nullptr);
@ -94,7 +94,7 @@ public:
RCLCPP_PUBLIC
std::shared_future<rcl_interfaces::msg::SetParametersResult>
set_parameters_atomically(
const std::vector<rclcpp::parameter::ParameterVariant> & parameters,
const std::vector<rclcpp::Parameter> & parameters,
std::function<
void(std::shared_future<rcl_interfaces::msg::SetParametersResult>)
> callback = nullptr);
@ -185,7 +185,7 @@ public:
const rmw_qos_profile_t & qos_profile = rmw_qos_profile_parameters);
RCLCPP_PUBLIC
std::vector<rclcpp::parameter::ParameterVariant>
std::vector<rclcpp::Parameter>
get_parameters(const std::vector<std::string> & parameter_names);
RCLCPP_PUBLIC
@ -200,7 +200,7 @@ public:
std::vector<std::string> 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<T>(vars[0].get_value<T>());
@ -226,16 +226,16 @@ public:
}
RCLCPP_PUBLIC
std::vector<rclcpp::parameter::ParameterType>
std::vector<rclcpp::ParameterType>
get_parameter_types(const std::vector<std::string> & parameter_names);
RCLCPP_PUBLIC
std::vector<rcl_interfaces::msg::SetParametersResult>
set_parameters(const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
set_parameters(const std::vector<rclcpp::Parameter> & parameters);
RCLCPP_PUBLIC
rcl_interfaces::msg::SetParametersResult
set_parameters_atomically(const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters);
RCLCPP_PUBLIC
rcl_interfaces::msg::ListParametersResult

View file

@ -0,0 +1,316 @@
// 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 <exception>
#include <iostream>
#include <ostream>
#include <sstream>
#include <string>
#include <vector>
#include "rcl_interfaces/msg/parameter_type.hpp"
#include "rcl_interfaces/msg/parameter_value.hpp"
#include "rclcpp/visibility_control.hpp"
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::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)
: std::runtime_error("expected [" + to_string(expected) + "] got [" + to_string(actual) + "]")
{}
};
/// 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<uint8_t> & byte_array_value);
/// Construct a parameter value with type PARAMETER_BOOL_ARRAY.
RCLCPP_PUBLIC
explicit ParameterValue(const std::vector<bool> & bool_array_value);
/// Construct a parameter value with type PARAMETER_INTEGER_ARRAY.
RCLCPP_PUBLIC
explicit ParameterValue(const std::vector<int> & int_array_value);
/// Construct a parameter value with type PARAMETER_INTEGER_ARRAY.
RCLCPP_PUBLIC
explicit ParameterValue(const std::vector<int64_t> & int_array_value);
/// Construct a parameter value with type PARAMETER_DOUBLE_ARRAY.
RCLCPP_PUBLIC
explicit ParameterValue(const std::vector<float> & double_array_value);
/// Construct a parameter value with type PARAMETER_DOUBLE_ARRAY.
RCLCPP_PUBLIC
explicit ParameterValue(const std::vector<double> & double_array_value);
/// Construct a parameter value with type PARAMETER_STRING_ARRAY.
RCLCPP_PUBLIC
explicit ParameterValue(const std::vector<std::string> & 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
to_value_msg() const;
// The following get() variants require the use of ParameterType
template<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_BOOL, bool>::type
get() const
{
if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
throw ParameterTypeException(ParameterType::PARAMETER_BOOL, get_type());
}
return value_.bool_value;
}
template<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_INTEGER, int64_t>::type
get() const
{
if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER) {
throw ParameterTypeException(ParameterType::PARAMETER_INTEGER, get_type());
}
return value_.integer_value;
}
template<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_DOUBLE, double>::type
get() const
{
if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) {
throw ParameterTypeException(ParameterType::PARAMETER_DOUBLE, get_type());
}
return value_.double_value;
}
template<ParameterType type>
typename std::enable_if<type == ParameterType::PARAMETER_STRING, const std::string &>::type
get() const
{
if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_STRING) {
throw ParameterTypeException(ParameterType::PARAMETER_STRING, get_type());
}
return value_.string_value;
}
template<ParameterType type>
typename std::enable_if<
type == ParameterType::PARAMETER_BYTE_ARRAY, const std::vector<uint8_t> &>::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<ParameterType type>
typename std::enable_if<
type == ParameterType::PARAMETER_BOOL_ARRAY, const std::vector<bool> &>::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<ParameterType type>
typename std::enable_if<
type == ParameterType::PARAMETER_INTEGER_ARRAY, const std::vector<int64_t> &>::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<ParameterType type>
typename std::enable_if<
type == ParameterType::PARAMETER_DOUBLE_ARRAY, const std::vector<double> &>::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<ParameterType type>
typename std::enable_if<
type == ParameterType::PARAMETER_STRING_ARRAY, const std::vector<std::string> &>::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 type>
typename std::enable_if<std::is_same<type, bool>::value, bool>::type
get() const
{
return get<ParameterType::PARAMETER_BOOL>();
}
template<typename type>
typename std::enable_if<
std::is_integral<type>::value && !std::is_same<type, bool>::value, int64_t>::type
get() const
{
return get<ParameterType::PARAMETER_INTEGER>();
}
template<typename type>
typename std::enable_if<std::is_floating_point<type>::value, double>::type
get() const
{
return get<ParameterType::PARAMETER_DOUBLE>();
}
template<typename type>
typename std::enable_if<std::is_convertible<type, std::string>::value, const std::string &>::type
get() const
{
return get<ParameterType::PARAMETER_STRING>();
}
template<typename type>
typename std::enable_if<
std::is_convertible<
type, const std::vector<uint8_t> &>::value, const std::vector<uint8_t> &>::type
get() const
{
return get<ParameterType::PARAMETER_BYTE_ARRAY>();
}
template<typename type>
typename std::enable_if<
std::is_convertible<
type, const std::vector<bool> &>::value, const std::vector<bool> &>::type
get() const
{
return get<ParameterType::PARAMETER_BOOL_ARRAY>();
}
template<typename type>
typename std::enable_if<
std::is_convertible<
type, const std::vector<int64_t> &>::value, const std::vector<int64_t> &>::type
get() const
{
return get<ParameterType::PARAMETER_INTEGER_ARRAY>();
}
template<typename type>
typename std::enable_if<
std::is_convertible<
type, const std::vector<double> &>::value, const std::vector<double> &>::type
get() const
{
return get<ParameterType::PARAMETER_DOUBLE_ARRAY>();
}
template<typename type>
typename std::enable_if<
std::is_convertible<
type, const std::vector<std::string> &>::value, const std::vector<std::string> &>::type
get() const
{
return get<ParameterType::PARAMETER_STRING_ARRAY>();
}
private:
rcl_interfaces::msg::ParameterValue value_;
};
/// Return the value of a parameter as a string
RCLCPP_PUBLIC
std::string
to_string(const ParameterValue & type);
} // namespace rclcpp
#endif // RCLCPP__PARAMETER_VALUE_HPP_

View file

@ -49,10 +49,12 @@
* - rclcpp::Node::describe_parameters()
* - rclcpp::Node::list_parameters()
* - rclcpp::Node::register_param_change_callback()
* - rclcpp::parameter::ParameterVariant
* - rclcpp::Parameter
* - rclcpp::ParameterValue
* - rclcpp::AsyncParametersClient
* - rclcpp::SyncParametersClient
* - rclcpp/parameter.hpp
* - rclcpp/parameter_value.hpp
* - rclcpp/parameter_client.hpp
* - rclcpp/parameter_service.hpp
* - Rate:

View file

@ -117,26 +117,26 @@ Node::group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr group)
std::vector<rcl_interfaces::msg::SetParametersResult>
Node::set_parameters(
const std::vector<rclcpp::parameter::ParameterVariant> & parameters)
const std::vector<rclcpp::Parameter> & parameters)
{
return node_parameters_->set_parameters(parameters);
}
rcl_interfaces::msg::SetParametersResult
Node::set_parameters_atomically(
const std::vector<rclcpp::parameter::ParameterVariant> & parameters)
const std::vector<rclcpp::Parameter> & parameters)
{
return node_parameters_->set_parameters_atomically(parameters);
}
std::vector<rclcpp::parameter::ParameterVariant>
std::vector<rclcpp::Parameter>
Node::get_parameters(
const std::vector<std::string> & 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);
}

View file

@ -57,7 +57,7 @@ NodeParameters::~NodeParameters()
std::vector<rcl_interfaces::msg::SetParametersResult>
NodeParameters::set_parameters(
const std::vector<rclcpp::parameter::ParameterVariant> & parameters)
const std::vector<rclcpp::Parameter> & parameters)
{
std::vector<rcl_interfaces::msg::SetParametersResult> results;
for (auto p : parameters) {
@ -69,10 +69,10 @@ NodeParameters::set_parameters(
rcl_interfaces::msg::SetParametersResult
NodeParameters::set_parameters_atomically(
const std::vector<rclcpp::parameter::ParameterVariant> & parameters)
const std::vector<rclcpp::Parameter> & parameters)
{
std::lock_guard<std::mutex> lock(mutex_);
std::map<std::string, rclcpp::parameter::ParameterVariant> tmp_map;
std::map<std::string, rclcpp::Parameter> tmp_map;
auto parameter_event = std::make_shared<rcl_interfaces::msg::ParameterEvent>();
// TODO(jacquelinekay): handle parameter constraints
@ -89,20 +89,20 @@ 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());
parameter_event->new_parameters.push_back(p.to_parameter_msg());
}
} 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());
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
// ParameterVariant with type "NOT_SET"
parameter_event->deleted_parameters.push_back(p.to_parameter());
// Parameter with type "NOT_SET"
parameter_event->deleted_parameters.push_back(p.to_parameter_msg());
}
tmp_map[p.get_name()] = p;
}
@ -116,15 +116,15 @@ NodeParameters::set_parameters_atomically(
return result;
}
std::vector<rclcpp::parameter::ParameterVariant>
std::vector<rclcpp::Parameter>
NodeParameters::get_parameters(const std::vector<std::string> & names) const
{
std::lock_guard<std::mutex> lock(mutex_);
std::vector<rclcpp::parameter::ParameterVariant> results;
std::vector<rclcpp::Parameter> results;
for (auto & name : names) {
if (std::any_of(parameters_.cbegin(), parameters_.cend(),
[&name](const std::pair<std::string, rclcpp::parameter::ParameterVariant> & kv) {
[&name](const std::pair<std::string, rclcpp::Parameter> & kv) {
return name == kv.first;
}))
{
@ -134,10 +134,10 @@ NodeParameters::get_parameters(const std::vector<std::string> & 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<std::mutex> lock(mutex_);

View file

@ -20,297 +20,120 @@
#include "rclcpp/parameter.hpp"
#include "rclcpp/utilities.hpp"
using rclcpp::parameter::ParameterType;
using rclcpp::parameter::ParameterVariant;
using rclcpp::ParameterType;
using rclcpp::Parameter;
ParameterVariant::ParameterVariant()
Parameter::Parameter()
: name_("")
{
value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET;
}
ParameterVariant::ParameterVariant(const std::string & name, const bool bool_value)
: name_(name)
Parameter::Parameter(const std::string & name, const rclcpp::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<uint8_t> & 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> & 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> & 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<int64_t> & 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<float> & 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> & 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<std::string> & 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
Parameter::get_type() const
{
return static_cast<ParameterType>(value_.type);
return value_.get_type();
}
std::string
ParameterVariant::get_type_name() const
Parameter::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 &
ParameterVariant::get_name() const
Parameter::get_name() const
{
return name_;
}
rcl_interfaces::msg::ParameterValue
ParameterVariant::get_parameter_value() const
Parameter::get_value_message() const
{
return value_;
return value_.to_value_msg();
}
bool
ParameterVariant::as_bool() const
Parameter::as_bool() const
{
return get_value<ParameterType::PARAMETER_BOOL>();
}
int64_t
ParameterVariant::as_int() const
Parameter::as_int() const
{
return get_value<ParameterType::PARAMETER_INTEGER>();
}
double
ParameterVariant::as_double() const
Parameter::as_double() const
{
return get_value<ParameterType::PARAMETER_DOUBLE>();
}
const std::string &
ParameterVariant::as_string() const
Parameter::as_string() const
{
return get_value<ParameterType::PARAMETER_STRING>();
}
const std::vector<uint8_t> &
ParameterVariant::as_byte_array() const
Parameter::as_byte_array() const
{
return get_value<ParameterType::PARAMETER_BYTE_ARRAY>();
}
const std::vector<bool> &
ParameterVariant::as_bool_array() const
Parameter::as_bool_array() const
{
return get_value<ParameterType::PARAMETER_BOOL_ARRAY>();
}
const std::vector<int64_t> &
ParameterVariant::as_integer_array() const
Parameter::as_integer_array() const
{
return get_value<ParameterType::PARAMETER_INTEGER_ARRAY>();
}
const std::vector<double> &
ParameterVariant::as_double_array() const
Parameter::as_double_array() const
{
return get_value<ParameterType::PARAMETER_DOUBLE_ARRAY>();
}
const std::vector<std::string> &
ParameterVariant::as_string_array() const
Parameter::as_string_array() const
{
return get_value<ParameterType::PARAMETER_STRING_ARRAY>();
}
ParameterVariant
ParameterVariant::from_parameter(const rcl_interfaces::msg::Parameter & parameter)
Parameter
Parameter::from_parameter_msg(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 Parameter(parameter.name, parameter.value);
}
rcl_interfaces::msg::Parameter
ParameterVariant::to_parameter()
Parameter::to_parameter_msg() const
{
rcl_interfaces::msg::Parameter parameter;
parameter.name = name_;
parameter.value = value_;
parameter.value = value_.to_value_msg();
return parameter;
}
std::string
ParameterVariant::value_to_string() const
Parameter::value_to_string() const
{
switch (get_type()) {
case rclcpp::parameter::ParameterType::PARAMETER_NOT_SET:
return "not set";
case rclcpp::parameter::ParameterType::PARAMETER_BOOL:
return as_bool() ? "true" : "false";
case rclcpp::parameter::ParameterType::PARAMETER_INTEGER:
return std::to_string(as_int());
case rclcpp::parameter::ParameterType::PARAMETER_DOUBLE:
return std::to_string(as_double());
case rclcpp::parameter::ParameterType::PARAMETER_STRING:
return as_string();
case rclcpp::parameter::ParameterType::PARAMETER_BYTE_ARRAY:
return array_to_string<uint8_t, int>(as_byte_array(), std::ios::hex);
case rclcpp::parameter::ParameterType::PARAMETER_BOOL_ARRAY:
return array_to_string(as_bool_array(), std::ios::boolalpha);
case rclcpp::parameter::ParameterType::PARAMETER_INTEGER_ARRAY:
return array_to_string(as_integer_array());
case rclcpp::parameter::ParameterType::PARAMETER_DOUBLE_ARRAY:
return array_to_string(as_double_array());
case rclcpp::parameter::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
rclcpp::parameter::_to_json_dict_entry(const ParameterVariant &param)
rclcpp::_to_json_dict_entry(const Parameter & param)
{
std::stringstream ss;
ss << "\"" << param.get_name() << "\": ";
@ -320,21 +143,21 @@ rclcpp::parameter::_to_json_dict_entry(const ParameterVariant &param)
}
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<ParameterVariant> & parameters)
rclcpp::operator<<(std::ostream & os, const std::vector<Parameter> & 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() << "\", ";
@ -344,7 +167,7 @@ std::to_string(const rclcpp::parameter::ParameterVariant & param)
}
std::string
std::to_string(const std::vector<rclcpp::parameter::ParameterVariant> & parameters)
std::to_string(const std::vector<rclcpp::Parameter> & parameters)
{
std::stringstream ss;
ss << "{";
@ -355,7 +178,7 @@ std::to_string(const std::vector<rclcpp::parameter::ParameterVariant> & paramete
} else {
first = false;
}
ss << rclcpp::parameter::_to_json_dict_entry(pv);
ss << rclcpp::_to_json_dict_entry(pv);
}
ss << "}";
return ss.str();

View file

@ -114,15 +114,15 @@ AsyncParametersClient::AsyncParametersClient(
qos_profile)
{}
std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>>
std::shared_future<std::vector<rclcpp::Parameter>>
AsyncParametersClient::get_parameters(
const std::vector<std::string> & names,
std::function<
void(std::shared_future<std::vector<rclcpp::parameter::ParameterVariant>>)
void(std::shared_future<std::vector<rclcpp::Parameter>>)
> callback)
{
auto promise_result =
std::make_shared<std::promise<std::vector<rclcpp::parameter::ParameterVariant>>>();
std::make_shared<std::promise<std::vector<rclcpp::Parameter>>>();
auto future_result = promise_result->get_future().share();
auto request = std::make_shared<rcl_interfaces::srv::GetParameters::Request>();
@ -133,7 +133,7 @@ AsyncParametersClient::get_parameters(
[request, promise_result, future_result, callback](
rclcpp::Client<rcl_interfaces::srv::GetParameters>::SharedFuture cb_f)
{
std::vector<rclcpp::parameter::ParameterVariant> parameter_variants;
std::vector<rclcpp::Parameter> 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_msg(
parameter));
}
promise_result->set_value(parameter_variants);
promise_result->set_value(parameters);
if (callback != nullptr) {
callback(future_result);
}
@ -155,15 +155,15 @@ AsyncParametersClient::get_parameters(
return future_result;
}
std::shared_future<std::vector<rclcpp::parameter::ParameterType>>
std::shared_future<std::vector<rclcpp::ParameterType>>
AsyncParametersClient::get_parameter_types(
const std::vector<std::string> & names,
std::function<
void(std::shared_future<std::vector<rclcpp::parameter::ParameterType>>)
void(std::shared_future<std::vector<rclcpp::ParameterType>>)
> callback)
{
auto promise_result =
std::make_shared<std::promise<std::vector<rclcpp::parameter::ParameterType>>>();
std::make_shared<std::promise<std::vector<rclcpp::ParameterType>>>();
auto future_result = promise_result->get_future().share();
auto request = std::make_shared<rcl_interfaces::srv::GetParameterTypes::Request>();
@ -174,10 +174,10 @@ AsyncParametersClient::get_parameter_types(
[promise_result, future_result, callback](
rclcpp::Client<rcl_interfaces::srv::GetParameterTypes>::SharedFuture cb_f)
{
std::vector<rclcpp::parameter::ParameterType> types;
std::vector<rclcpp::ParameterType> types;
auto & pts = cb_f.get()->types;
for (auto & pt : pts) {
pts.push_back(static_cast<rclcpp::parameter::ParameterType>(pt));
pts.push_back(static_cast<rclcpp::ParameterType>(pt));
}
promise_result->set_value(types);
if (callback != nullptr) {
@ -191,7 +191,7 @@ AsyncParametersClient::get_parameter_types(
std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>
AsyncParametersClient::set_parameters(
const std::vector<rclcpp::parameter::ParameterVariant> & parameters,
const std::vector<rclcpp::Parameter> & parameters,
std::function<
void(std::shared_future<std::vector<rcl_interfaces::msg::SetParametersResult>>)
> callback)
@ -203,8 +203,8 @@ AsyncParametersClient::set_parameters(
auto request = std::make_shared<rcl_interfaces::srv::SetParameters::Request>();
std::transform(parameters.begin(), parameters.end(), std::back_inserter(request->parameters),
[](rclcpp::parameter::ParameterVariant p) {
return p.to_parameter();
[](rclcpp::Parameter p) {
return p.to_parameter_msg();
}
);
@ -225,7 +225,7 @@ AsyncParametersClient::set_parameters(
std::shared_future<rcl_interfaces::msg::SetParametersResult>
AsyncParametersClient::set_parameters_atomically(
const std::vector<rclcpp::parameter::ParameterVariant> & parameters,
const std::vector<rclcpp::Parameter> & parameters,
std::function<
void(std::shared_future<rcl_interfaces::msg::SetParametersResult>)
> callback)
@ -237,8 +237,8 @@ AsyncParametersClient::set_parameters_atomically(
auto request = std::make_shared<rcl_interfaces::srv::SetParametersAtomically::Request>();
std::transform(parameters.begin(), parameters.end(), std::back_inserter(request->parameters),
[](rclcpp::parameter::ParameterVariant p) {
return p.to_parameter();
[](rclcpp::Parameter p) {
return p.to_parameter_msg();
}
);
@ -347,7 +347,7 @@ SyncParametersClient::SyncParametersClient(
std::make_shared<AsyncParametersClient>(node, remote_node_name, qos_profile);
}
std::vector<rclcpp::parameter::ParameterVariant>
std::vector<rclcpp::Parameter>
SyncParametersClient::get_parameters(const std::vector<std::string> & parameter_names)
{
auto f = async_parameters_client_->get_parameters(parameter_names);
@ -358,7 +358,7 @@ SyncParametersClient::get_parameters(const std::vector<std::string> & parameter_
return f.get();
}
// Return an empty vector if unsuccessful
return std::vector<rclcpp::parameter::ParameterVariant>();
return std::vector<rclcpp::Parameter>();
}
bool
@ -370,7 +370,7 @@ SyncParametersClient::has_parameter(const std::string & parameter_name)
return vars.names.size() > 0;
}
std::vector<rclcpp::parameter::ParameterType>
std::vector<rclcpp::ParameterType>
SyncParametersClient::get_parameter_types(const std::vector<std::string> & parameter_names)
{
auto f = async_parameters_client_->get_parameter_types(parameter_names);
@ -381,12 +381,12 @@ SyncParametersClient::get_parameter_types(const std::vector<std::string> & param
{
return f.get();
}
return std::vector<rclcpp::parameter::ParameterType>();
return std::vector<rclcpp::ParameterType>();
}
std::vector<rcl_interfaces::msg::SetParametersResult>
SyncParametersClient::set_parameters(
const std::vector<rclcpp::parameter::ParameterVariant> & parameters)
const std::vector<rclcpp::Parameter> & 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<rclcpp::parameter::ParameterVariant> & parameters)
const std::vector<rclcpp::Parameter> & parameters)
{
auto f = async_parameters_client_->set_parameters_atomically(parameters);

View file

@ -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);
@ -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<rclcpp::parameter::ParameterType>(type);
return static_cast<rclcpp::ParameterType>(type);
});
},
qos_profile, nullptr);
@ -70,9 +70,9 @@ ParameterService::ParameterService(
const std::shared_ptr<rcl_interfaces::srv::SetParameters::Request> request,
std::shared_ptr<rcl_interfaces::srv::SetParameters::Response> response)
{
std::vector<rclcpp::parameter::ParameterVariant> pvariants;
std::vector<rclcpp::Parameter> pvariants;
for (auto & p : request->parameters) {
pvariants.push_back(rclcpp::parameter::ParameterVariant::from_parameter(p));
pvariants.push_back(rclcpp::Parameter::from_parameter_msg(p));
}
auto results = node_params->set_parameters(pvariants);
response->results = results;
@ -87,11 +87,11 @@ ParameterService::ParameterService(
const std::shared_ptr<rcl_interfaces::srv::SetParametersAtomically::Request> request,
std::shared_ptr<rcl_interfaces::srv::SetParametersAtomically::Response> response)
{
std::vector<rclcpp::parameter::ParameterVariant> pvariants;
std::vector<rclcpp::Parameter> 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_msg(p);
});
auto result = node_params->set_parameters_atomically(pvariants);
response->result = result;

View file

@ -0,0 +1,230 @@
// 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 <string>
#include <vector>
using rclcpp::ParameterType;
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;
}
template<typename ValType, typename PrintType = ValType>
std::string
array_to_string(
const std::vector<ValType> & 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<PrintType>(value);
}
type_array << "]";
return type_array.str();
}
std::string
rclcpp::to_string(const ParameterValue & value)
{
switch (value.get_type()) {
case ParameterType::PARAMETER_NOT_SET:
return "not set";
case ParameterType::PARAMETER_BOOL:
return value.get<bool>() ? "true" : "false";
case ParameterType::PARAMETER_INTEGER:
return std::to_string(value.get<int>());
case ParameterType::PARAMETER_DOUBLE:
return std::to_string(value.get<double>());
case ParameterType::PARAMETER_STRING:
return value.get<std::string>();
case ParameterType::PARAMETER_BYTE_ARRAY:
return array_to_string<uint8_t, int>(value.get<std::vector<uint8_t>>(), std::ios::hex);
case ParameterType::PARAMETER_BOOL_ARRAY:
return array_to_string(value.get<std::vector<bool>>(), std::ios::boolalpha);
case ParameterType::PARAMETER_INTEGER_ARRAY:
return array_to_string(value.get<std::vector<int64_t>>());
case ParameterType::PARAMETER_DOUBLE_ARRAY:
return array_to_string(value.get<std::vector<double>>());
case ParameterType::PARAMETER_STRING_ARRAY:
return array_to_string(value.get<std::vector<std::string>>());
default:
return "unknown type";
}
}
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;
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<uint8_t> & 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> & 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> & 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<int64_t> & int_array_value)
{
value_.integer_array_value = int_array_value;
value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY;
}
ParameterValue::ParameterValue(const std::vector<float> & float_array_value)
{
value_.double_array_value.assign(float_array_value.cbegin(), float_array_value.cend());
value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY;
}
ParameterValue::ParameterValue(const std::vector<double> & double_array_value)
{
value_.double_array_value = double_array_value;
value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY;
}
ParameterValue::ParameterValue(const std::vector<std::string> & 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<ParameterType>(value_.type);
}
rcl_interfaces::msg::ParameterValue
ParameterValue::to_value_msg() const
{
return value_;
}

View file

@ -217,7 +217,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;
}

View file

@ -34,388 +34,388 @@ protected:
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());
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());
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();
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::ParameterVariant::from_parameter(not_set_param),
EXPECT_THROW(rclcpp::Parameter::from_parameter_msg(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::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<rclcpp::parameter::ParameterType::PARAMETER_BOOL>());
EXPECT_TRUE(bool_variant_true.get_parameter_value().bool_value);
EXPECT_TRUE(bool_variant_true.get_value<rclcpp::ParameterType::PARAMETER_BOOL>());
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(), 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());
rclcpp::parameter::ParameterVariant bool_variant_false("bool_param", false);
EXPECT_FALSE(bool_variant_false.get_value<rclcpp::parameter::ParameterType::PARAMETER_BOOL>());
EXPECT_FALSE(bool_variant_false.get_parameter_value().bool_value);
rclcpp::Parameter bool_variant_false("bool_param", false);
EXPECT_FALSE(bool_variant_false.get_value<rclcpp::ParameterType::PARAMETER_BOOL>());
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();
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::ParameterVariant from_msg_true =
rclcpp::parameter::ParameterVariant::from_parameter(bool_param);
rclcpp::Parameter from_msg_true =
rclcpp::Parameter::from_parameter_msg(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<rclcpp::parameter::ParameterType::PARAMETER_BOOL>());
EXPECT_TRUE(from_msg_true.get_parameter_value().bool_value);
EXPECT_TRUE(from_msg_true.get_value<rclcpp::ParameterType::PARAMETER_BOOL>());
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<rclcpp::parameter::ParameterType::PARAMETER_BOOL>());
EXPECT_FALSE(from_msg_false.get_parameter_value().bool_value);
rclcpp::Parameter from_msg_false =
rclcpp::Parameter::from_parameter_msg(bool_param);
EXPECT_FALSE(from_msg_false.get_value<rclcpp::ParameterType::PARAMETER_BOOL>());
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) {
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::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<rclcpp::parameter::ParameterType::PARAMETER_INTEGER>());
EXPECT_EQ(TEST_VALUE, integer_variant.get_parameter_value().integer_value);
integer_variant.get_value<rclcpp::ParameterType::PARAMETER_INTEGER>());
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(), 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());
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::ParameterVariant from_msg =
rclcpp::parameter::ParameterVariant::from_parameter(integer_param);
rclcpp::Parameter from_msg =
rclcpp::Parameter::from_parameter_msg(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<rclcpp::parameter::ParameterType::PARAMETER_INTEGER>());
EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().integer_value);
from_msg.get_value<rclcpp::ParameterType::PARAMETER_INTEGER>());
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) {
const int64_t TEST_VALUE {std::numeric_limits<int64_t>::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::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<rclcpp::parameter::ParameterType::PARAMETER_INTEGER>());
EXPECT_EQ(TEST_VALUE, long_variant.get_parameter_value().integer_value);
long_variant.get_value<rclcpp::ParameterType::PARAMETER_INTEGER>());
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(), 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());
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::ParameterVariant from_msg =
rclcpp::parameter::ParameterVariant::from_parameter(integer_param);
rclcpp::Parameter from_msg =
rclcpp::Parameter::from_parameter_msg(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<rclcpp::parameter::ParameterType::PARAMETER_INTEGER>());
EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().integer_value);
from_msg.get_value<rclcpp::ParameterType::PARAMETER_INTEGER>());
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) {
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::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<rclcpp::parameter::ParameterType::PARAMETER_DOUBLE>());
EXPECT_EQ(TEST_VALUE, float_variant.get_parameter_value().double_value);
float_variant.get_value<rclcpp::ParameterType::PARAMETER_DOUBLE>());
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(), 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());
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::ParameterVariant from_msg =
rclcpp::parameter::ParameterVariant::from_parameter(float_param);
rclcpp::Parameter from_msg =
rclcpp::Parameter::from_parameter_msg(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<rclcpp::parameter::ParameterType::PARAMETER_DOUBLE>());
EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().double_value);
from_msg.get_value<rclcpp::ParameterType::PARAMETER_DOUBLE>());
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) {
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::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<rclcpp::parameter::ParameterType::PARAMETER_DOUBLE>());
EXPECT_EQ(TEST_VALUE, double_variant.get_parameter_value().double_value);
double_variant.get_value<rclcpp::ParameterType::PARAMETER_DOUBLE>());
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(), 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());
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::ParameterVariant from_msg =
rclcpp::parameter::ParameterVariant::from_parameter(double_param);
rclcpp::Parameter from_msg =
rclcpp::Parameter::from_parameter_msg(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<rclcpp::parameter::ParameterType::PARAMETER_DOUBLE>());
EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().double_value);
from_msg.get_value<rclcpp::ParameterType::PARAMETER_DOUBLE>());
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) {
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::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<rclcpp::parameter::ParameterType::PARAMETER_STRING>());
EXPECT_EQ(TEST_VALUE, string_variant.get_parameter_value().string_value);
string_variant.get_value<rclcpp::ParameterType::PARAMETER_STRING>());
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(), 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());
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::ParameterVariant from_msg =
rclcpp::parameter::ParameterVariant::from_parameter(string_param);
rclcpp::Parameter from_msg =
rclcpp::Parameter::from_parameter_msg(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<rclcpp::parameter::ParameterType::PARAMETER_STRING>());
EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().string_value);
EXPECT_EQ(TEST_VALUE, from_msg.get_value<rclcpp::ParameterType::PARAMETER_STRING>());
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) {
const std::vector<uint8_t> 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::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<rclcpp::parameter::ParameterType::PARAMETER_BYTE_ARRAY>());
EXPECT_EQ(TEST_VALUE, byte_array_variant.get_parameter_value().byte_array_value);
byte_array_variant.get_value<rclcpp::ParameterType::PARAMETER_BYTE_ARRAY>());
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(), 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());
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::ParameterVariant from_msg =
rclcpp::parameter::ParameterVariant::from_parameter(byte_array_param);
rclcpp::Parameter from_msg =
rclcpp::Parameter::from_parameter_msg(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<rclcpp::parameter::ParameterType::PARAMETER_BYTE_ARRAY>());
EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().byte_array_value);
from_msg.get_value<rclcpp::ParameterType::PARAMETER_BYTE_ARRAY>());
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) {
const std::vector<bool> 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::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<rclcpp::parameter::ParameterType::PARAMETER_BOOL_ARRAY>());
EXPECT_EQ(TEST_VALUE, bool_array_variant.get_parameter_value().bool_array_value);
bool_array_variant.get_value<rclcpp::ParameterType::PARAMETER_BOOL_ARRAY>());
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(), 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());
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::ParameterVariant from_msg =
rclcpp::parameter::ParameterVariant::from_parameter(bool_array_param);
rclcpp::Parameter from_msg =
rclcpp::Parameter::from_parameter_msg(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<rclcpp::parameter::ParameterType::PARAMETER_BOOL_ARRAY>());
EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().bool_array_value);
from_msg.get_value<rclcpp::ParameterType::PARAMETER_BOOL_ARRAY>());
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) {
@ -423,23 +423,23 @@ TEST(TestParameter, integer_array_variant) {
{42, -99, std::numeric_limits<int>::max(), std::numeric_limits<int>::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::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,
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 =
integer_array_variant.get_value<rclcpp::parameter::ParameterType::PARAMETER_INTEGER_ARRAY>();
integer_array_variant.get_value<rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY>();
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);
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);
@ -449,20 +449,20 @@ 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]",
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);
@ -473,23 +473,23 @@ 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_msg(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<rclcpp::parameter::ParameterType::PARAMETER_INTEGER_ARRAY>();
param_value = from_msg.get_value<rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY>();
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);
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);
}
@ -497,48 +497,48 @@ TEST(TestParameter, long_integer_array_variant) {
const std::vector<int64_t> TEST_VALUE
{42, -99, std::numeric_limits<int64_t>::max(), std::numeric_limits<int64_t>::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::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);
long_array_variant.get_value_message().type);
EXPECT_EQ(TEST_VALUE,
long_array_variant.get_value<rclcpp::parameter::ParameterType::PARAMETER_INTEGER_ARRAY>());
EXPECT_EQ(TEST_VALUE, long_array_variant.get_parameter_value().integer_array_value);
long_array_variant.get_value<rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY>());
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(), 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]",
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);
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_msg(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<rclcpp::parameter::ParameterType::PARAMETER_INTEGER_ARRAY>());
EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().integer_array_value);
from_msg.get_value<rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY>());
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) {
@ -546,23 +546,23 @@ TEST(TestParameter, float_array_variant) {
{42.1f, -99.1f, std::numeric_limits<float>::max(), std::numeric_limits<float>::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::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,
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 =
float_array_variant.get_value<rclcpp::parameter::ParameterType::PARAMETER_DOUBLE_ARRAY>();
float_array_variant.get_value<rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY>();
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);
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);
@ -572,20 +572,20 @@ 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]",
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);
@ -596,116 +596,116 @@ 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_msg(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<rclcpp::parameter::ParameterType::PARAMETER_DOUBLE_ARRAY>();
param_value = from_msg.get_value<rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY>();
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);
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) {
const std::vector<double> TEST_VALUE
{42.1, -99.1, std::numeric_limits<double>::max(), std::numeric_limits<double>::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::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);
double_array_variant.get_value_message().type);
EXPECT_EQ(TEST_VALUE,
double_array_variant.get_value<rclcpp::parameter::ParameterType::PARAMETER_DOUBLE_ARRAY>());
EXPECT_EQ(TEST_VALUE, double_array_variant.get_parameter_value().double_array_value);
double_array_variant.get_value<rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY>());
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(), 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]",
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);
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_msg(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<rclcpp::parameter::ParameterType::PARAMETER_DOUBLE_ARRAY>());
EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().double_array_value);
from_msg.get_value<rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY>());
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) {
const std::vector<std::string> 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::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<rclcpp::parameter::ParameterType::PARAMETER_STRING_ARRAY>());
EXPECT_EQ(TEST_VALUE, string_array_variant.get_parameter_value().string_array_value);
string_array_variant.get_value<rclcpp::ParameterType::PARAMETER_STRING_ARRAY>());
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(), 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());
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);
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_msg(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<rclcpp::parameter::ParameterType::PARAMETER_STRING_ARRAY>());
EXPECT_EQ(TEST_VALUE, from_msg.get_parameter_value().string_array_value);
from_msg.get_value<rclcpp::ParameterType::PARAMETER_STRING_ARRAY>());
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);
}

View file

@ -334,7 +334,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);
@ -346,7 +346,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", rclcpp::parameter::PARAMETER_NOT_SET)
rclcpp::Parameter("use_sim_time", rclcpp::ParameterType::PARAMETER_NOT_SET)
});
for (auto & result : set_parameters_results) {
EXPECT_TRUE(result.successful);
@ -355,7 +355,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);
@ -364,7 +364,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("use_sim_time", rclcpp::ParameterType::PARAMETER_NOT_SET)
});
for (auto & result : set_parameters_results) {
EXPECT_TRUE(result.successful);

View file

@ -252,25 +252,25 @@ public:
RCLCPP_LIFECYCLE_PUBLIC
std::vector<rcl_interfaces::msg::SetParametersResult>
set_parameters(const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
set_parameters(const std::vector<rclcpp::Parameter> & parameters);
RCLCPP_LIFECYCLE_PUBLIC
rcl_interfaces::msg::SetParametersResult
set_parameters_atomically(const std::vector<rclcpp::parameter::ParameterVariant> & parameters);
set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters);
RCLCPP_LIFECYCLE_PUBLIC
std::vector<rclcpp::parameter::ParameterVariant>
std::vector<rclcpp::Parameter>
get_parameters(const std::vector<std::string> & 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<typename ParameterT>
bool

View file

@ -186,9 +186,9 @@ template<typename ParameterT>
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<ParameterT>();
rclcpp::Parameter param(name, parameter);
bool result = get_parameter(name, param);
parameter = param.get_value<ParameterT>();
return result;
}

View file

@ -137,26 +137,26 @@ LifecycleNode::group_in_node(rclcpp::callback_group::CallbackGroup::SharedPtr gr
std::vector<rcl_interfaces::msg::SetParametersResult>
LifecycleNode::set_parameters(
const std::vector<rclcpp::parameter::ParameterVariant> & parameters)
const std::vector<rclcpp::Parameter> & parameters)
{
return node_parameters_->set_parameters(parameters);
}
rcl_interfaces::msg::SetParametersResult
LifecycleNode::set_parameters_atomically(
const std::vector<rclcpp::parameter::ParameterVariant> & parameters)
const std::vector<rclcpp::Parameter> & parameters)
{
return node_parameters_->set_parameters_atomically(parameters);
}
std::vector<rclcpp::parameter::ParameterVariant>
std::vector<rclcpp::Parameter>
LifecycleNode::get_parameters(
const std::vector<std::string> & 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);
}