Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fail fast on invalid ROS arguments #493

Merged
merged 3 commits into from
Sep 6, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 6 additions & 2 deletions rcl/include/rcl/arguments.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,6 +80,9 @@ rcl_get_zero_initialized_arguments(void);
* `warn`, not case sensitive.
* If multiple of these rules are found, the last one parsed will be used.
*
* If an argument does not appear to be a valid ROS argument e.g. a `-r/--remap` flag followed by
* anything but a valid remap rule, parsing will fail immediately.
*
* If an argument does not appear to be a known ROS argument, then it is skipped and left unparsed.
*
* \sa rcl_arguments_get_count_unparsed_ros()
Expand All @@ -104,6 +107,7 @@ rcl_get_zero_initialized_arguments(void);
* \param[out] args_output A structure that will contain the result of parsing.
* Must be zero initialized before use.
* \return `RCL_RET_OK` if the arguments were parsed successfully, or
* \return `RCL_RET_INVALID_ROS_ARGS` if an invalid ROS argument is found, 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_ERROR` if an unspecified error occurs.
Expand Down Expand Up @@ -190,9 +194,9 @@ int
rcl_arguments_get_count_unparsed_ros(
const rcl_arguments_t * args);

/// Return a list of indices to ROS specific arguments that were not successfully parsed.
/// Return a list of indices to unknown ROS specific arguments that were left unparsed.
/**
* Some ROS specific arguments may not have been successfully parsed, or were not intended to be
* Some ROS specific arguments may not have been recognized, or were not intended to be
* parsed by rcl.
* This function populates an array of indices to these arguments in the original argv array.
*
Expand Down
2 changes: 2 additions & 0 deletions rcl/include/rcl/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,8 @@ typedef rmw_ret_t rcl_ret_t;
#define RCL_RET_INVALID_REMAP_RULE 1001
/// Expected one type of lexeme but got another
#define RCL_RET_WRONG_LEXEME 1002
/// Found invalid ros argument while parsing
#define RCL_RET_INVALID_ROS_ARGS 1003
/// Argument is not a valid parameter rule
#define RCL_RET_INVALID_PARAM_RULE 1010
/// Argument is not a valid log level rule
Expand Down
37 changes: 23 additions & 14 deletions rcl/src/rcl/arguments.c
Original file line number Diff line number Diff line change
Expand Up @@ -310,18 +310,22 @@ rcl_parse_arguments(
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "param override rule : %s\n", argv[i + 1]);
i += 1; // Skip flag here, for loop will skip rule.
continue;
} else {
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Couldn't parse arg %d (%s) as parameter override rule. Error: %s", i + 1,
argv[i + 1], rcl_get_error_string().str);
}
rcl_error_string_t prev_error_string = rcl_get_error_string();
rcl_reset_error();
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse parameter override rule: '%s %s'. Error: %s", argv[i], argv[i + 1],
ivanpauno marked this conversation as resolved.
Show resolved Hide resolved
prev_error_string.str);
} else {
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Couldn't parse arg %d (%s) as parameter override flag. No rule found.\n",
i, argv[i]);
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse trailing parameter override rule: '%s'. No rule found.", argv[i]);
}
rcl_reset_error();
ret = RCL_RET_INVALID_ROS_ARGS;
goto fail;
}
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Couldn't parse arg %d (%s) as parameter override rule. Not a '%s' or '%s' flag.", i,
argv[i], RCL_PARAM_FLAG, RCL_SHORT_PARAM_FLAG);

// Attempt to parse argument as remap rule flag
if (strcmp(RCL_REMAP_FLAG, argv[i]) == 0 || strcmp(RCL_SHORT_REMAP_FLAG, argv[i]) == 0) {
Expand All @@ -335,16 +339,21 @@ rcl_parse_arguments(
i += 1; // Skip flag here, for loop will skip rule.
continue;
}
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Couldn't parse arg %d (%s) as remap rule. Error: %s", i + 1, argv[i + 1],
rcl_get_error_string().str);
rcl_error_string_t prev_error_string = rcl_get_error_string();
rcl_reset_error();
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse remap rule: '%s %s'. Error: %s", argv[i], argv[i + 1],
ivanpauno marked this conversation as resolved.
Show resolved Hide resolved
prev_error_string.str);
} else {
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Couldn't parse arg %d (%s) as remap rule flag. No rule found.\n",
i, argv[i]);
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse trailing remap rule: '%s'. No rule found.", argv[i]);
}
ret = RCL_RET_INVALID_ROS_ARGS;
goto fail;
}
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
"Couldn't parse arg %d (%s) as remap rule. Not a '%s' or '%s' flag.", i,
argv[i], RCL_REMAP_FLAG, RCL_SHORT_REMAP_FLAG);

// Attempt to parse argument as parameter file rule
args_impl->parameter_files[args_impl->num_param_files_args] = NULL;
Expand Down
91 changes: 60 additions & 31 deletions rcl/test/rcl/test_arguments.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -145,37 +145,11 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), check_known_vs_unkno
EXPECT_TRUE(are_known_ros_args({"--ros-args", "-p", "/foo123:=/bar123"}));
EXPECT_TRUE(are_known_ros_args({"--ros-args", "__params:=file_name.yaml"}));

EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "--remap"}));

EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", ":="}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", "foo:="}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", ":=bar"}));

EXPECT_FALSE(are_known_ros_args({"--ros-args", "-p"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "--param"}));

EXPECT_FALSE(are_known_ros_args({"--ros-args", "-p", ":="}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-p", "foo:="}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-p", ":=bar"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", "__ns:="}));

EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", "__node:="}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", "__node:=/foo/bar"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", "__ns:=foo"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", ":__node:=nodename"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", "~:__node:=nodename"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", "}foo:=/bar"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", "f oo:=/bar"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", "foo:=/b ar"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", "f{oo:=/bar"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", "foo:=/b}ar"}));

EXPECT_FALSE(are_known_ros_args({"--ros-args", "-p", "}foo:=/bar"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-p", "f oo:=/bar"}));

EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", "rostopic://:=rosservice"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "-r", "rostopic::=rosservice"}));
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", "old_name:__node:=node_name"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "/foo/bar:=bar"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "foo:=/bar"}));
EXPECT_FALSE(are_known_ros_args({"--ros-args", "__param:=file_name.yaml"}));

// Setting logger level
Expand All @@ -194,6 +168,61 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), check_known_vs_unkno
EXPECT_FALSE(are_known_ros_args({"--ros-args", "__log_level:=foo"}));
}

bool
are_valid_ros_args(std::vector<const char *> argv)
ivanpauno marked this conversation as resolved.
Show resolved Hide resolved
{
const int argc = static_cast<int>(argv.size());
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
rcl_ret_t ret = rcl_parse_arguments(
argc, argv.data(), rcl_get_default_allocator(), &parsed_args);
if (RCL_RET_OK != ret) {
EXPECT_EQ(ret, RCL_RET_INVALID_ROS_ARGS) << rcl_get_error_string().str;
rcl_reset_error();
return false;
}
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
return true;
}

TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), check_valid_vs_invalid_args) {
EXPECT_TRUE(are_valid_ros_args({"--ros-args", "-p", "foo:=bar", "-r", "__node:=node_name"}));

// ROS args unknown to rcl are not (necessarily) invalid
EXPECT_TRUE(are_valid_ros_args({"--ros-args", "--custom-ros-arg"}));

EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r"}));
ivanpauno marked this conversation as resolved.
Show resolved Hide resolved
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "--remap"}));

EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", ":="}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", "foo:="}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", ":=bar"}));

EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-p"}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "--param"}));

EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-p", ":="}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-p", "foo:="}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-p", ":=bar"}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", "__ns:="}));

EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", "__node:="}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", "__node:=/foo/bar"}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", "__ns:=foo"}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", ":__node:=nodename"}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", "~:__node:=nodename"}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", "}foo:=/bar"}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", "f oo:=/bar"}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", "foo:=/b ar"}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", "f{oo:=/bar"}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", "foo:=/b}ar"}));

EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-p", "}foo:=/bar"}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-p", "f oo:=/bar"}));

EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", "rostopic://:=rosservice"}));
EXPECT_FALSE(are_valid_ros_args({"--ros-args", "-r", "rostopic::=rosservice"}));
}

TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_args) {
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
rcl_ret_t ret = rcl_parse_arguments(0, NULL, rcl_get_default_allocator(), &parsed_args);
Expand Down