Parse CLI parameters and YAML files (#508)

* Enable incremental parameter yaml file parsing.

Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>

* Parse CLI parameter files and overrides in rcl.

Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>

* Address peer review comments.

Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
This commit is contained in:
Michel Hidalgo 2019-09-25 14:57:57 -03:00 committed by GitHub
parent 78f8652ee4
commit 9196cb81b4
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
8 changed files with 182 additions and 33 deletions

View file

@ -283,8 +283,11 @@ rcl_arguments_get_param_files(
rcl_allocator_t allocator, rcl_allocator_t allocator,
char *** parameter_files); char *** parameter_files);
/// Return all parameter overrides specified on the command line. /// Return all parameter overrides parsed from the command line.
/** /**
* Parameter overrides are parsed directly from command line arguments and
* parameter files provided in the command line.
*
* <hr> * <hr>
* Attribute | Adherence * Attribute | Adherence
* ------------------ | ------------- * ------------------ | -------------
@ -294,8 +297,9 @@ rcl_arguments_get_param_files(
* Lock-Free | Yes * Lock-Free | Yes
* *
* \param[in] arguments An arguments structure that has been parsed. * \param[in] arguments An arguments structure that has been parsed.
* \param[out] parameter_overrides Zero or more parameter overrides. * \param[out] parameter_overrides Parameter overrides as parsed from command line arguments.
* This structure must be finalized by the caller. * This structure must be finalized by the caller.
* The output is NULL if no parameter overrides were parsed.
* \return `RCL_RET_OK` if everything goes correctly, or * \return `RCL_RET_OK` if everything goes correctly, or
* \return `RCL_RET_INVALID_ARGUMENT` if any function arguments are invalid, or * \return `RCL_RET_INVALID_ARGUMENT` if any function arguments are invalid, or
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or * \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or

View file

@ -25,6 +25,7 @@
<test_depend>ament_cmake_pytest</test_depend> <test_depend>ament_cmake_pytest</test_depend>
<test_depend>ament_lint_auto</test_depend> <test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend> <test_depend>ament_lint_common</test_depend>
<test_depend>rcpputils</test_depend>
<test_depend>rmw</test_depend> <test_depend>rmw</test_depend>
<test_depend>rmw_implementation_cmake</test_depend> <test_depend>rmw_implementation_cmake</test_depend>
<test_depend>launch</test_depend> <test_depend>launch</test_depend>

View file

@ -124,14 +124,18 @@ rcl_arguments_get_param_overrides(
RCL_CHECK_ARGUMENT_FOR_NULL(arguments, RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(arguments, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(arguments->impl, RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(arguments->impl, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(parameter_overrides, RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(parameter_overrides, RCL_RET_INVALID_ARGUMENT);
if (NULL != *parameter_overrides) { if (NULL != *parameter_overrides) {
RCL_SET_ERROR_MSG("Output parameter override pointer is not null. May leak memory."); RCL_SET_ERROR_MSG("Output parameter override pointer is not null. May leak memory.");
return RCL_RET_INVALID_ARGUMENT; return RCL_RET_INVALID_ARGUMENT;
} }
*parameter_overrides = NULL;
if (NULL != arguments->impl->parameter_overrides) {
*parameter_overrides = rcl_yaml_node_struct_copy(arguments->impl->parameter_overrides); *parameter_overrides = rcl_yaml_node_struct_copy(arguments->impl->parameter_overrides);
if (NULL == *parameter_overrides) { if (NULL == *parameter_overrides) {
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
}
return RCL_RET_OK; return RCL_RET_OK;
} }
@ -218,6 +222,7 @@ rcl_ret_t
_rcl_parse_param_file( _rcl_parse_param_file(
const char * arg, const char * arg,
rcl_allocator_t allocator, rcl_allocator_t allocator,
rcl_params_t * params,
char ** param_file); char ** param_file);
/// Parse an argument that may or may not be a parameter file rule. /// Parse an argument that may or may not be a parameter file rule.
@ -237,6 +242,7 @@ rcl_ret_t
_rcl_parse_param_file_rule( _rcl_parse_param_file_rule(
const char * arg, const char * arg,
rcl_allocator_t allocator, rcl_allocator_t allocator,
rcl_params_t * params,
char ** param_file); char ** param_file);
#define RCL_ENABLE_FLAG_PREFIX "--enable-" #define RCL_ENABLE_FLAG_PREFIX "--enable-"
@ -443,11 +449,11 @@ rcl_parse_arguments(
// Attempt to parse argument as parameter file rule // Attempt to parse argument as parameter file rule
if (strcmp(RCL_PARAM_FILE_FLAG, argv[i]) == 0) { if (strcmp(RCL_PARAM_FILE_FLAG, argv[i]) == 0) {
if (i + 1 < argc) { if (i + 1 < argc) {
// Attempt to parse next argument as remap rule // Attempt to parse next argument as parameter file rule
args_impl->parameter_files[args_impl->num_param_files_args] = NULL; args_impl->parameter_files[args_impl->num_param_files_args] = NULL;
if ( if (
RCL_RET_OK == _rcl_parse_param_file( RCL_RET_OK == _rcl_parse_param_file(
argv[i + 1], allocator, argv[i + 1], allocator, args_impl->parameter_overrides,
&args_impl->parameter_files[args_impl->num_param_files_args])) &args_impl->parameter_files[args_impl->num_param_files_args]))
{ {
++(args_impl->num_param_files_args); ++(args_impl->num_param_files_args);
@ -606,7 +612,8 @@ rcl_parse_arguments(
args_impl->parameter_files[args_impl->num_param_files_args] = NULL; args_impl->parameter_files[args_impl->num_param_files_args] = NULL;
if ( if (
RCL_RET_OK == _rcl_parse_param_file_rule( RCL_RET_OK == _rcl_parse_param_file_rule(
argv[i], allocator, &(args_impl->parameter_files[args_impl->num_param_files_args]))) argv[i], allocator, args_impl->parameter_overrides,
&args_impl->parameter_files[args_impl->num_param_files_args]))
{ {
++(args_impl->num_param_files_args); ++(args_impl->num_param_files_args);
RCUTILS_LOG_WARN_NAMED(ROS_PACKAGE_NAME, RCUTILS_LOG_WARN_NAMED(ROS_PACKAGE_NAME,
@ -743,6 +750,12 @@ rcl_parse_arguments(
} }
} }
// Drop parameter overrides if none was found.
if (0U == args_impl->parameter_overrides->num_nodes) {
rcl_yaml_node_struct_fini(args_impl->parameter_overrides);
args_impl->parameter_overrides = NULL;
}
// Shrink unparsed_ros_args // Shrink unparsed_ros_args
if (0 == args_impl->num_unparsed_ros_args) { if (0 == args_impl->num_unparsed_ros_args) {
// No unparsed ros args // No unparsed ros args
@ -1811,16 +1824,21 @@ rcl_ret_t
_rcl_parse_param_file( _rcl_parse_param_file(
const char * arg, const char * arg,
rcl_allocator_t allocator, rcl_allocator_t allocator,
rcl_params_t * params,
char ** param_file) char ** param_file)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(params, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(param_file, RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(param_file, RCL_RET_INVALID_ARGUMENT);
*param_file = rcutils_strdup(arg, allocator); *param_file = rcutils_strdup(arg, allocator);
if (NULL == *param_file) { if (NULL == *param_file) {
RCL_SET_ERROR_MSG("Failed to allocate memory for parameters file path"); RCL_SET_ERROR_MSG("Failed to allocate memory for parameters file path");
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
if (!rcl_parse_yaml_file(*param_file, params)) {
// Error message already set.
return RCL_RET_ERROR;
}
return RCL_RET_OK; return RCL_RET_OK;
} }
@ -1828,9 +1846,12 @@ rcl_ret_t
_rcl_parse_param_file_rule( _rcl_parse_param_file_rule(
const char * arg, const char * arg,
rcl_allocator_t allocator, rcl_allocator_t allocator,
rcl_params_t * params,
char ** param_file) char ** param_file)
{ {
RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(params, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(param_file, RCL_RET_INVALID_ARGUMENT);
const size_t param_prefix_len = strlen(RCL_PARAM_FILE_ARG_RULE); const size_t param_prefix_len = strlen(RCL_PARAM_FILE_ARG_RULE);
if (strncmp(RCL_PARAM_FILE_ARG_RULE, arg, param_prefix_len) == 0) { if (strncmp(RCL_PARAM_FILE_ARG_RULE, arg, param_prefix_len) == 0) {
@ -1841,6 +1862,10 @@ _rcl_parse_param_file_rule(
return RCL_RET_BAD_ALLOC; return RCL_RET_BAD_ALLOC;
} }
snprintf(*param_file, outlen + 1, "%s", arg + param_prefix_len); snprintf(*param_file, outlen + 1, "%s", arg + param_prefix_len);
if (!rcl_parse_yaml_file(*param_file, params)) {
// Error message already set.
return RCL_RET_ERROR;
}
return RCL_RET_OK; return RCL_RET_OK;
} }
RCL_SET_ERROR_MSG("Argument does not start with '" RCL_PARAM_FILE_ARG_RULE "'"); RCL_SET_ERROR_MSG("Argument does not start with '" RCL_PARAM_FILE_ARG_RULE "'");

View file

@ -39,6 +39,7 @@ typedef struct rcl_arguments_impl_t
/// Parameter override rules parsed from arguments. /// Parameter override rules parsed from arguments.
rcl_params_t * parameter_overrides; rcl_params_t * parameter_overrides;
/// Array of yaml parameter file paths /// Array of yaml parameter file paths
char ** parameter_files; char ** parameter_files;
/// Length of parameter_files. /// Length of parameter_files.

View file

@ -3,6 +3,7 @@ find_package(launch_testing_ament_cmake REQUIRED)
find_package(test_msgs REQUIRED) find_package(test_msgs REQUIRED)
find_package(rcpputils REQUIRED)
find_package(rmw_implementation_cmake REQUIRED) find_package(rmw_implementation_cmake REQUIRED)
find_package(osrf_testing_tools_cpp REQUIRED) find_package(osrf_testing_tools_cpp REQUIRED)
@ -148,7 +149,7 @@ function(test_target_function)
ENV ${rmw_implementation_env_var} ENV ${rmw_implementation_env_var}
APPEND_LIBRARY_DIRS ${extra_lib_dirs} APPEND_LIBRARY_DIRS ${extra_lib_dirs}
LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools
AMENT_DEPENDENCIES "osrf_testing_tools_cpp" AMENT_DEPENDENCIES "osrf_testing_tools_cpp" "rcpputils"
) )
rcl_add_custom_gtest(test_remap${target_suffix} rcl_add_custom_gtest(test_remap${target_suffix}

View file

@ -14,9 +14,11 @@
#include <gtest/gtest.h> #include <gtest/gtest.h>
#include <sstream> #include <sstream>
#include <string>
#include <vector> #include <vector>
#include "osrf_testing_tools_cpp/scope_exit.hpp" #include "osrf_testing_tools_cpp/scope_exit.hpp"
#include "rcpputils/filesystem_helper.hpp"
#include "rcl/rcl.h" #include "rcl/rcl.h"
#include "rcl/arguments.h" #include "rcl/arguments.h"
@ -36,11 +38,14 @@ class CLASSNAME (TestArgumentsFixture, RMW_IMPLEMENTATION) : public ::testing::T
public: public:
void SetUp() void SetUp()
{ {
test_path /= "test_arguments";
} }
void TearDown() void TearDown()
{ {
} }
rcpputils::fs::path test_path{TEST_RESOURCES_DIRECTORY};
}; };
#define EXPECT_UNPARSED(parsed_args, ...) \ #define EXPECT_UNPARSED(parsed_args, ...) \
@ -143,7 +148,9 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), check_known_vs_unkno
EXPECT_TRUE(are_known_ros_args({"--ros-args", "-p", "/foo/bar:=bar"})); EXPECT_TRUE(are_known_ros_args({"--ros-args", "-p", "/foo/bar:=bar"}));
EXPECT_TRUE(are_known_ros_args({"--ros-args", "-p", "foo:=/bar"})); EXPECT_TRUE(are_known_ros_args({"--ros-args", "-p", "foo:=/bar"}));
EXPECT_TRUE(are_known_ros_args({"--ros-args", "-p", "/foo123:=/bar123"})); EXPECT_TRUE(are_known_ros_args({"--ros-args", "-p", "/foo123:=/bar123"}));
EXPECT_TRUE(are_known_ros_args({"--ros-args", "--params-file", "file_name.yaml"}));
const std::string parameters_filepath = (test_path / "test_parameters.1.yaml").string();
EXPECT_TRUE(are_known_ros_args({"--ros-args", "--params-file", parameters_filepath.c_str()}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "--custom-ros-arg"})); EXPECT_FALSE(are_known_ros_args({"--ros-args", "--custom-ros-arg"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "__node:=node_name"})); EXPECT_FALSE(are_known_ros_args({"--ros-args", "__node:=node_name"}));
@ -204,7 +211,9 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), check_known_deprecat
EXPECT_TRUE(are_known_ros_args({"rostopic:///foo/bar:=baz"})); EXPECT_TRUE(are_known_ros_args({"rostopic:///foo/bar:=baz"}));
// Setting params file // Setting params file
EXPECT_TRUE(are_known_ros_args({"__params:=file_name.yaml"})); const std::string parameters_filepath = (test_path / "test_parameters.1.yaml").string();
const std::string parameter_rule = "__params:=" + parameters_filepath;
EXPECT_TRUE(are_known_ros_args({parameter_rule.c_str()}));
// Setting config logging file // Setting config logging file
EXPECT_TRUE(are_known_ros_args({"__log_config_file:=file.config"})); EXPECT_TRUE(are_known_ros_args({"__log_config_file:=file.config"}));
@ -245,9 +254,10 @@ are_valid_ros_args(std::vector<const char *> argv)
} }
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), check_valid_vs_invalid_args) { TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), check_valid_vs_invalid_args) {
const std::string parameters_filepath = (test_path / "test_parameters.1.yaml").string();
EXPECT_TRUE(are_valid_ros_args({ EXPECT_TRUE(are_valid_ros_args({
"--ros-args", "-p", "foo:=bar", "-r", "__node:=node_name", "--ros-args", "-p", "foo:=bar", "-r", "__node:=node_name",
"--params-file", "file_name.yaml", "--log-level", "INFO", "--params-file", parameters_filepath.c_str(), "--log-level", "INFO",
"--log-config-file", "file.config" "--log-config-file", "file.config"
})); }));
@ -530,10 +540,12 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_double_parse) {
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
ASSERT_EQ(RCL_RET_OK, ASSERT_EQ(RCL_RET_OK,
rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args)); rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args));
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
});
ASSERT_EQ(RCL_RET_INVALID_ARGUMENT, ASSERT_EQ(RCL_RET_INVALID_ARGUMENT,
rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args)); rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args));
rcl_reset_error(); rcl_reset_error();
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
} }
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_fini_null) { TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_fini_null) {
@ -669,16 +681,19 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_
ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args); ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
});
int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args); int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args);
EXPECT_EQ(0, parameter_filecount); EXPECT_EQ(0, parameter_filecount);
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
} }
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_single) { TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_single) {
const std::string parameters_filepath = (test_path / "test_parameters.1.yaml").string();
const char * argv[] = { const char * argv[] = {
"process_name", "--ros-args", "-r", "__ns:=/namespace", "random:=arg", "process_name", "--ros-args", "-r", "__ns:=/namespace", "random:=arg",
"--params-file", "parameter_filepath" "--params-file", parameters_filepath.c_str()
}; };
int argc = sizeof(argv) / sizeof(const char *); int argc = sizeof(argv) / sizeof(const char *);
rcl_ret_t ret; rcl_ret_t ret;
@ -688,26 +703,49 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_
ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args); ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
});
int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args); int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args);
EXPECT_EQ(1, parameter_filecount); EXPECT_EQ(1, parameter_filecount);
char ** parameter_files = NULL; char ** parameter_files = NULL;
ret = rcl_arguments_get_param_files(&parsed_args, alloc, &parameter_files); ret = rcl_arguments_get_param_files(&parsed_args, alloc, &parameter_files);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("parameter_filepath", parameter_files[0]); EXPECT_STREQ(parameters_filepath.c_str(), parameter_files[0]);
for (int i = 0; i < parameter_filecount; ++i) { for (int i = 0; i < parameter_filecount; ++i) {
alloc.deallocate(parameter_files[i], alloc.state); alloc.deallocate(parameter_files[i], alloc.state);
} }
alloc.deallocate(parameter_files, alloc.state); alloc.deallocate(parameter_files, alloc.state);
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
rcl_params_t * params = NULL;
ret = rcl_arguments_get_param_overrides(&parsed_args, &params);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_yaml_node_struct_fini(params);
});
EXPECT_EQ(1U, params->num_nodes);
rcl_variant_t * param_value =
rcl_yaml_node_struct_get("some_node", "param_group.string_param", params);
ASSERT_TRUE(NULL != param_value);
ASSERT_TRUE(NULL != param_value->string_value);
EXPECT_STREQ("foo", param_value->string_value);
param_value = rcl_yaml_node_struct_get("some_node", "int_param", params);
ASSERT_TRUE(NULL != param_value);
ASSERT_TRUE(NULL != param_value->integer_value);
EXPECT_EQ(1, *(param_value->integer_value));
} }
// \deprecated to be removed in F-Turtle // \deprecated to be removed in F-Turtle
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_deprecated_param_argument_single) { TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_deprecated_param_argument_single) {
const std::string parameters_filepath = (test_path / "test_parameters.1.yaml").string();
const std::string parameter_rule = "__params:=" + parameters_filepath;
const char * argv[] = { const char * argv[] = {
"process_name", "--ros-args", "-r", "__ns:=/namespace", "random:=arg", "--", "process_name", "--ros-args", "-r", "__ns:=/namespace", "random:=arg", "--",
"__params:=parameter_filepath" parameter_rule.c_str()
}; };
int argc = sizeof(argv) / sizeof(const char *); int argc = sizeof(argv) / sizeof(const char *);
rcl_ret_t ret; rcl_ret_t ret;
@ -717,25 +755,48 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_deprecated_para
ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args); ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
});
int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args); int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args);
EXPECT_EQ(1, parameter_filecount); EXPECT_EQ(1, parameter_filecount);
char ** parameter_files = NULL; char ** parameter_files = NULL;
ret = rcl_arguments_get_param_files(&parsed_args, alloc, &parameter_files); ret = rcl_arguments_get_param_files(&parsed_args, alloc, &parameter_files);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("parameter_filepath", parameter_files[0]); EXPECT_STREQ(parameters_filepath.c_str(), parameter_files[0]);
for (int i = 0; i < parameter_filecount; ++i) { for (int i = 0; i < parameter_filecount; ++i) {
alloc.deallocate(parameter_files[i], alloc.state); alloc.deallocate(parameter_files[i], alloc.state);
} }
alloc.deallocate(parameter_files, alloc.state); alloc.deallocate(parameter_files, alloc.state);
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
rcl_params_t * params = NULL;
ret = rcl_arguments_get_param_overrides(&parsed_args, &params);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_yaml_node_struct_fini(params);
});
EXPECT_EQ(1U, params->num_nodes);
rcl_variant_t * param_value =
rcl_yaml_node_struct_get("some_node", "param_group.string_param", params);
ASSERT_TRUE(NULL != param_value);
ASSERT_TRUE(NULL != param_value->string_value);
EXPECT_STREQ("foo", param_value->string_value);
param_value = rcl_yaml_node_struct_get("some_node", "int_param", params);
ASSERT_TRUE(NULL != param_value);
ASSERT_TRUE(NULL != param_value->integer_value);
EXPECT_EQ(1, *(param_value->integer_value));
} }
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_multiple) { TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_multiple) {
const std::string parameters_filepath1 = (test_path / "test_parameters.1.yaml").string();
const std::string parameters_filepath2 = (test_path / "test_parameters.2.yaml").string();
const char * argv[] = { const char * argv[] = {
"process_name", "--ros-args", "--params-file", "parameter_filepath1", "process_name", "--ros-args", "--params-file", parameters_filepath1.c_str(),
"-r", "__ns:=/namespace", "random:=arg", "--params-file", "parameter_filepath2" "-r", "__ns:=/namespace", "random:=arg", "--params-file", parameters_filepath2.c_str()
}; };
int argc = sizeof(argv) / sizeof(const char *); int argc = sizeof(argv) / sizeof(const char *);
rcl_ret_t ret; rcl_ret_t ret;
@ -745,19 +806,55 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_
ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args); ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
});
int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args); int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args);
EXPECT_EQ(2, parameter_filecount); EXPECT_EQ(2, parameter_filecount);
char ** parameter_files = NULL; char ** parameter_files = NULL;
ret = rcl_arguments_get_param_files(&parsed_args, alloc, &parameter_files); ret = rcl_arguments_get_param_files(&parsed_args, alloc, &parameter_files);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_STREQ("parameter_filepath1", parameter_files[0]); EXPECT_STREQ(parameters_filepath1.c_str(), parameter_files[0]);
EXPECT_STREQ("parameter_filepath2", parameter_files[1]); EXPECT_STREQ(parameters_filepath2.c_str(), parameter_files[1]);
for (int i = 0; i < parameter_filecount; ++i) { for (int i = 0; i < parameter_filecount; ++i) {
alloc.deallocate(parameter_files[i], alloc.state); alloc.deallocate(parameter_files[i], alloc.state);
} }
alloc.deallocate(parameter_files, alloc.state); alloc.deallocate(parameter_files, alloc.state);
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
rcl_params_t * params = NULL;
ret = rcl_arguments_get_param_overrides(&parsed_args, &params);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_yaml_node_struct_fini(params);
});
EXPECT_EQ(2U, params->num_nodes);
rcl_variant_t * param_value =
rcl_yaml_node_struct_get("some_node", "int_param", params);
ASSERT_TRUE(NULL != param_value);
ASSERT_TRUE(NULL != param_value->integer_value);
EXPECT_EQ(3, *(param_value->integer_value));
param_value = rcl_yaml_node_struct_get("some_node", "param_group.string_param", params);
ASSERT_TRUE(NULL != param_value);
ASSERT_TRUE(NULL != param_value->string_value);
EXPECT_STREQ("foo", param_value->string_value);
param_value = rcl_yaml_node_struct_get("another_node", "double_param", params);
ASSERT_TRUE(NULL != param_value);
ASSERT_TRUE(NULL != param_value->double_value);
EXPECT_DOUBLE_EQ(1.0, *(param_value->double_value));
param_value = rcl_yaml_node_struct_get("another_node", "param_group.bool_array_param", params);
ASSERT_TRUE(NULL != param_value);
ASSERT_TRUE(NULL != param_value->bool_array_value);
ASSERT_TRUE(NULL != param_value->bool_array_value->values);
ASSERT_EQ(3U, param_value->bool_array_value->size);
EXPECT_TRUE(param_value->bool_array_value->values[0]);
EXPECT_FALSE(param_value->bool_array_value->values[1]);
EXPECT_FALSE(param_value->bool_array_value->values[2]);
} }
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_param_overrides) { TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_param_overrides) {
@ -769,6 +866,9 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_param_overri
rcl_ret_t ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args); rcl_ret_t ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args);
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
});
ret = rcl_arguments_get_param_overrides(&parsed_args, NULL); ret = rcl_arguments_get_param_overrides(&parsed_args, NULL);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str;
@ -788,16 +888,15 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_param_overri
params = NULL; params = NULL;
ret = rcl_arguments_get_param_overrides(&parsed_args, &params); ret = rcl_arguments_get_param_overrides(&parsed_args, &params);
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
EXPECT_EQ(0U, params->num_nodes); EXPECT_TRUE(NULL == params);
rcl_yaml_node_struct_fini(params);
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
} }
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_two_param_overrides) { TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_overrides) {
const std::string parameters_filepath = (test_path / "test_parameters.1.yaml").string();
const char * argv[] = { const char * argv[] = {
"process_name", "--ros-args", "process_name", "--ros-args",
"--param", "string_param:=test_string", "--params-file", parameters_filepath.c_str(),
"--param", "string_param:=bar",
"-p", "some_node:int_param:=4" "-p", "some_node:int_param:=4"
}; };
int argc = sizeof(argv) / sizeof(const char *); int argc = sizeof(argv) / sizeof(const char *);
@ -823,10 +922,15 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_two_param_overr
rcl_yaml_node_struct_get("/**", "string_param", params); rcl_yaml_node_struct_get("/**", "string_param", params);
ASSERT_TRUE(NULL != param_value); ASSERT_TRUE(NULL != param_value);
ASSERT_TRUE(NULL != param_value->string_value); ASSERT_TRUE(NULL != param_value->string_value);
EXPECT_STREQ("test_string", param_value->string_value); EXPECT_STREQ("bar", param_value->string_value);
param_value = rcl_yaml_node_struct_get("some_node", "int_param", params); param_value = rcl_yaml_node_struct_get("some_node", "int_param", params);
ASSERT_TRUE(NULL != param_value); ASSERT_TRUE(NULL != param_value);
ASSERT_TRUE(NULL != param_value->integer_value); ASSERT_TRUE(NULL != param_value->integer_value);
EXPECT_EQ(4, *(param_value->integer_value)); EXPECT_EQ(4, *(param_value->integer_value));
param_value = rcl_yaml_node_struct_get("some_node", "param_group.string_param", params);
ASSERT_TRUE(NULL != param_value);
ASSERT_TRUE(NULL != param_value->string_value);
EXPECT_STREQ("foo", param_value->string_value);
} }

View file

@ -0,0 +1,5 @@
some_node:
ros__parameters:
int_param: 1
param_group:
string_param: foo

View file

@ -0,0 +1,8 @@
some_node:
ros__parameters:
int_param: 3
another_node:
ros__parameters:
double_param: 1.0
param_group:
bool_array_param: [true, false, false]