From 12d3d80f815f35bbf0844f45f3b15a76f786081c Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Thu, 31 May 2018 14:50:38 +0200 Subject: [PATCH 01/18] wip --- rcl/include/rcl/arguments.h | 19 +++++++ rcl/include/rcl/types.h | 2 + rcl/src/rcl/arguments.c | 104 ++++++++++++++++++++++++++++++++++- rcl/src/rcl/arguments_impl.h | 6 ++ 4 files changed, 130 insertions(+), 1 deletion(-) diff --git a/rcl/include/rcl/arguments.h b/rcl/include/rcl/arguments.h index 7dd5e1588..1022c8577 100644 --- a/rcl/include/rcl/arguments.h +++ b/rcl/include/rcl/arguments.h @@ -20,6 +20,8 @@ #include "rcl/types.h" #include "rcl/visibility_control.h" +#include "rcutils/types.h" + #ifdef __cplusplus extern "C" { @@ -137,6 +139,23 @@ rcl_arguments_get_unparsed( rcl_allocator_t allocator, int ** output_unparsed_indices); + +RCL_PUBLIC +RCL_WARN_UNUSED +int +rcl_arguments_get_param_files_count( + const rcl_arguments_t * args); + + +RCL_PUBLIC +RCL_WARN_UNUSED +rcl_ret_t +rcl_arguments_get_param_files( + const rcl_arguments_t * arguments, + rcl_allocator_t allocator, + char ** parameter_files); + // rcutils_string_array_t * parameter_files); + /// Return a list of arguments with ROS-specific arguments removed. /** * Some arguments may not have been intended as ROS arguments. diff --git a/rcl/include/rcl/types.h b/rcl/include/rcl/types.h index f63622a27..e18d78b5e 100644 --- a/rcl/include/rcl/types.h +++ b/rcl/include/rcl/types.h @@ -92,5 +92,7 @@ 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 +/// Argument is not a valid remap rule +#define RCL_RET_INVALID_PARAM_RULE 1010 #endif // RCL__TYPES_H_ diff --git a/rcl/src/rcl/arguments.c b/rcl/src/rcl/arguments.c index 58224a545..bd6f889ba 100644 --- a/rcl/src/rcl/arguments.c +++ b/rcl/src/rcl/arguments.c @@ -51,6 +51,48 @@ _rcl_parse_remap_rule( rcl_allocator_t allocator, rcl_remap_t * output_rule); +RCL_LOCAL +rcl_ret_t +_rcl_parse_param_rule( + const char * arg, + rcl_allocator_t allocator, + char * output_rule); + +rcl_ret_t +rcl_arguments_get_param_files( + const rcl_arguments_t * arguments, + rcl_allocator_t allocator, + // char ** parameter_files) + rcutils_string_array_t * parameter_files) +{ + RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); + RCL_CHECK_ARGUMENT_FOR_NULL(arguments, RCL_RET_INVALID_ARGUMENT, allocator); + RCL_CHECK_ARGUMENT_FOR_NULL(arguments->impl, RCL_RET_INVALID_ARGUMENT, allocator); + RCL_CHECK_ARGUMENT_FOR_NULL(parameter_files, RCL_RET_INVALID_ARGUMENT, allocator); + rcutils_ret_t ret = rcutils_string_array_init( + parameter_files, arguments->impl->num_param_files_args, &allocator); + if (ret != RCUTILS_RET_OK) { + return RCL_RET_BAD_ALLOC; + } + for (int i = 0; i < arguments->impl->num_param_files_args; ++i) { + snprintf( + parameter_files->data[i], + strlen(arguments->impl->parameter_files[i]), + "%s", arguments->impl->parameter_files[i]); + } + return RCL_RET_OK; +} + +int +rcl_arguments_get_param_files_count( + const rcl_arguments_t * args) +{ + if (NULL == args || NULL == args->impl) { + return -1; + } + return args->impl->num_param_files_args; +} + rcl_ret_t rcl_parse_arguments( int argc, @@ -84,6 +126,8 @@ rcl_parse_arguments( args_impl->remap_rules = NULL; args_impl->unparsed_args = NULL; args_impl->num_unparsed_args = 0; + args_impl->parameter_files = NULL; + args_impl->num_param_files_args = 0; args_impl->allocator = allocator; if (argc == 0) { @@ -102,12 +146,39 @@ rcl_parse_arguments( ret = RCL_RET_BAD_ALLOC; goto fail; } + args_impl->parameter_files = allocator.allocate(sizeof(char *) * argc, allocator.state); + if (NULL == args_impl->parameter_files) { + ret = RCL_RET_BAD_ALLOC; + goto fail; + } + RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "coucou1"); // Attempt to parse arguments as remap rules for (int i = 0; i < argc; ++i) { + RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "coucou2 : %d", i); rcl_remap_t * rule = &(args_impl->remap_rules[args_impl->num_remap_rules]); *rule = rcl_remap_get_zero_initialized(); - if (RCL_RET_OK == _rcl_parse_remap_rule(argv[i], allocator, rule)) { + args_impl->parameter_files[args_impl->num_param_files_args] = allocator.allocate(sizeof(char) * (strlen(argv[i]) + 1), allocator.state); + if (NULL == args_impl->parameter_files[args_impl->num_param_files_args]) { + ret = RCL_RET_BAD_ALLOC; + goto fail; + } + // char * foobar = allocator.allocate(sizeof(char) * (strlen(argv[i]) + 1), allocator.state); + if ( + RCL_RET_OK == _rcl_parse_param_rule( + argv[i], allocator, args_impl->parameter_files[args_impl->num_param_files_args]) + // RCL_RET_OK == _rcl_parse_param_rule( + // argv[i], allocator, foobar) + ) { + ++(args_impl->num_param_files_args); + RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, + "params rule : %s\n total num param rules %d", + args_impl->parameter_files[args_impl->num_param_files_args], + // args_impl->parameter_files[args_impl->num_param_files_args], + // foobar, + args_impl->num_param_files_args) + } else if (RCL_RET_OK == _rcl_parse_remap_rule(argv[i], allocator, rule)) { + RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "remap rule") ++(args_impl->num_remap_rules); } else { RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "arg %d (%s) error '%s'", i, argv[i], @@ -117,6 +188,7 @@ rcl_parse_arguments( ++(args_impl->num_unparsed_args); } } + RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "coucou3"); // Shrink remap_rules array to match number of successfully parsed rules if (args_impl->num_remap_rules > 0) { @@ -857,6 +929,36 @@ _rcl_parse_remap_rule( return ret; } +rcl_ret_t +_rcl_parse_param_rule( + const char * arg, + rcl_allocator_t allocator, + char * output_rule) +{ + RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "enter param parsing"); + RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT, allocator); + // RCL_CHECK_ARGUMENT_FOR_NULL(output_rule, RCL_RET_INVALID_ARGUMENT, allocator); + + const char * param_prefix = "__params:="; + size_t param_prefix_len = strlen(param_prefix); + RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "looking for '%s' in '%s'", param_prefix, arg); + if (strncmp(param_prefix, arg, param_prefix_len) == 0) { + RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Found '%s' in '%s'", param_prefix, arg); + size_t outlen = strlen(arg) - param_prefix_len; + // output_rule = allocator.allocate(sizeof(char) * (outlen + 1), allocator.state); + if (NULL == output_rule) { + return RCL_RET_BAD_ALLOC; + } + snprintf(output_rule, outlen + 1, "%s", arg + strlen("__params:=")); + // memcpy(&output_rule, arg + param_prefix_len, outlen); + RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Stripped param string: '%s'", output_rule); + return RCL_RET_OK; + } else{ + RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Couldn't find '%s' in '%s'", param_prefix, arg); + } + return RCL_RET_INVALID_PARAM_RULE; +} + #ifdef __cplusplus } #endif diff --git a/rcl/src/rcl/arguments_impl.h b/rcl/src/rcl/arguments_impl.h index a689c2c11..d2a0e4274 100644 --- a/rcl/src/rcl/arguments_impl.h +++ b/rcl/src/rcl/arguments_impl.h @@ -31,6 +31,12 @@ typedef struct rcl_arguments_impl_t /// Length of unparsed_args. int num_unparsed_args; + // TODO(mikaelarguedas) consider storing CLI parameter rules here + /// Array of yaml parameter file paths + char ** parameter_files; + /// Length of parameter_files. + int num_param_files_args; + /// Array of rules for name remapping. rcl_remap_t * remap_rules; /// Length of remap_rules. From eb7026875a5d0b06368e9d1d91f434098edec490 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 1 Jun 2018 09:31:40 -0700 Subject: [PATCH 02/18] rcl_arguments_get_param_files() with char ** Restore version of function that outputs a char ** --- rcl/include/rcl/arguments.h | 23 +++++++++++++++++++++-- rcl/src/rcl/arguments.c | 11 +++++------ 2 files changed, 26 insertions(+), 8 deletions(-) diff --git a/rcl/include/rcl/arguments.h b/rcl/include/rcl/arguments.h index 1022c8577..168bbf5ce 100644 --- a/rcl/include/rcl/arguments.h +++ b/rcl/include/rcl/arguments.h @@ -147,14 +147,33 @@ rcl_arguments_get_param_files_count( const rcl_arguments_t * args); +/// Return a list of yaml parameter file paths specified on the command line. +/** + *
+ * Attribute | Adherence + * ------------------ | ------------- + * Allocates Memory | Yes + * Thread-Safe | No + * Uses Atomics | No + * Lock-Free | Yes + * + * \param[in] arguments An arguments structure that has been parsed. + * \param[in] allocator A valid allocator. + * \param[out] parameter_files An allocated array of paramter file names. + * This array must be deallocated by the caller using the given allocator. + * The output is NULL if there were no paramter files. + * \return `RCL_RET_OK` if everything goes correctly, 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. + */ RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_arguments_get_param_files( const rcl_arguments_t * arguments, rcl_allocator_t allocator, - char ** parameter_files); - // rcutils_string_array_t * parameter_files); + char *** parameter_files); /// Return a list of arguments with ROS-specific arguments removed. /** diff --git a/rcl/src/rcl/arguments.c b/rcl/src/rcl/arguments.c index bd6f889ba..7e90cfd12 100644 --- a/rcl/src/rcl/arguments.c +++ b/rcl/src/rcl/arguments.c @@ -62,21 +62,20 @@ rcl_ret_t rcl_arguments_get_param_files( const rcl_arguments_t * arguments, rcl_allocator_t allocator, - // char ** parameter_files) - rcutils_string_array_t * parameter_files) + char *** parameter_files) { RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(arguments, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(arguments->impl, RCL_RET_INVALID_ARGUMENT, allocator); RCL_CHECK_ARGUMENT_FOR_NULL(parameter_files, RCL_RET_INVALID_ARGUMENT, allocator); - rcutils_ret_t ret = rcutils_string_array_init( - parameter_files, arguments->impl->num_param_files_args, &allocator); - if (ret != RCUTILS_RET_OK) { + *(parameter_files) = allocator.allocate( + sizeof(char *) * arguments->impl->num_param_files_args, allocator.state); + if (NULL == *parameter_files) { return RCL_RET_BAD_ALLOC; } for (int i = 0; i < arguments->impl->num_param_files_args; ++i) { snprintf( - parameter_files->data[i], + (*parameter_files)[i], strlen(arguments->impl->parameter_files[i]), "%s", arguments->impl->parameter_files[i]); } From 80cb01676f887f1750617dd382f20a1f822db31c Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 1 Jun 2018 10:12:19 -0700 Subject: [PATCH 03/18] _rcl_parse_param_rule() allocates string Before this commit `rcl_parse_params` was allocating space the size of the argument, but the space only needs to be as big as the argument minus the prefix length. --- rcl/src/rcl/arguments.c | 27 ++++++--------------------- 1 file changed, 6 insertions(+), 21 deletions(-) diff --git a/rcl/src/rcl/arguments.c b/rcl/src/rcl/arguments.c index 7e90cfd12..8304a6750 100644 --- a/rcl/src/rcl/arguments.c +++ b/rcl/src/rcl/arguments.c @@ -56,7 +56,7 @@ rcl_ret_t _rcl_parse_param_rule( const char * arg, rcl_allocator_t allocator, - char * output_rule); + char ** output_rule); rcl_ret_t rcl_arguments_get_param_files( @@ -157,17 +157,10 @@ rcl_parse_arguments( RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "coucou2 : %d", i); rcl_remap_t * rule = &(args_impl->remap_rules[args_impl->num_remap_rules]); *rule = rcl_remap_get_zero_initialized(); - args_impl->parameter_files[args_impl->num_param_files_args] = allocator.allocate(sizeof(char) * (strlen(argv[i]) + 1), allocator.state); - if (NULL == args_impl->parameter_files[args_impl->num_param_files_args]) { - ret = RCL_RET_BAD_ALLOC; - goto fail; - } - // char * foobar = allocator.allocate(sizeof(char) * (strlen(argv[i]) + 1), allocator.state); + args_impl->parameter_files[args_impl->num_param_files_args] = NULL; if ( RCL_RET_OK == _rcl_parse_param_rule( - argv[i], allocator, args_impl->parameter_files[args_impl->num_param_files_args]) - // RCL_RET_OK == _rcl_parse_param_rule( - // argv[i], allocator, foobar) + argv[i], allocator, &(args_impl->parameter_files[args_impl->num_param_files_args])) ) { ++(args_impl->num_param_files_args); RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, @@ -932,28 +925,20 @@ rcl_ret_t _rcl_parse_param_rule( const char * arg, rcl_allocator_t allocator, - char * output_rule) + char ** output_rule) { - RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "enter param parsing"); RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT, allocator); - // RCL_CHECK_ARGUMENT_FOR_NULL(output_rule, RCL_RET_INVALID_ARGUMENT, allocator); const char * param_prefix = "__params:="; size_t param_prefix_len = strlen(param_prefix); - RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "looking for '%s' in '%s'", param_prefix, arg); if (strncmp(param_prefix, arg, param_prefix_len) == 0) { - RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Found '%s' in '%s'", param_prefix, arg); size_t outlen = strlen(arg) - param_prefix_len; - // output_rule = allocator.allocate(sizeof(char) * (outlen + 1), allocator.state); + *output_rule = allocator.allocate(sizeof(char) * (outlen + 1), allocator.state); if (NULL == output_rule) { return RCL_RET_BAD_ALLOC; } - snprintf(output_rule, outlen + 1, "%s", arg + strlen("__params:=")); - // memcpy(&output_rule, arg + param_prefix_len, outlen); - RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Stripped param string: '%s'", output_rule); + snprintf(*output_rule, outlen + 1, "%s", arg + param_prefix_len); return RCL_RET_OK; - } else{ - RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Couldn't find '%s' in '%s'", param_prefix, arg); } return RCL_RET_INVALID_PARAM_RULE; } From 5015711cd7df05b73549ae6a3b857e5c24942d10 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 1 Jun 2018 10:15:37 -0700 Subject: [PATCH 04/18] Debug print before incrementing num files --- rcl/src/rcl/arguments.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rcl/src/rcl/arguments.c b/rcl/src/rcl/arguments.c index 8304a6750..4dfb0eddf 100644 --- a/rcl/src/rcl/arguments.c +++ b/rcl/src/rcl/arguments.c @@ -162,13 +162,13 @@ rcl_parse_arguments( RCL_RET_OK == _rcl_parse_param_rule( argv[i], allocator, &(args_impl->parameter_files[args_impl->num_param_files_args])) ) { - ++(args_impl->num_param_files_args); RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "params rule : %s\n total num param rules %d", args_impl->parameter_files[args_impl->num_param_files_args], // args_impl->parameter_files[args_impl->num_param_files_args], // foobar, args_impl->num_param_files_args) + ++(args_impl->num_param_files_args); } else if (RCL_RET_OK == _rcl_parse_remap_rule(argv[i], allocator, rule)) { RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "remap rule") ++(args_impl->num_remap_rules); From 1ee2846084f8a2c1066eb0f820445a5f3b279735 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 1 Jun 2018 12:11:17 -0700 Subject: [PATCH 05/18] Alloc and make sure to dealloc on failure --- rcl/src/rcl/arguments.c | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/rcl/src/rcl/arguments.c b/rcl/src/rcl/arguments.c index 4dfb0eddf..cc218efbf 100644 --- a/rcl/src/rcl/arguments.c +++ b/rcl/src/rcl/arguments.c @@ -74,10 +74,16 @@ rcl_arguments_get_param_files( return RCL_RET_BAD_ALLOC; } for (int i = 0; i < arguments->impl->num_param_files_args; ++i) { - snprintf( - (*parameter_files)[i], - strlen(arguments->impl->parameter_files[i]), - "%s", arguments->impl->parameter_files[i]); + (*parameter_files)[i] = rcutils_strdup(arguments->impl->parameter_files[i], allocator); + if (NULL == *parameter_files) { + // deallocate allocated memory + for (int r = i; r >= 0; --r) { + allocator.deallocate((*parameter_files[i]), allocator.state); + } + allocator.deallocate((*parameter_files), allocator.state); + (*parameter_files) = NULL; + return RCL_RET_BAD_ALLOC; + } } return RCL_RET_OK; } From 7538cfde88f984e55308624df72080f3afb8b214 Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Mon, 4 Jun 2018 21:35:40 +0200 Subject: [PATCH 06/18] fix print of parsed parameter rule --- rcl/src/rcl/arguments.c | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/rcl/src/rcl/arguments.c b/rcl/src/rcl/arguments.c index cc218efbf..b7c88fadd 100644 --- a/rcl/src/rcl/arguments.c +++ b/rcl/src/rcl/arguments.c @@ -168,13 +168,11 @@ rcl_parse_arguments( RCL_RET_OK == _rcl_parse_param_rule( argv[i], allocator, &(args_impl->parameter_files[args_impl->num_param_files_args])) ) { + ++(args_impl->num_param_files_args); RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "params rule : %s\n total num param rules %d", - args_impl->parameter_files[args_impl->num_param_files_args], - // args_impl->parameter_files[args_impl->num_param_files_args], - // foobar, + args_impl->parameter_files[args_impl->num_param_files_args - 1], args_impl->num_param_files_args) - ++(args_impl->num_param_files_args); } else if (RCL_RET_OK == _rcl_parse_remap_rule(argv[i], allocator, rule)) { RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "remap rule") ++(args_impl->num_remap_rules); From 9afdf2982982f84faf464a14c74658ead2ffa7cf Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Mon, 4 Jun 2018 21:36:53 +0200 Subject: [PATCH 07/18] rcutils types not needed as we dont use rcutils_string_array anymore --- rcl/include/rcl/arguments.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/rcl/include/rcl/arguments.h b/rcl/include/rcl/arguments.h index 168bbf5ce..9b89e806c 100644 --- a/rcl/include/rcl/arguments.h +++ b/rcl/include/rcl/arguments.h @@ -20,8 +20,6 @@ #include "rcl/types.h" #include "rcl/visibility_control.h" -#include "rcutils/types.h" - #ifdef __cplusplus extern "C" { From 06f6d94371ee86cbeb3cb8596e01d66e5a6630ae Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Mon, 4 Jun 2018 23:52:40 +0200 Subject: [PATCH 08/18] minimal test --- rcl/test/rcl/test_arguments.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/rcl/test/rcl/test_arguments.cpp b/rcl/test/rcl/test_arguments.cpp index f4b9b2f5a..6401cc8ae 100644 --- a/rcl/test/rcl/test_arguments.cpp +++ b/rcl/test/rcl/test_arguments.cpp @@ -100,6 +100,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), check_valid_vs_inval EXPECT_TRUE(is_valid_arg("rostopic://rostopic:=rosservice")); EXPECT_TRUE(is_valid_arg("rostopic:///rosservice:=rostopic")); EXPECT_TRUE(is_valid_arg("rostopic:///foo/bar:=baz")); + EXPECT_TRUE(is_valid_arg("__params:=node_name")); EXPECT_FALSE(is_valid_arg(":=")); EXPECT_FALSE(is_valid_arg("foo:=")); @@ -117,6 +118,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), check_valid_vs_inval EXPECT_FALSE(is_valid_arg("foo:=/b}ar")); EXPECT_FALSE(is_valid_arg("rostopic://:=rosservice")); EXPECT_FALSE(is_valid_arg("rostopic::=rosservice")); + EXPECT_FALSE(is_valid_arg("__param:=node_name")); } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_args) { From 82d07df8c651ee4c750a1e600a7d43cd23c08c0a Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Tue, 5 Jun 2018 13:40:51 +0200 Subject: [PATCH 09/18] cleanup debug prints --- rcl/include/rcl/types.h | 2 +- rcl/src/rcl/arguments.c | 6 +----- 2 files changed, 2 insertions(+), 6 deletions(-) diff --git a/rcl/include/rcl/types.h b/rcl/include/rcl/types.h index e18d78b5e..725161b69 100644 --- a/rcl/include/rcl/types.h +++ b/rcl/include/rcl/types.h @@ -92,7 +92,7 @@ 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 -/// Argument is not a valid remap rule +/// Argument is not a valid parameter rule #define RCL_RET_INVALID_PARAM_RULE 1010 #endif // RCL__TYPES_H_ diff --git a/rcl/src/rcl/arguments.c b/rcl/src/rcl/arguments.c index b7c88fadd..da3bfd599 100644 --- a/rcl/src/rcl/arguments.c +++ b/rcl/src/rcl/arguments.c @@ -157,10 +157,8 @@ rcl_parse_arguments( goto fail; } - RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "coucou1"); // Attempt to parse arguments as remap rules for (int i = 0; i < argc; ++i) { - RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "coucou2 : %d", i); rcl_remap_t * rule = &(args_impl->remap_rules[args_impl->num_remap_rules]); *rule = rcl_remap_get_zero_initialized(); args_impl->parameter_files[args_impl->num_param_files_args] = NULL; @@ -169,12 +167,11 @@ rcl_parse_arguments( argv[i], allocator, &(args_impl->parameter_files[args_impl->num_param_files_args])) ) { ++(args_impl->num_param_files_args); - RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, + 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) } else if (RCL_RET_OK == _rcl_parse_remap_rule(argv[i], allocator, rule)) { - RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "remap rule") ++(args_impl->num_remap_rules); } else { RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "arg %d (%s) error '%s'", i, argv[i], @@ -184,7 +181,6 @@ rcl_parse_arguments( ++(args_impl->num_unparsed_args); } } - RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "coucou3"); // Shrink remap_rules array to match number of successfully parsed rules if (args_impl->num_remap_rules > 0) { From 72a28741605e6ffea8fb2d5aaed2e8c513c34088 Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Tue, 5 Jun 2018 13:45:47 +0200 Subject: [PATCH 10/18] linter fixup --- rcl/src/rcl/arguments.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rcl/src/rcl/arguments.c b/rcl/src/rcl/arguments.c index da3bfd599..0bb611f4a 100644 --- a/rcl/src/rcl/arguments.c +++ b/rcl/src/rcl/arguments.c @@ -164,8 +164,8 @@ rcl_parse_arguments( args_impl->parameter_files[args_impl->num_param_files_args] = NULL; if ( RCL_RET_OK == _rcl_parse_param_rule( - argv[i], allocator, &(args_impl->parameter_files[args_impl->num_param_files_args])) - ) { + argv[i], allocator, &(args_impl->parameter_files[args_impl->num_param_files_args]))) + { ++(args_impl->num_param_files_args); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "params rule : %s\n total num param rules %d", From 6073307d9768ab01486d4df46283fb81bfe5d091 Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Tue, 5 Jun 2018 14:12:43 +0200 Subject: [PATCH 11/18] add tests for param arguments --- rcl/test/rcl/test_arguments.cpp | 56 +++++++++++++++++++++++++++++++++ 1 file changed, 56 insertions(+) diff --git a/rcl/test/rcl/test_arguments.cpp b/rcl/test/rcl/test_arguments.cpp index 6401cc8ae..6f91096b8 100644 --- a/rcl/test/rcl/test_arguments.cpp +++ b/rcl/test/rcl/test_arguments.cpp @@ -301,3 +301,59 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remove_ros_args alloc.deallocate(nonros_argv, alloc.state); } } + +TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_zero) { + const char * argv[] = {"process_name", "__ns:=/namespace", "random:=arg"}; + 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_OK, ret) << rcl_get_error_string_safe(); + + int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args); + EXPECT_EQ(0, parameter_filecount); +} + +TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_single) { + const char * argv[] = {"process_name", "__ns:=/namespace", "random:=arg", "__params:=parameter_filepath"}; + 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_OK, ret) << rcl_get_error_string_safe(); + + int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args); + EXPECT_EQ(1, parameter_filecount); + char ** parameter_files = NULL; + ret = rcl_arguments_get_param_files(&parsed_args, alloc, ¶meter_files); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + EXPECT_STREQ("parameter_filepath", parameter_files[0]); +} + +TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_multiple) { + const char * argv[] = { + "process_name", "__params:=parameter_filepath1", "__ns:=/namespace", + "random:=arg", "__params:=parameter_filepath2"}; + 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_OK, ret) << rcl_get_error_string_safe(); + + int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args); + EXPECT_EQ(2, parameter_filecount); + char ** parameter_files = NULL; + ret = rcl_arguments_get_param_files(&parsed_args, alloc, ¶meter_files); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); + EXPECT_STREQ("parameter_filepath1", parameter_files[0]); + EXPECT_STREQ("parameter_filepath2", parameter_files[1]); +} From 4592e3e2806b2ffe8119962d82b26756d234a2f8 Mon Sep 17 00:00:00 2001 From: Mikael Arguedas Date: Tue, 5 Jun 2018 15:07:12 +0200 Subject: [PATCH 12/18] lint tests --- rcl/test/rcl/test_arguments.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/rcl/test/rcl/test_arguments.cpp b/rcl/test/rcl/test_arguments.cpp index 6f91096b8..7d36673f4 100644 --- a/rcl/test/rcl/test_arguments.cpp +++ b/rcl/test/rcl/test_arguments.cpp @@ -318,7 +318,9 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_ } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_single) { - const char * argv[] = {"process_name", "__ns:=/namespace", "random:=arg", "__params:=parameter_filepath"}; + const char * argv[] = { + "process_name", "__ns:=/namespace", "random:=arg", "__params:=parameter_filepath" + }; int argc = sizeof(argv) / sizeof(const char *); rcl_ret_t ret; @@ -339,7 +341,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_multiple) { const char * argv[] = { "process_name", "__params:=parameter_filepath1", "__ns:=/namespace", - "random:=arg", "__params:=parameter_filepath2"}; + "random:=arg", "__params:=parameter_filepath2" + }; int argc = sizeof(argv) / sizeof(const char *); rcl_ret_t ret; From dcd58b26448c208de27747014b8093883b3a0d3d Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 5 Jun 2018 09:28:54 -0700 Subject: [PATCH 13/18] Doc for rcl_arguments_get_param_files_count() --- rcl/include/rcl/arguments.h | 15 ++++++++++++++- 1 file changed, 14 insertions(+), 1 deletion(-) diff --git a/rcl/include/rcl/arguments.h b/rcl/include/rcl/arguments.h index 9b89e806c..64f310e3b 100644 --- a/rcl/include/rcl/arguments.h +++ b/rcl/include/rcl/arguments.h @@ -137,7 +137,20 @@ rcl_arguments_get_unparsed( rcl_allocator_t allocator, int ** output_unparsed_indices); - +/// Return the number of parameter yaml files given in the arguments. +/** + *
+ * Attribute | Adherence + * ------------------ | ------------- + * Allocates Memory | No + * Thread-Safe | No + * Uses Atomics | No + * Lock-Free | Yes + * + * \param[in] args An arguments structure that has been parsed. + * \return number of yaml files, or + * \return -1 if args is `NULL` or zero initialized. + */ RCL_PUBLIC RCL_WARN_UNUSED int From 8e5d553c2ae95ebc9bb48eff02df5674b5a9a80b Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 5 Jun 2018 09:36:02 -0700 Subject: [PATCH 14/18] Shrink parameter files --- rcl/src/rcl/arguments.c | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/rcl/src/rcl/arguments.c b/rcl/src/rcl/arguments.c index 0bb611f4a..18a4eaf5c 100644 --- a/rcl/src/rcl/arguments.c +++ b/rcl/src/rcl/arguments.c @@ -195,6 +195,18 @@ rcl_parse_arguments( allocator.deallocate(args_impl->remap_rules, allocator.state); args_impl->remap_rules = NULL; } + // Shrink Parameter files + if (0 == args_impl->num_param_files_args) { + allocator.deallocate(args_impl->parameter_files, allocator.state); + args_impl->parameter_files = NULL; + } else if (args_impl->num_param_files_args < argc) { + args_impl->parameter_files = rcutils_reallocf( + args_impl->parameter_files, sizeof(char *) * args_impl->num_param_files_args, &allocator); + if (NULL == args_impl->parameter_files) { + ret = RCL_RET_BAD_ALLOC; + goto fail; + } + } // Shrink unparsed_args if (0 == args_impl->num_unparsed_args) { // No unparsed args From 449ccb95cee04b08265aa98ad674f6b6f9098f2d Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 5 Jun 2018 09:38:45 -0700 Subject: [PATCH 15/18] const param_prefix_len --- rcl/src/rcl/arguments.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rcl/src/rcl/arguments.c b/rcl/src/rcl/arguments.c index 18a4eaf5c..51abdd2b8 100644 --- a/rcl/src/rcl/arguments.c +++ b/rcl/src/rcl/arguments.c @@ -942,7 +942,7 @@ _rcl_parse_param_rule( RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT, allocator); const char * param_prefix = "__params:="; - size_t param_prefix_len = strlen(param_prefix); + const size_t param_prefix_len = strlen(param_prefix); if (strncmp(param_prefix, arg, param_prefix_len) == 0) { size_t outlen = strlen(arg) - param_prefix_len; *output_rule = allocator.allocate(sizeof(char) * (outlen + 1), allocator.state); From dd0f088f0171af9bd1cf452123d393ac6056daea Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 5 Jun 2018 10:20:40 -0700 Subject: [PATCH 16/18] Copy parameter file names --- rcl/src/rcl/arguments.c | 25 +++++++++++++++++++++++++ 1 file changed, 25 insertions(+) diff --git a/rcl/src/rcl/arguments.c b/rcl/src/rcl/arguments.c index 51abdd2b8..7d55f493a 100644 --- a/rcl/src/rcl/arguments.c +++ b/rcl/src/rcl/arguments.c @@ -346,6 +346,7 @@ rcl_arguments_copy( // Zero so it's safe to call rcl_arguments_fini() if an error occurrs while copying. args_out->impl->num_remap_rules = 0; args_out->impl->num_unparsed_args = 0; + args_out->impl->num_param_files_args = 0; // Copy unparsed args args_out->impl->unparsed_args = allocator.allocate( @@ -382,6 +383,30 @@ rcl_arguments_copy( return ret; } } + // Copy parameter files + if (args->impl->num_param_files_args) { + args_out->impl->parameter_files = allocator.allocate( + sizeof(char *) * args->impl->num_param_files_args, allocator.state); + if (NULL == args_out->impl->parameter_files) { + if (RCL_RET_OK != rcl_arguments_fini(args_out)) { + RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error", error_alloc); + } + return RCL_RET_BAD_ALLOC; + } + args_out->impl->num_param_files_args = args->impl->num_param_files_args; + for (int i = 0; i < args->impl->num_param_files_args; ++i) { + args_out->impl->parameter_files[i] = + rcutils_strdup(args->impl->parameter_files[i], allocator); + if (NULL == args_out->impl->parameter_files[i]) { + if (RCL_RET_OK != rcl_arguments_fini(args_out)) { + RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error", error_alloc); + } + return RCL_RET_BAD_ALLOC; + } + } + } else { + args_out->impl->parameter_files = NULL; + } return RCL_RET_OK; } From e90eddedab5a961a45f1ca556da54f517e2f564b Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 5 Jun 2018 10:21:07 -0700 Subject: [PATCH 17/18] deallocate parameter files in fini --- rcl/src/rcl/arguments.c | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/rcl/src/rcl/arguments.c b/rcl/src/rcl/arguments.c index 7d55f493a..f16994d17 100644 --- a/rcl/src/rcl/arguments.c +++ b/rcl/src/rcl/arguments.c @@ -438,6 +438,16 @@ rcl_arguments_fini( args->impl->num_unparsed_args = 0; args->impl->unparsed_args = NULL; + if (args->impl->parameter_files) { + for (int p = 0; p < args->impl->num_param_files_args; ++p) { + args->impl->allocator.deallocate( + args->impl->parameter_files[p], args->impl->allocator.state); + } + args->impl->allocator.deallocate(args->impl->parameter_files, args->impl->allocator.state); + args->impl->num_param_files_args = 0; + args->impl->parameter_files = NULL; + } + args->impl->allocator.deallocate(args->impl, args->impl->allocator.state); args->impl = NULL; return ret; From 18a6ef780bab325915ba522df401d855e88489c0 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 5 Jun 2018 10:21:23 -0700 Subject: [PATCH 18/18] free memory after tests pass --- rcl/test/rcl/test_arguments.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/rcl/test/rcl/test_arguments.cpp b/rcl/test/rcl/test_arguments.cpp index 7d36673f4..bd28342b2 100644 --- a/rcl/test/rcl/test_arguments.cpp +++ b/rcl/test/rcl/test_arguments.cpp @@ -315,6 +315,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_ int parameter_filecount = rcl_arguments_get_param_files_count(&parsed_args); 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) { @@ -336,6 +337,12 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_ ret = rcl_arguments_get_param_files(&parsed_args, alloc, ¶meter_files); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_STREQ("parameter_filepath", parameter_files[0]); + + for (int i = 0; i < parameter_filecount; ++i) { + alloc.deallocate(parameter_files[i], alloc.state); + } + alloc.deallocate(parameter_files, alloc.state); + EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_multiple) { @@ -359,4 +366,9 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_ ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe(); EXPECT_STREQ("parameter_filepath1", parameter_files[0]); EXPECT_STREQ("parameter_filepath2", parameter_files[1]); + for (int i = 0; i < parameter_filecount; ++i) { + alloc.deallocate(parameter_files[i], alloc.state); + } + alloc.deallocate(parameter_files, alloc.state); + EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); }