Take parameter overrides provided through the CLI. (#865)
* Take parameter overrides provided through the CLI. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Address peer review comments. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Do not 'find_package' rcpputils twice. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
This commit is contained in:
parent
b6d18ccc81
commit
7728d8a38c
4 changed files with 110 additions and 50 deletions
|
@ -150,6 +150,8 @@ if(BUILD_TESTING)
|
|||
|
||||
include(cmake/rclcpp_add_build_failure_test.cmake)
|
||||
|
||||
add_definitions(-DTEST_RESOURCES_DIRECTORY="${CMAKE_CURRENT_BINARY_DIR}/test/resources")
|
||||
|
||||
ament_add_gtest(test_client test/test_client.cpp)
|
||||
if(TARGET test_client)
|
||||
ament_target_dependencies(test_client
|
||||
|
@ -215,6 +217,7 @@ if(BUILD_TESTING)
|
|||
if(TARGET test_node)
|
||||
ament_target_dependencies(test_node
|
||||
"rcl_interfaces"
|
||||
"rcpputils"
|
||||
"rmw"
|
||||
"rosidl_generator_cpp"
|
||||
"rosidl_typesupport_cpp"
|
||||
|
@ -462,6 +465,11 @@ if(BUILD_TESTING)
|
|||
"rcl")
|
||||
target_link_libraries(test_multi_threaded_executor ${PROJECT_NAME})
|
||||
endif()
|
||||
|
||||
# Install test resources
|
||||
install(
|
||||
DIRECTORY test/resources
|
||||
DESTINATION ${CMAKE_CURRENT_BINARY_DIR}/test)
|
||||
endif()
|
||||
|
||||
ament_package()
|
||||
|
|
|
@ -84,58 +84,29 @@ NodeParameters::NodeParameters(
|
|||
throw std::runtime_error("Need valid node options in NodeParameters");
|
||||
}
|
||||
|
||||
// Get paths to yaml files containing initial parameter values
|
||||
std::vector<std::string> yaml_paths;
|
||||
|
||||
auto get_yaml_paths = [&yaml_paths, &options](const rcl_arguments_t * args) {
|
||||
int num_yaml_files = rcl_arguments_get_param_files_count(args);
|
||||
if (num_yaml_files > 0) {
|
||||
char ** param_files;
|
||||
rcl_ret_t ret = rcl_arguments_get_param_files(args, options->allocator, ¶m_files);
|
||||
if (RCL_RET_OK != ret) {
|
||||
rclcpp::exceptions::throw_from_rcl_error(ret);
|
||||
}
|
||||
auto cleanup_param_files = make_scope_exit(
|
||||
[¶m_files, &num_yaml_files, &options]() {
|
||||
for (int i = 0; i < num_yaml_files; ++i) {
|
||||
options->allocator.deallocate(param_files[i], options->allocator.state);
|
||||
}
|
||||
options->allocator.deallocate(param_files, options->allocator.state);
|
||||
});
|
||||
for (int i = 0; i < num_yaml_files; ++i) {
|
||||
yaml_paths.emplace_back(param_files[i]);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
std::vector<const rcl_arguments_t *> argument_sources;
|
||||
// global before local so that local overwrites global
|
||||
if (options->use_global_arguments) {
|
||||
auto context_ptr = node_base->get_context()->get_rcl_context();
|
||||
get_yaml_paths(&(context_ptr->global_arguments));
|
||||
argument_sources.push_back(&(context_ptr->global_arguments));
|
||||
}
|
||||
get_yaml_paths(&(options->arguments));
|
||||
argument_sources.push_back(&options->arguments);
|
||||
|
||||
// Get fully qualified node name post-remapping to use to find node's params in yaml files
|
||||
combined_name_ = node_base->get_fully_qualified_name();
|
||||
|
||||
// TODO(sloretz) use rcl to parse yaml when circular dependency is solved
|
||||
// See https://github.com/ros2/rcl/issues/252
|
||||
for (const std::string & yaml_path : yaml_paths) {
|
||||
rcl_params_t * yaml_params = rcl_yaml_node_struct_init(options->allocator);
|
||||
if (nullptr == yaml_params) {
|
||||
throw std::bad_alloc();
|
||||
for (const rcl_arguments_t * source : argument_sources) {
|
||||
rcl_params_t * params = NULL;
|
||||
rcl_ret_t ret = rcl_arguments_get_param_overrides(source, ¶ms);
|
||||
if (RCL_RET_OK != ret) {
|
||||
rclcpp::exceptions::throw_from_rcl_error(ret);
|
||||
}
|
||||
if (!rcl_parse_yaml_file(yaml_path.c_str(), yaml_params)) {
|
||||
std::ostringstream ss;
|
||||
ss << "Failed to parse parameters from file '" << yaml_path << "': " <<
|
||||
rcl_get_error_string().str;
|
||||
rcl_reset_error();
|
||||
throw std::runtime_error(ss.str());
|
||||
}
|
||||
|
||||
rclcpp::ParameterMap initial_map = rclcpp::parameter_map_from(yaml_params);
|
||||
rcl_yaml_node_struct_fini(yaml_params);
|
||||
|
||||
if (params) {
|
||||
auto cleanup_params = make_scope_exit(
|
||||
[params]() {
|
||||
rcl_yaml_node_struct_fini(params);
|
||||
});
|
||||
rclcpp::ParameterMap initial_map = rclcpp::parameter_map_from(params);
|
||||
for (auto iter = initial_map.begin(); initial_map.end() != iter; iter++) {
|
||||
// TODO(cottsay) implement further wildcard matching
|
||||
if (iter->first == "/**" || iter->first == combined_name_) {
|
||||
|
@ -147,6 +118,7 @@ NodeParameters::NodeParameters(
|
|||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// parameter overrides passed to constructor will overwrite overrides from yaml file sources
|
||||
for (auto & param : parameter_overrides) {
|
||||
|
|
4
rclcpp/test/resources/test_node/test_parameters.yaml
Normal file
4
rclcpp/test/resources/test_node/test_parameters.yaml
Normal file
|
@ -0,0 +1,4 @@
|
|||
/**:
|
||||
ros__parameters:
|
||||
parameter_int: 21
|
||||
parameter_string_array: [baz, baz, baz]
|
|
@ -25,6 +25,8 @@
|
|||
#include "rclcpp/scope_exit.hpp"
|
||||
#include "rclcpp/rclcpp.hpp"
|
||||
|
||||
#include "rcpputils/filesystem_helper.hpp"
|
||||
|
||||
class TestNode : public ::testing::Test
|
||||
{
|
||||
protected:
|
||||
|
@ -32,6 +34,13 @@ protected:
|
|||
{
|
||||
rclcpp::init(0, nullptr);
|
||||
}
|
||||
|
||||
void SetUp() override
|
||||
{
|
||||
test_resources_path /= "test_node";
|
||||
}
|
||||
|
||||
rcpputils::fs::path test_resources_path{TEST_RESOURCES_DIRECTORY};
|
||||
};
|
||||
|
||||
/*
|
||||
|
@ -469,6 +478,7 @@ TEST_F(TestNode, declare_parameter_with_overrides) {
|
|||
{"parameter_rejected", 42},
|
||||
{"parameter_type_mismatch", "not an int"},
|
||||
});
|
||||
|
||||
auto node = std::make_shared<rclcpp::Node>("test_declare_parameter_node"_unq, no);
|
||||
{
|
||||
// no default, with override
|
||||
|
@ -685,6 +695,72 @@ TEST_F(TestNode, declare_parameters_with_no_initial_values) {
|
|||
}
|
||||
}
|
||||
|
||||
TEST_F(TestNode, declare_parameter_with_cli_overrides) {
|
||||
const std::string parameters_filepath = (
|
||||
test_resources_path / "test_parameters.yaml").string();
|
||||
// test cases with overrides
|
||||
rclcpp::NodeOptions no;
|
||||
no.arguments({
|
||||
"--ros-args",
|
||||
"-p", "parameter_bool:=true",
|
||||
"-p", "parameter_int:=42",
|
||||
"-p", "parameter_double:=0.42",
|
||||
"-p", "parameter_string:=foo",
|
||||
"--params-file", parameters_filepath.c_str(),
|
||||
"-p", "parameter_bool_array:=[false, true]",
|
||||
"-p", "parameter_int_array:=[-21, 42]",
|
||||
"-p", "parameter_double_array:=[-1.0, .42]",
|
||||
"-p", "parameter_string_array:=[foo, bar]"
|
||||
});
|
||||
|
||||
auto node = std::make_shared<rclcpp::Node>("test_declare_parameter_node"_unq, no);
|
||||
{
|
||||
rclcpp::ParameterValue value = node->declare_parameter("parameter_bool");
|
||||
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_BOOL);
|
||||
EXPECT_EQ(value.get<bool>(), true);
|
||||
}
|
||||
{
|
||||
rclcpp::ParameterValue value = node->declare_parameter("parameter_int");
|
||||
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_INTEGER);
|
||||
EXPECT_EQ(value.get<int64_t>(), 21); // set to 42 in CLI, overriden by file
|
||||
}
|
||||
{
|
||||
rclcpp::ParameterValue value = node->declare_parameter("parameter_double");
|
||||
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_DOUBLE);
|
||||
EXPECT_EQ(value.get<double>(), 0.42);
|
||||
}
|
||||
{
|
||||
rclcpp::ParameterValue value = node->declare_parameter("parameter_string");
|
||||
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_STRING);
|
||||
EXPECT_EQ(value.get<std::string>(), "foo");
|
||||
}
|
||||
{
|
||||
rclcpp::ParameterValue value = node->declare_parameter("parameter_bool_array");
|
||||
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_BOOL_ARRAY);
|
||||
std::vector<bool> expected_value{false, true};
|
||||
EXPECT_EQ(value.get<std::vector<bool>>(), expected_value);
|
||||
}
|
||||
{
|
||||
rclcpp::ParameterValue value = node->declare_parameter("parameter_int_array");
|
||||
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_INTEGER_ARRAY);
|
||||
std::vector<int64_t> expected_value{-21, 42};
|
||||
EXPECT_EQ(value.get<std::vector<int64_t>>(), expected_value);
|
||||
}
|
||||
{
|
||||
rclcpp::ParameterValue value = node->declare_parameter("parameter_double_array");
|
||||
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_DOUBLE_ARRAY);
|
||||
std::vector<double> expected_value{-1.0, 0.42};
|
||||
EXPECT_EQ(value.get<std::vector<double>>(), expected_value);
|
||||
}
|
||||
{
|
||||
rclcpp::ParameterValue value = node->declare_parameter("parameter_string_array");
|
||||
EXPECT_EQ(value.get_type(), rclcpp::PARAMETER_STRING_ARRAY);
|
||||
std::vector<std::string> expected_value{"foo", "bar"};
|
||||
// set to [baz, baz, baz] in file, overriden by CLI
|
||||
EXPECT_EQ(value.get<std::vector<std::string>>(), expected_value);
|
||||
}
|
||||
}
|
||||
|
||||
TEST_F(TestNode, undeclare_parameter) {
|
||||
auto node = std::make_shared<rclcpp::Node>("test_undeclare_parameter_node"_unq);
|
||||
{
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue