Skip to content

Commit

Permalink
Fix behavior when provided a malformed parameters file (#556)
Browse files Browse the repository at this point in the history
* Don't finalize parameters struct in rcl_parse_yaml_file function

The function assumes that the structure has already been initialized, so it should be the callers
responsibility to finalize it. Otherwise, this may lead to a double free as reported in #553.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Return an error code if there's a malformed parameters file

This restores behavior that was lost when the '__params:=' syntax was deprecated in #495.

An extra guard was also added when finalizing the parameters struct.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Refactor comment

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Add regression test

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Provide detailed error message

Also warn about deprecated usage, even if there is an error parsing parameters file.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron authored Jan 28, 2020
1 parent 48cb27e commit b6f6492
Show file tree
Hide file tree
Showing 4 changed files with 47 additions and 9 deletions.
30 changes: 22 additions & 8 deletions rcl/src/rcl/arguments.c
Original file line number Diff line number Diff line change
Expand Up @@ -610,21 +610,35 @@ rcl_parse_arguments(

// Attempt to parse argument as parameter file rule
args_impl->parameter_files[args_impl->num_param_files_args] = NULL;
if (
RCL_RET_OK == _rcl_parse_param_file_rule(
argv[i], allocator, args_impl->parameter_overrides,
&args_impl->parameter_files[args_impl->num_param_files_args]))
{
++(args_impl->num_param_files_args);
ret = _rcl_parse_param_file_rule(
argv[i], allocator, args_impl->parameter_overrides,
&args_impl->parameter_files[args_impl->num_param_files_args]);

// Deprecation warning regardless if there is an error parsing the file
if (RCL_RET_INVALID_PARAM_RULE != ret) {
RCUTILS_LOG_WARN_NAMED(ROS_PACKAGE_NAME,
"Found parameter file rule '%s'. This syntax is deprecated. Use '%s %s %s' instead.",
argv[i], RCL_ROS_ARGS_FLAG, RCL_PARAM_FILE_FLAG,
args_impl->parameter_files[args_impl->num_param_files_args - 1]);
args_impl->parameter_files[args_impl->num_param_files_args]);
}

if (RCL_RET_OK == ret) {
++(args_impl->num_param_files_args);
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"params rule : %s\n total num param rules %d",
args_impl->parameter_files[args_impl->num_param_files_args - 1],
args_impl->num_param_files_args);
continue;
} else if (RCL_RET_ERROR == ret) {
// If _rcl_parse_param_file_rule() returned RCL_RET_ERROR then the argument contained the
// '__params:=' prefix, but parsing the parameter file failed.
rcl_error_string_t prev_error_string = rcl_get_error_string();
rcl_reset_error();
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse params file: '%s'. Error: %s",
args_impl->parameter_files[args_impl->num_param_files_args],
prev_error_string.str);
goto fail;
}
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Couldn't parse arg %d (%s) as a deprecated parameter file rule. Error: %s",
Expand Down Expand Up @@ -751,7 +765,7 @@ rcl_parse_arguments(
}

// Drop parameter overrides if none was found.
if (0U == args_impl->parameter_overrides->num_nodes) {
if (NULL != args_impl->parameter_overrides && 0U == args_impl->parameter_overrides->num_nodes) {
rcl_yaml_node_struct_fini(args_impl->parameter_overrides);
args_impl->parameter_overrides = NULL;
}
Expand Down
20 changes: 20 additions & 0 deletions rcl/test/rcl/test_arguments.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -897,6 +897,26 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_deprecated_para
EXPECT_EQ(1, *(param_value->integer_value));
}

// Regression test for https://github.com/ros2/rcl/issues/553
// Testing behaviour that was broken in Eloquent
TEST_F(
CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_deprecated_param_argument_malformed)
{
const std::string parameters_filepath = (test_path / "test_malformed_parameters.1.yaml").string();
const std::string parameter_rule = "__params:=" + parameters_filepath;
const char * argv[] = {
"process_name", parameter_rule.c_str()
};
int argc = sizeof(argv) / sizeof(const char *);
rcl_ret_t ret;

rcl_allocator_t alloc = rcl_get_default_allocator();
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();

ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args);
ASSERT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str;
}

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();
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
some_node:
ros_parameters:
int_param: 1
param_group:
string_param: foo
1 change: 0 additions & 1 deletion rcl_yaml_param_parser/src/parser.c
Original file line number Diff line number Diff line change
Expand Up @@ -1705,7 +1705,6 @@ bool rcl_parse_yaml_file(
if (NULL != ns_tracker.parameter_ns) {
allocator.deallocate(ns_tracker.parameter_ns, allocator.state);
}
rcl_yaml_node_struct_fini(params_st);
return false;
}

Expand Down

0 comments on commit b6f6492

Please sign in to comment.