Convert rcl_params_t to ParameterMap (#485)
Convert from rcl_params_t to map of node parameters Adds rclcpp::parameter_map_from(const rcl_params_t * const) Adds rclcpp::parameter_value_from(const rcl_variant_t * const) Adds dependency on rcl_yaml_param_parser
This commit is contained in:
parent
5ab6bde1db
commit
8f793fdb4a
6 changed files with 559 additions and 0 deletions
|
@ -6,6 +6,7 @@ find_package(ament_cmake_ros REQUIRED)
|
|||
find_package(builtin_interfaces REQUIRED)
|
||||
find_package(rcl REQUIRED)
|
||||
find_package(rcl_interfaces REQUIRED)
|
||||
find_package(rcl_yaml_param_parser REQUIRED)
|
||||
find_package(rmw REQUIRED)
|
||||
find_package(rmw_implementation REQUIRED)
|
||||
find_package(rosgraph_msgs REQUIRED)
|
||||
|
@ -62,6 +63,7 @@ set(${PROJECT_NAME}_SRCS
|
|||
src/rclcpp/parameter_value.cpp
|
||||
src/rclcpp/parameter_client.cpp
|
||||
src/rclcpp/parameter_events_filter.cpp
|
||||
src/rclcpp/parameter_map.cpp
|
||||
src/rclcpp/parameter_service.cpp
|
||||
src/rclcpp/publisher.cpp
|
||||
src/rclcpp/service.cpp
|
||||
|
@ -100,6 +102,7 @@ add_library(${PROJECT_NAME}
|
|||
# specific order: dependents before dependencies
|
||||
ament_target_dependencies(${PROJECT_NAME}
|
||||
"rcl"
|
||||
"rcl_yaml_param_parser"
|
||||
"builtin_interfaces"
|
||||
"rosgraph_msgs"
|
||||
"rosidl_typesupport_cpp"
|
||||
|
@ -128,6 +131,7 @@ ament_export_dependencies(rosgraph_msgs)
|
|||
ament_export_dependencies(rosidl_typesupport_cpp)
|
||||
ament_export_dependencies(rosidl_typesupport_c)
|
||||
ament_export_dependencies(rosidl_generator_cpp)
|
||||
ament_export_dependencies(rcl_yaml_param_parser)
|
||||
|
||||
if(BUILD_TESTING)
|
||||
find_package(ament_cmake_gtest REQUIRED)
|
||||
|
@ -225,6 +229,10 @@ if(BUILD_TESTING)
|
|||
)
|
||||
target_link_libraries(test_parameter ${PROJECT_NAME})
|
||||
endif()
|
||||
ament_add_gtest(test_parameter_map test/test_parameter_map.cpp)
|
||||
if(TARGET test_parameter_map)
|
||||
target_link_libraries(test_parameter_map ${PROJECT_NAME})
|
||||
endif()
|
||||
ament_add_gtest(test_publisher test/test_publisher.cpp)
|
||||
if(TARGET test_publisher)
|
||||
target_include_directories(test_publisher PUBLIC
|
||||
|
|
|
@ -181,6 +181,21 @@ public:
|
|||
: std::runtime_error("event already registered") {}
|
||||
};
|
||||
|
||||
/// Thrown if passed parameters are inconsistent or invalid
|
||||
class InvalidParametersException : public std::runtime_error
|
||||
{
|
||||
public:
|
||||
// Inherit constructors from runtime_error;
|
||||
using std::runtime_error::runtime_error;
|
||||
};
|
||||
|
||||
/// Throwing if passed parameter value is invalid.
|
||||
class InvalidParameterValueException : public std::runtime_error
|
||||
{
|
||||
// Inherit constructors from runtime_error;
|
||||
using std::runtime_error::runtime_error;
|
||||
};
|
||||
|
||||
} // namespace exceptions
|
||||
} // namespace rclcpp
|
||||
|
||||
|
|
53
rclcpp/include/rclcpp/parameter_map.hpp
Normal file
53
rclcpp/include/rclcpp/parameter_map.hpp
Normal file
|
@ -0,0 +1,53 @@
|
|||
// 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_MAP_HPP_
|
||||
#define RCLCPP__PARAMETER_MAP_HPP_
|
||||
|
||||
#include <rcl_yaml_param_parser/types.h>
|
||||
|
||||
#include <string>
|
||||
#include <unordered_map>
|
||||
#include <vector>
|
||||
|
||||
#include "rclcpp/exceptions.hpp"
|
||||
#include "rclcpp/parameter.hpp"
|
||||
#include "rclcpp/parameter_value.hpp"
|
||||
#include "rclcpp/visibility_control.hpp"
|
||||
|
||||
namespace rclcpp
|
||||
{
|
||||
|
||||
/// A map of fully qualified node names to a list of parameters
|
||||
using ParameterMap = std::unordered_map<std::string, std::vector<Parameter>>;
|
||||
|
||||
/// Convert parameters from rcl_yaml_param_parser into C++ class instances.
|
||||
/// \param[in] c_params C structures containing parameters for multiple nodes.
|
||||
/// \returns a map where the keys are fully qualified node names and values a list of parameters.
|
||||
/// \throws InvalidParametersException if the `rcl_params_t` is inconsistent or invalid.
|
||||
RCLCPP_PUBLIC
|
||||
ParameterMap
|
||||
parameter_map_from(const rcl_params_t * const c_params);
|
||||
|
||||
/// Convert parameter value from rcl_yaml_param_parser into a C++ class instance.
|
||||
/// \param[in] c_value C structure containing a value of a parameter.
|
||||
/// \returns an instance of a parameter value
|
||||
/// \throws InvalidParameterValueException if the `rcl_variant_t` is inconsistent or invalid.
|
||||
RCLCPP_PUBLIC
|
||||
ParameterValue
|
||||
parameter_value_from(const rcl_variant_t * const c_value);
|
||||
|
||||
} // namespace rclcpp
|
||||
|
||||
#endif // RCLCPP__PARAMETER_MAP_HPP_
|
|
@ -25,6 +25,7 @@
|
|||
<build_export_depend>rosidl_typesupport_cpp</build_export_depend>
|
||||
|
||||
<depend>rcl</depend>
|
||||
<depend>rcl_yaml_param_parser</depend>
|
||||
<depend>rmw_implementation</depend>
|
||||
|
||||
<exec_depend>ament_cmake</exec_depend>
|
||||
|
|
128
rclcpp/src/rclcpp/parameter_map.cpp
Normal file
128
rclcpp/src/rclcpp/parameter_map.cpp
Normal file
|
@ -0,0 +1,128 @@
|
|||
// 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 <string>
|
||||
#include <vector>
|
||||
|
||||
#include "rclcpp/parameter_map.hpp"
|
||||
|
||||
using rclcpp::exceptions::InvalidParametersException;
|
||||
using rclcpp::exceptions::InvalidParameterValueException;
|
||||
using rclcpp::ParameterMap;
|
||||
using rclcpp::ParameterValue;
|
||||
|
||||
ParameterMap
|
||||
rclcpp::parameter_map_from(const rcl_params_t * const c_params)
|
||||
{
|
||||
if (NULL == c_params) {
|
||||
throw InvalidParametersException("parameters struct is NULL");
|
||||
} else if (NULL == c_params->node_names) {
|
||||
throw InvalidParametersException("node names array is NULL");
|
||||
} else if (NULL == c_params->params) {
|
||||
throw InvalidParametersException("node params array is NULL");
|
||||
}
|
||||
|
||||
// Convert c structs into a list of parameters to set
|
||||
ParameterMap parameters;
|
||||
for (size_t n = 0; n < c_params->num_nodes; ++n) {
|
||||
const char * c_node_name = c_params->node_names[n];
|
||||
if (NULL == c_node_name) {
|
||||
throw InvalidParametersException("Node name at index " + std::to_string(n) + " is NULL");
|
||||
}
|
||||
|
||||
/// make sure there is a leading slash on the fully qualified node name
|
||||
std::string node_name("/");
|
||||
if ('/' != c_node_name[0]) {
|
||||
node_name += c_node_name;
|
||||
} else {
|
||||
node_name = c_node_name;
|
||||
}
|
||||
|
||||
const rcl_node_params_t * const c_params_node = &(c_params->params[n]);
|
||||
|
||||
std::vector<Parameter> & params_node = parameters[node_name];
|
||||
params_node.reserve(c_params_node->num_params);
|
||||
|
||||
for (size_t p = 0; p < c_params_node->num_params; ++p) {
|
||||
const char * const c_param_name = c_params_node->parameter_names[p];
|
||||
if (NULL == c_param_name) {
|
||||
std::string message(
|
||||
"At node " + std::to_string(n) + " parameter " + std::to_string(p) + " name is NULL");
|
||||
throw InvalidParametersException(message);
|
||||
}
|
||||
const rcl_variant_t * const c_param_value = &(c_params_node->parameter_values[p]);
|
||||
params_node.emplace_back(c_param_name, parameter_value_from(c_param_value));
|
||||
}
|
||||
}
|
||||
return parameters;
|
||||
}
|
||||
|
||||
ParameterValue
|
||||
rclcpp::parameter_value_from(const rcl_variant_t * const c_param_value)
|
||||
{
|
||||
if (NULL == c_param_value) {
|
||||
throw InvalidParameterValueException("Passed argument is NULL");
|
||||
}
|
||||
if (c_param_value->bool_value) {
|
||||
return ParameterValue(*(c_param_value->bool_value));
|
||||
} else if (c_param_value->integer_value) {
|
||||
return ParameterValue(*(c_param_value->integer_value));
|
||||
} else if (c_param_value->double_value) {
|
||||
return ParameterValue(*(c_param_value->double_value));
|
||||
} else if (c_param_value->string_value) {
|
||||
return ParameterValue(std::string(c_param_value->string_value));
|
||||
} else if (c_param_value->byte_array_value) {
|
||||
const rcl_byte_array_t * const byte_array = c_param_value->byte_array_value;
|
||||
std::vector<uint8_t> bytes;
|
||||
bytes.reserve(byte_array->size);
|
||||
for (size_t v = 0; v < byte_array->size; ++v) {
|
||||
bytes.push_back(byte_array->values[v]);
|
||||
}
|
||||
return ParameterValue(bytes);
|
||||
} else if (c_param_value->bool_array_value) {
|
||||
const rcl_bool_array_t * const bool_array = c_param_value->bool_array_value;
|
||||
std::vector<bool> bools;
|
||||
bools.reserve(bool_array->size);
|
||||
for (size_t v = 0; v < bool_array->size; ++v) {
|
||||
bools.push_back(bool_array->values[v]);
|
||||
}
|
||||
return ParameterValue(bools);
|
||||
} else if (c_param_value->integer_array_value) {
|
||||
const rcl_int64_array_t * const int_array = c_param_value->integer_array_value;
|
||||
std::vector<int64_t> integers;
|
||||
integers.reserve(int_array->size);
|
||||
for (size_t v = 0; v < int_array->size; ++v) {
|
||||
integers.push_back(int_array->values[v]);
|
||||
}
|
||||
return ParameterValue(integers);
|
||||
} else if (c_param_value->double_array_value) {
|
||||
const rcl_double_array_t * const double_array = c_param_value->double_array_value;
|
||||
std::vector<double> doubles;
|
||||
doubles.reserve(double_array->size);
|
||||
for (size_t v = 0; v < double_array->size; ++v) {
|
||||
doubles.push_back(double_array->values[v]);
|
||||
}
|
||||
return ParameterValue(doubles);
|
||||
} else if (c_param_value->string_array_value) {
|
||||
const rcutils_string_array_t * const string_array = c_param_value->string_array_value;
|
||||
std::vector<std::string> strings;
|
||||
strings.reserve(string_array->size);
|
||||
for (size_t v = 0; v < string_array->size; ++v) {
|
||||
strings.emplace_back(string_array->data[v]);
|
||||
}
|
||||
return ParameterValue(strings);
|
||||
}
|
||||
|
||||
throw InvalidParameterValueException("No parameter value set");
|
||||
}
|
354
rclcpp/test/test_parameter_map.cpp
Normal file
354
rclcpp/test/test_parameter_map.cpp
Normal file
|
@ -0,0 +1,354 @@
|
|||
// 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 <gtest/gtest.h>
|
||||
#include <rcl_yaml_param_parser/parser.h>
|
||||
#include <rcutils/strdup.h>
|
||||
|
||||
#include <cstdio>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
|
||||
#include "rclcpp/parameter_map.hpp"
|
||||
|
||||
rcl_params_t *
|
||||
make_params(std::vector<std::string> node_names)
|
||||
{
|
||||
rcl_allocator_t alloc = rcl_get_default_allocator();
|
||||
rcl_params_t * c_params = rcl_yaml_node_struct_init(alloc);
|
||||
c_params->num_nodes = node_names.size();
|
||||
c_params->allocator = alloc;
|
||||
if (c_params->num_nodes) {
|
||||
// Copy node names
|
||||
for (size_t n = 0; n < node_names.size(); ++n) {
|
||||
c_params->node_names[n] = static_cast<char *>(alloc.allocate(
|
||||
sizeof(char) * (node_names[n].size() + 1), alloc.state));
|
||||
std::snprintf(c_params->node_names[n], node_names[n].size() + 1, "%s", node_names[n].c_str());
|
||||
}
|
||||
// zero init node params
|
||||
for (size_t n = 0; n < node_names.size(); ++n) {
|
||||
c_params->params[n].parameter_names = NULL;
|
||||
c_params->params[n].parameter_values = NULL;
|
||||
c_params->params[n].num_params = 0;
|
||||
}
|
||||
}
|
||||
return c_params;
|
||||
}
|
||||
|
||||
void
|
||||
make_node_params(rcl_params_t * c_params, size_t node_idx, std::vector<std::string> param_names)
|
||||
{
|
||||
rcl_allocator_t alloc = c_params->allocator;
|
||||
ASSERT_LT(node_idx, c_params->num_nodes);
|
||||
ASSERT_GT(param_names.size(), 0u);
|
||||
|
||||
rcl_node_params_s * c_node_params = &(c_params->params[node_idx]);
|
||||
c_node_params->num_params = param_names.size();
|
||||
|
||||
// Copy parameter names
|
||||
c_node_params->parameter_names = static_cast<char **>(
|
||||
alloc.allocate(sizeof(char *) * param_names.size(), alloc.state));
|
||||
for (size_t p = 0; p < param_names.size(); ++p) {
|
||||
const std::string & param_name = param_names[p];
|
||||
c_node_params->parameter_names[p] = static_cast<char *>(alloc.allocate(
|
||||
sizeof(char) * (param_name.size() + 1), alloc.state));
|
||||
std::snprintf(
|
||||
c_node_params->parameter_names[p], param_name.size() + 1, "%s", param_name.c_str());
|
||||
}
|
||||
// zero init parameter value
|
||||
c_node_params->parameter_values = static_cast<rcl_variant_t *>(alloc.allocate(
|
||||
sizeof(rcl_variant_t) * param_names.size(), alloc.state));
|
||||
for (size_t p = 0; p < param_names.size(); ++p) {
|
||||
c_node_params->parameter_values[p].bool_value = NULL;
|
||||
c_node_params->parameter_values[p].integer_value = NULL;
|
||||
c_node_params->parameter_values[p].double_value = NULL;
|
||||
c_node_params->parameter_values[p].string_value = NULL;
|
||||
c_node_params->parameter_values[p].byte_array_value = NULL;
|
||||
c_node_params->parameter_values[p].bool_array_value = NULL;
|
||||
c_node_params->parameter_values[p].integer_array_value = NULL;
|
||||
c_node_params->parameter_values[p].double_array_value = NULL;
|
||||
c_node_params->parameter_values[p].string_array_value = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
TEST(Test_parameter_map_from, null_c_parameter)
|
||||
{
|
||||
EXPECT_THROW(rclcpp::parameter_map_from(NULL), rclcpp::exceptions::InvalidParametersException);
|
||||
}
|
||||
|
||||
TEST(Test_parameter_map_from, null_node_names)
|
||||
{
|
||||
rcl_params_t * c_params = make_params({});
|
||||
c_params->num_nodes = 1;
|
||||
|
||||
EXPECT_THROW(
|
||||
rclcpp::parameter_map_from(c_params), rclcpp::exceptions::InvalidParametersException);
|
||||
|
||||
c_params->num_nodes = 0;
|
||||
rcl_yaml_node_struct_fini(c_params);
|
||||
}
|
||||
|
||||
TEST(Test_parameter_map_from, null_node_params)
|
||||
{
|
||||
rcl_params_t * c_params = make_params({"foo"});
|
||||
std::snprintf(c_params->node_names[0], 3 + 1, "foo");
|
||||
auto allocated_params = c_params->params;
|
||||
c_params->params = NULL;
|
||||
|
||||
EXPECT_THROW(
|
||||
rclcpp::parameter_map_from(c_params), rclcpp::exceptions::InvalidParametersException);
|
||||
|
||||
c_params->params = allocated_params;
|
||||
rcl_yaml_node_struct_fini(c_params);
|
||||
}
|
||||
|
||||
TEST(Test_parameter_map_from, null_node_name_in_node_names)
|
||||
{
|
||||
rcl_params_t * c_params = make_params({"foo"});
|
||||
auto allocated_name = c_params->node_names[0];
|
||||
c_params->node_names[0] = NULL;
|
||||
|
||||
EXPECT_THROW(
|
||||
rclcpp::parameter_map_from(c_params), rclcpp::exceptions::InvalidParametersException);
|
||||
|
||||
c_params->node_names[0] = allocated_name;
|
||||
rcl_yaml_node_struct_fini(c_params);
|
||||
}
|
||||
|
||||
TEST(Test_parameter_map_from, null_node_param_value)
|
||||
{
|
||||
rcl_params_t * c_params = make_params({"foo"});
|
||||
make_node_params(c_params, 0, {"bar"});
|
||||
|
||||
EXPECT_THROW(
|
||||
rclcpp::parameter_map_from(c_params), rclcpp::exceptions::InvalidParameterValueException);
|
||||
|
||||
rcl_yaml_node_struct_fini(c_params);
|
||||
}
|
||||
|
||||
TEST(Test_parameter_map_from, null_node_param_name)
|
||||
{
|
||||
rcl_params_t * c_params = make_params({"foo"});
|
||||
make_node_params(c_params, 0, {"bar"});
|
||||
auto allocated_name = c_params->params[0].parameter_names[0];
|
||||
c_params->params[0].parameter_names[0] = NULL;
|
||||
|
||||
EXPECT_THROW(
|
||||
rclcpp::parameter_map_from(c_params), rclcpp::exceptions::InvalidParametersException);
|
||||
|
||||
c_params->params[0].parameter_names[0] = allocated_name;
|
||||
rcl_yaml_node_struct_fini(c_params);
|
||||
}
|
||||
|
||||
TEST(Test_parameter_map_from, bool_param_value)
|
||||
{
|
||||
rcl_params_t * c_params = make_params({"foo"});
|
||||
make_node_params(c_params, 0, {"true_bool", "false_bool"});
|
||||
bool true_bool = true;
|
||||
bool false_bool = false;
|
||||
c_params->params[0].parameter_values[0].bool_value = &true_bool;
|
||||
c_params->params[0].parameter_values[1].bool_value = &false_bool;
|
||||
|
||||
rclcpp::ParameterMap map = rclcpp::parameter_map_from(c_params);
|
||||
const std::vector<rclcpp::Parameter> & params = map.at("/foo");
|
||||
EXPECT_STREQ("true_bool", params.at(0).get_name().c_str());
|
||||
EXPECT_TRUE(params.at(0).get_value<bool>());
|
||||
EXPECT_STREQ("false_bool", params.at(1).get_name().c_str());
|
||||
EXPECT_FALSE(params.at(1).get_value<bool>());
|
||||
|
||||
c_params->params[0].parameter_values[0].bool_value = NULL;
|
||||
c_params->params[0].parameter_values[1].bool_value = NULL;
|
||||
rcl_yaml_node_struct_fini(c_params);
|
||||
}
|
||||
|
||||
TEST(Test_parameter_map_from, integer_param_value)
|
||||
{
|
||||
rcl_params_t * c_params = make_params({"bar"});
|
||||
make_node_params(c_params, 0, {"positive.int", "negative.int"});
|
||||
int64_t positive_int = 42;
|
||||
int64_t negative_int = -12345;
|
||||
c_params->params[0].parameter_values[0].integer_value = &positive_int;
|
||||
c_params->params[0].parameter_values[1].integer_value = &negative_int;
|
||||
|
||||
rclcpp::ParameterMap map = rclcpp::parameter_map_from(c_params);
|
||||
const std::vector<rclcpp::Parameter> & params = map.at("/bar");
|
||||
EXPECT_STREQ("positive.int", params.at(0).get_name().c_str());
|
||||
EXPECT_EQ(42, params.at(0).get_value<int64_t>());
|
||||
EXPECT_STREQ("negative.int", params.at(1).get_name().c_str());
|
||||
EXPECT_EQ(-12345, params.at(1).get_value<int64_t>());
|
||||
|
||||
c_params->params[0].parameter_values[0].integer_value = NULL;
|
||||
c_params->params[0].parameter_values[1].integer_value = NULL;
|
||||
rcl_yaml_node_struct_fini(c_params);
|
||||
}
|
||||
|
||||
TEST(Test_parameter_map_from, double_param_value)
|
||||
{
|
||||
rcl_params_t * c_params = make_params({"foo/bar"});
|
||||
make_node_params(c_params, 0, {"positive.double", "negative.double"});
|
||||
double positive_double = 3.14;
|
||||
double negative_double = -2.718;
|
||||
c_params->params[0].parameter_values[0].double_value = &positive_double;
|
||||
c_params->params[0].parameter_values[1].double_value = &negative_double;
|
||||
|
||||
rclcpp::ParameterMap map = rclcpp::parameter_map_from(c_params);
|
||||
const std::vector<rclcpp::Parameter> & params = map.at("/foo/bar");
|
||||
EXPECT_STREQ("positive.double", params.at(0).get_name().c_str());
|
||||
EXPECT_DOUBLE_EQ(3.14, params.at(0).get_value<double>());
|
||||
EXPECT_STREQ("negative.double", params.at(1).get_name().c_str());
|
||||
EXPECT_DOUBLE_EQ(-2.718, params.at(1).get_value<double>());
|
||||
|
||||
c_params->params[0].parameter_values[0].double_value = NULL;
|
||||
c_params->params[0].parameter_values[1].double_value = NULL;
|
||||
rcl_yaml_node_struct_fini(c_params);
|
||||
}
|
||||
|
||||
TEST(Test_parameter_map_from, string_param_value)
|
||||
{
|
||||
rcl_params_t * c_params = make_params({"/foo/bar"});
|
||||
make_node_params(c_params, 0, {"string_param"});
|
||||
std::string hello_world = "hello world";
|
||||
char * c_hello_world = new char[hello_world.length() + 1];
|
||||
std::snprintf(c_hello_world, hello_world.size() + 1, "%s", hello_world.c_str());
|
||||
c_params->params[0].parameter_values[0].string_value = c_hello_world;
|
||||
|
||||
rclcpp::ParameterMap map = rclcpp::parameter_map_from(c_params);
|
||||
const std::vector<rclcpp::Parameter> & params = map.at("/foo/bar");
|
||||
EXPECT_STREQ("string_param", params.at(0).get_name().c_str());
|
||||
EXPECT_STREQ(hello_world.c_str(), params.at(0).get_value<std::string>().c_str());
|
||||
|
||||
c_params->params[0].parameter_values[0].string_value = NULL;
|
||||
delete[] c_hello_world;
|
||||
rcl_yaml_node_struct_fini(c_params);
|
||||
}
|
||||
|
||||
#define MAKE_ARRAY_VALUE(VAR, TYPE, V1, V2) \
|
||||
do { \
|
||||
VAR.values = new TYPE[2]; \
|
||||
VAR.size = 2; \
|
||||
VAR.values[0] = V1; \
|
||||
VAR.values[1] = V2; \
|
||||
} while (false)
|
||||
|
||||
#define FREE_ARRAY_VALUE(VAR) \
|
||||
do { \
|
||||
delete[] VAR.values; \
|
||||
} while (false)
|
||||
|
||||
TEST(Test_parameter_map_from, byte_array_param_value)
|
||||
{
|
||||
rcl_params_t * c_params = make_params({"/foobar"});
|
||||
make_node_params(c_params, 0, {"byte_array_param"});
|
||||
rcl_byte_array_t c_byte_array;
|
||||
MAKE_ARRAY_VALUE(c_byte_array, uint8_t, 0xf0, 0xaa);
|
||||
c_params->params[0].parameter_values[0].byte_array_value = &c_byte_array;
|
||||
|
||||
rclcpp::ParameterMap map = rclcpp::parameter_map_from(c_params);
|
||||
const std::vector<rclcpp::Parameter> & params = map.at("/foobar");
|
||||
EXPECT_STREQ("byte_array_param", params.at(0).get_name().c_str());
|
||||
std::vector<uint8_t> byte_array = params.at(0).get_value<std::vector<uint8_t>>();
|
||||
ASSERT_EQ(2u, byte_array.size());
|
||||
EXPECT_EQ(0xf0, byte_array.at(0));
|
||||
EXPECT_EQ(0xaa, byte_array.at(1));
|
||||
|
||||
c_params->params[0].parameter_values[0].byte_array_value = NULL;
|
||||
FREE_ARRAY_VALUE(c_byte_array);
|
||||
rcl_yaml_node_struct_fini(c_params);
|
||||
}
|
||||
|
||||
TEST(Test_parameter_map_from, bool_array_param_value)
|
||||
{
|
||||
rcl_params_t * c_params = make_params({"foo/bar/baz"});
|
||||
make_node_params(c_params, 0, {"bool_array_param"});
|
||||
rcl_bool_array_t c_bool_array;
|
||||
MAKE_ARRAY_VALUE(c_bool_array, bool, true, false);
|
||||
c_params->params[0].parameter_values[0].bool_array_value = &c_bool_array;
|
||||
|
||||
rclcpp::ParameterMap map = rclcpp::parameter_map_from(c_params);
|
||||
const std::vector<rclcpp::Parameter> & params = map.at("/foo/bar/baz");
|
||||
EXPECT_STREQ("bool_array_param", params.at(0).get_name().c_str());
|
||||
std::vector<bool> bool_array = params.at(0).get_value<std::vector<bool>>();
|
||||
ASSERT_EQ(2u, bool_array.size());
|
||||
EXPECT_TRUE(bool_array.at(0));
|
||||
EXPECT_FALSE(bool_array.at(1));
|
||||
|
||||
c_params->params[0].parameter_values[0].bool_array_value = NULL;
|
||||
FREE_ARRAY_VALUE(c_bool_array);
|
||||
rcl_yaml_node_struct_fini(c_params);
|
||||
}
|
||||
|
||||
TEST(Test_parameter_map_from, integer_array_param_value)
|
||||
{
|
||||
rcl_params_t * c_params = make_params({"foo"});
|
||||
make_node_params(c_params, 0, {"integer_array_param"});
|
||||
rcl_int64_array_t c_integer_array;
|
||||
MAKE_ARRAY_VALUE(c_integer_array, int64_t, 42, -12345);
|
||||
c_params->params[0].parameter_values[0].integer_array_value = &c_integer_array;
|
||||
|
||||
rclcpp::ParameterMap map = rclcpp::parameter_map_from(c_params);
|
||||
const std::vector<rclcpp::Parameter> & params = map.at("/foo");
|
||||
EXPECT_STREQ("integer_array_param", params.at(0).get_name().c_str());
|
||||
std::vector<int64_t> integer_array = params.at(0).get_value<std::vector<int64_t>>();
|
||||
ASSERT_EQ(2u, integer_array.size());
|
||||
EXPECT_EQ(42, integer_array.at(0));
|
||||
EXPECT_EQ(-12345, integer_array.at(1));
|
||||
|
||||
c_params->params[0].parameter_values[0].integer_array_value = NULL;
|
||||
FREE_ARRAY_VALUE(c_integer_array);
|
||||
rcl_yaml_node_struct_fini(c_params);
|
||||
}
|
||||
|
||||
TEST(Test_parameter_map_from, double_array_param_value)
|
||||
{
|
||||
rcl_params_t * c_params = make_params({"foo"});
|
||||
make_node_params(c_params, 0, {"double_array_param"});
|
||||
rcl_double_array_t c_double_array;
|
||||
MAKE_ARRAY_VALUE(c_double_array, double, 3.14, -2.718);
|
||||
c_params->params[0].parameter_values[0].double_array_value = &c_double_array;
|
||||
|
||||
rclcpp::ParameterMap map = rclcpp::parameter_map_from(c_params);
|
||||
const std::vector<rclcpp::Parameter> & params = map.at("/foo");
|
||||
EXPECT_STREQ("double_array_param", params.at(0).get_name().c_str());
|
||||
std::vector<double> double_array = params.at(0).get_value<std::vector<double>>();
|
||||
ASSERT_EQ(2u, double_array.size());
|
||||
EXPECT_DOUBLE_EQ(3.14, double_array.at(0));
|
||||
EXPECT_DOUBLE_EQ(-2.718, double_array.at(1));
|
||||
|
||||
c_params->params[0].parameter_values[0].double_array_value = NULL;
|
||||
FREE_ARRAY_VALUE(c_double_array);
|
||||
rcl_yaml_node_struct_fini(c_params);
|
||||
}
|
||||
|
||||
TEST(Test_parameter_map_from, string_array_param_value)
|
||||
{
|
||||
rcl_params_t * c_params = make_params({"foo"});
|
||||
make_node_params(c_params, 0, {"string_array_param"});
|
||||
rcutils_string_array_t c_string_array = rcutils_get_zero_initialized_string_array();
|
||||
ASSERT_EQ(RCUTILS_RET_OK, rcutils_string_array_init(&c_string_array, 2, &(c_params->allocator)));
|
||||
c_string_array.data[0] = rcutils_strdup("Hello", c_params->allocator);
|
||||
c_string_array.data[1] = rcutils_strdup("World", c_params->allocator);
|
||||
c_params->params[0].parameter_values[0].string_array_value = &c_string_array;
|
||||
|
||||
rclcpp::ParameterMap map = rclcpp::parameter_map_from(c_params);
|
||||
const std::vector<rclcpp::Parameter> & params = map.at("/foo");
|
||||
EXPECT_STREQ("string_array_param", params.at(0).get_name().c_str());
|
||||
std::vector<std::string> string_array = params.at(0).get_value<std::vector<std::string>>();
|
||||
ASSERT_EQ(2u, string_array.size());
|
||||
EXPECT_STREQ("Hello", string_array.at(0).c_str());
|
||||
EXPECT_STREQ("World", string_array.at(1).c_str());
|
||||
|
||||
EXPECT_EQ(RCUTILS_RET_OK, rcutils_string_array_fini(&c_string_array));
|
||||
c_params->params[0].parameter_values[0].string_array_value = NULL;
|
||||
rcl_yaml_node_struct_fini(c_params);
|
||||
}
|
Loading…
Add table
Add a link
Reference in a new issue