Migrate to '--ros-args ... [--]'-based ROS args extraction (#477)
* Migrate to '--ros-args ... [--]'-based ROS args extraction Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Extend rcl arguments API to retrieve unparsed ROS args. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Adapt rcl arguments tests. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Complete unparsed ROS args functionality. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Address peer review comments. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Extend rcl arguments test coverage. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Adapt more rcl tests to use --ros-args. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Address peer review comments. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Ignore duplicate --ros-args flags. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
This commit is contained in:
parent
6f20cd9480
commit
41792cb6e8
6 changed files with 553 additions and 197 deletions
|
@ -34,6 +34,9 @@ typedef struct rcl_arguments_t
|
||||||
struct rcl_arguments_impl_t * impl;
|
struct rcl_arguments_impl_t * impl;
|
||||||
} rcl_arguments_t;
|
} rcl_arguments_t;
|
||||||
|
|
||||||
|
#define RCL_ROS_ARGS_FLAG "--ros-args"
|
||||||
|
#define RCL_ROS_ARGS_EXPLICIT_END_TOKEN "--"
|
||||||
|
|
||||||
#define RCL_LOG_LEVEL_ARG_RULE "__log_level:="
|
#define RCL_LOG_LEVEL_ARG_RULE "__log_level:="
|
||||||
#define RCL_EXTERNAL_LOG_CONFIG_ARG_RULE "__log_config_file:="
|
#define RCL_EXTERNAL_LOG_CONFIG_ARG_RULE "__log_config_file:="
|
||||||
#define RCL_LOG_DISABLE_STDOUT_ARG_RULE "__log_disable_stdout:="
|
#define RCL_LOG_DISABLE_STDOUT_ARG_RULE "__log_disable_stdout:="
|
||||||
|
@ -97,7 +100,7 @@ rcl_parse_arguments(
|
||||||
rcl_allocator_t allocator,
|
rcl_allocator_t allocator,
|
||||||
rcl_arguments_t * args_output);
|
rcl_arguments_t * args_output);
|
||||||
|
|
||||||
/// Return the number of arguments that were not successfully parsed.
|
/// Return the number of arguments that were not ROS specific arguments.
|
||||||
/**
|
/**
|
||||||
* <hr>
|
* <hr>
|
||||||
* Attribute | Adherence
|
* Attribute | Adherence
|
||||||
|
@ -117,10 +120,10 @@ int
|
||||||
rcl_arguments_get_count_unparsed(
|
rcl_arguments_get_count_unparsed(
|
||||||
const rcl_arguments_t * args);
|
const rcl_arguments_t * args);
|
||||||
|
|
||||||
/// Return a list of indexes that weren't successfully parsed.
|
/// Return a list of indices to non ROS specific arguments.
|
||||||
/**
|
/**
|
||||||
* Some arguments may not have been successfully parsed, or were not intended as ROS arguments.
|
* Non ROS specific arguments may have been provided i.e. arguments outside a '--ros-args' scope.
|
||||||
* This function populates an array of indexes to these arguments in the original argv array.
|
* This function populates an array of indices to these arguments in the original argv array.
|
||||||
* Since the first argument is always assumed to be a process name, the list will always contain
|
* Since the first argument is always assumed to be a process name, the list will always contain
|
||||||
* the index 0.
|
* the index 0.
|
||||||
*
|
*
|
||||||
|
@ -150,6 +153,58 @@ rcl_arguments_get_unparsed(
|
||||||
rcl_allocator_t allocator,
|
rcl_allocator_t allocator,
|
||||||
int ** output_unparsed_indices);
|
int ** output_unparsed_indices);
|
||||||
|
|
||||||
|
/// Return the number of ROS specific arguments that were not successfully parsed.
|
||||||
|
/**
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] args An arguments structure that has been parsed.
|
||||||
|
* \return number of unparsed ROS specific arguments, or
|
||||||
|
* \return -1 if args is `NULL` or zero initialized.
|
||||||
|
*/
|
||||||
|
RCL_PUBLIC
|
||||||
|
RCL_WARN_UNUSED
|
||||||
|
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.
|
||||||
|
/**
|
||||||
|
* Some ROS specific arguments may not have been successfully parsed, or were not intended to be
|
||||||
|
* parsed by rcl.
|
||||||
|
* This function populates an array of indices to these arguments in the original argv array.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
|
* \param[in] args An arguments structure that has been parsed.
|
||||||
|
* \param[in] allocator A valid allocator.
|
||||||
|
* \param[out] output_unparsed_indices An allocated array of indices into the original argv array.
|
||||||
|
* This array must be deallocated by the caller using the given allocator.
|
||||||
|
* If there are no unparsed ROS specific arguments then the output will be set to NULL.
|
||||||
|
* \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_unparsed_ros(
|
||||||
|
const rcl_arguments_t * args,
|
||||||
|
rcl_allocator_t allocator,
|
||||||
|
int ** output_unparsed_ros_indices);
|
||||||
|
|
||||||
/// Return the number of parameter yaml files given in the arguments.
|
/// Return the number of parameter yaml files given in the arguments.
|
||||||
/**
|
/**
|
||||||
* <hr>
|
* <hr>
|
||||||
|
|
|
@ -217,6 +217,8 @@ rcl_parse_arguments(
|
||||||
args_impl->external_log_config_file = NULL;
|
args_impl->external_log_config_file = NULL;
|
||||||
args_impl->unparsed_args = NULL;
|
args_impl->unparsed_args = NULL;
|
||||||
args_impl->num_unparsed_args = 0;
|
args_impl->num_unparsed_args = 0;
|
||||||
|
args_impl->unparsed_ros_args = NULL;
|
||||||
|
args_impl->num_unparsed_ros_args = 0;
|
||||||
args_impl->parameter_files = NULL;
|
args_impl->parameter_files = NULL;
|
||||||
args_impl->num_param_files_args = 0;
|
args_impl->num_param_files_args = 0;
|
||||||
args_impl->log_stdout_disabled = false;
|
args_impl->log_stdout_disabled = false;
|
||||||
|
@ -235,107 +237,135 @@ rcl_parse_arguments(
|
||||||
ret = RCL_RET_BAD_ALLOC;
|
ret = RCL_RET_BAD_ALLOC;
|
||||||
goto fail;
|
goto fail;
|
||||||
}
|
}
|
||||||
args_impl->unparsed_args = allocator.allocate(sizeof(int) * argc, allocator.state);
|
|
||||||
if (NULL == args_impl->unparsed_args) {
|
|
||||||
ret = RCL_RET_BAD_ALLOC;
|
|
||||||
goto fail;
|
|
||||||
}
|
|
||||||
args_impl->parameter_files = allocator.allocate(sizeof(char *) * argc, allocator.state);
|
args_impl->parameter_files = allocator.allocate(sizeof(char *) * argc, allocator.state);
|
||||||
if (NULL == args_impl->parameter_files) {
|
if (NULL == args_impl->parameter_files) {
|
||||||
ret = RCL_RET_BAD_ALLOC;
|
ret = RCL_RET_BAD_ALLOC;
|
||||||
goto fail;
|
goto fail;
|
||||||
}
|
}
|
||||||
|
args_impl->unparsed_ros_args = allocator.allocate(sizeof(int) * argc, allocator.state);
|
||||||
|
if (NULL == args_impl->unparsed_ros_args) {
|
||||||
|
ret = RCL_RET_BAD_ALLOC;
|
||||||
|
goto fail;
|
||||||
|
}
|
||||||
|
args_impl->unparsed_args = allocator.allocate(sizeof(int) * argc, allocator.state);
|
||||||
|
if (NULL == args_impl->unparsed_args) {
|
||||||
|
ret = RCL_RET_BAD_ALLOC;
|
||||||
|
goto fail;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool parsing_ros_args = false;
|
||||||
for (int i = 0; i < argc; ++i) {
|
for (int i = 0; i < argc; ++i) {
|
||||||
// Attempt to parse argument as parameter file rule
|
if (parsing_ros_args) {
|
||||||
args_impl->parameter_files[args_impl->num_param_files_args] = NULL;
|
// Ignore ROS specific arguments flags
|
||||||
if (
|
if (strcmp(RCL_ROS_ARGS_FLAG, argv[i]) == 0) {
|
||||||
RCL_RET_OK == _rcl_parse_param_file_rule(
|
continue;
|
||||||
argv[i], allocator, &(args_impl->parameter_files[args_impl->num_param_files_args])))
|
}
|
||||||
{
|
|
||||||
++(args_impl->num_param_files_args);
|
// Check for ROS specific arguments explicit end token
|
||||||
|
if (strcmp(RCL_ROS_ARGS_EXPLICIT_END_TOKEN, argv[i]) == 0) {
|
||||||
|
parsing_ros_args = false;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 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_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",
|
||||||
|
args_impl->parameter_files[args_impl->num_param_files_args - 1],
|
||||||
|
args_impl->num_param_files_args);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
||||||
"params rule : %s\n total num param rules %d",
|
"Couldn't parse arg %d (%s) as parameter file rule. Error: %s", i, argv[i],
|
||||||
args_impl->parameter_files[args_impl->num_param_files_args - 1],
|
rcl_get_error_string().str);
|
||||||
args_impl->num_param_files_args);
|
rcl_reset_error();
|
||||||
continue;
|
|
||||||
|
// Attempt to parse argument as remap rule
|
||||||
|
rcl_remap_t * rule = &(args_impl->remap_rules[args_impl->num_remap_rules]);
|
||||||
|
*rule = rcl_get_zero_initialized_remap();
|
||||||
|
if (RCL_RET_OK == _rcl_parse_remap_rule(argv[i], allocator, rule)) {
|
||||||
|
++(args_impl->num_remap_rules);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
||||||
|
"Couldn't parse arg %d (%s) as remap rule. Error: %s", i, argv[i],
|
||||||
|
rcl_get_error_string().str);
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
// Attempt to parse argument as log level configuration
|
||||||
|
int log_level;
|
||||||
|
if (RCL_RET_OK == _rcl_parse_log_level_rule(argv[i], allocator, &log_level)) {
|
||||||
|
args_impl->log_level = log_level;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
||||||
|
"Couldn't parse arg %d (%s) as log level rule. Error: %s", i, argv[i],
|
||||||
|
rcl_get_error_string().str);
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
// Attempt to parse argument as log configuration file
|
||||||
|
rcl_ret_t ret = _rcl_parse_external_log_config_file(
|
||||||
|
argv[i], allocator, &args_impl->external_log_config_file);
|
||||||
|
if (RCL_RET_OK == ret) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
||||||
|
"Couldn't parse arg %d (%s) as log config rule. Error: %s", i, argv[i],
|
||||||
|
rcl_get_error_string().str);
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
// Attempt to parse argument as log_stdout_disabled
|
||||||
|
ret = _rcl_parse_bool_arg(
|
||||||
|
argv[i], RCL_LOG_DISABLE_STDOUT_ARG_RULE, &args_impl->log_stdout_disabled);
|
||||||
|
if (RCL_RET_OK == ret) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
||||||
|
"Couldn't parse arg %d (%s) as log_stdout_disabled rule. Error: %s", i, argv[i],
|
||||||
|
rcl_get_error_string().str);
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
// Attempt to parse argument as log_rosout_disabled
|
||||||
|
ret = _rcl_parse_bool_arg(
|
||||||
|
argv[i], RCL_LOG_DISABLE_ROSOUT_ARG_RULE, &args_impl->log_rosout_disabled);
|
||||||
|
if (RCL_RET_OK == ret) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
||||||
|
"Couldn't parse arg %d (%s) as log_rosout_disabled rule. Error: %s", i, argv[i],
|
||||||
|
rcl_get_error_string().str);
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
// Attempt to parse argument as log_ext_lib_disabled
|
||||||
|
ret = _rcl_parse_bool_arg(
|
||||||
|
argv[i], RCL_LOG_DISABLE_EXT_LIB_ARG_RULE, &args_impl->log_ext_lib_disabled);
|
||||||
|
if (RCL_RET_OK == ret) {
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
||||||
|
"Couldn't parse arg %d (%s) as log_ext_lib_disabled rule. Error: %s", i, argv[i],
|
||||||
|
rcl_get_error_string().str);
|
||||||
|
rcl_reset_error();
|
||||||
|
|
||||||
|
// Argument is an unknown ROS specific argument
|
||||||
|
args_impl->unparsed_ros_args[args_impl->num_unparsed_ros_args] = i;
|
||||||
|
++(args_impl->num_unparsed_ros_args);
|
||||||
|
} else {
|
||||||
|
// Check for ROS specific arguments flags
|
||||||
|
if (strcmp(RCL_ROS_ARGS_FLAG, argv[i]) == 0) {
|
||||||
|
parsing_ros_args = true;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Argument is not a ROS specific argument
|
||||||
|
args_impl->unparsed_args[args_impl->num_unparsed_args] = i;
|
||||||
|
++(args_impl->num_unparsed_args);
|
||||||
}
|
}
|
||||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
|
||||||
"Couldn't parse arg %d (%s) as parameter file rule. Error: %s", i, argv[i],
|
|
||||||
rcl_get_error_string().str);
|
|
||||||
rcl_reset_error();
|
|
||||||
|
|
||||||
// Attempt to parse argument as remap rule
|
|
||||||
rcl_remap_t * rule = &(args_impl->remap_rules[args_impl->num_remap_rules]);
|
|
||||||
*rule = rcl_get_zero_initialized_remap();
|
|
||||||
if (RCL_RET_OK == _rcl_parse_remap_rule(argv[i], allocator, rule)) {
|
|
||||||
++(args_impl->num_remap_rules);
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
|
||||||
"Couldn't parse arg %d (%s) as remap rule. Error: %s", i, argv[i],
|
|
||||||
rcl_get_error_string().str);
|
|
||||||
rcl_reset_error();
|
|
||||||
|
|
||||||
// Attempt to parse argument as log level configuration
|
|
||||||
int log_level;
|
|
||||||
if (RCL_RET_OK == _rcl_parse_log_level_rule(argv[i], allocator, &log_level)) {
|
|
||||||
args_impl->log_level = log_level;
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
|
||||||
"Couldn't parse arg %d (%s) as log level rule. Error: %s", i, argv[i],
|
|
||||||
rcl_get_error_string().str);
|
|
||||||
rcl_reset_error();
|
|
||||||
|
|
||||||
// Attempt to parse argument as log configuration file
|
|
||||||
rcl_ret_t ret = _rcl_parse_external_log_config_file(
|
|
||||||
argv[i], allocator, &args_impl->external_log_config_file);
|
|
||||||
if (RCL_RET_OK == ret) {
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
|
||||||
"Couldn't parse arg %d (%s) as log config rule. Error: %s", i, argv[i],
|
|
||||||
rcl_get_error_string().str);
|
|
||||||
rcl_reset_error();
|
|
||||||
|
|
||||||
// Attempt to parse argument as log_stdout_disabled
|
|
||||||
ret = _rcl_parse_bool_arg(
|
|
||||||
argv[i], RCL_LOG_DISABLE_STDOUT_ARG_RULE, &args_impl->log_stdout_disabled);
|
|
||||||
if (RCL_RET_OK == ret) {
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
|
||||||
"Couldn't parse arg %d (%s) as log_stdout_disabled rule. Error: %s", i, argv[i],
|
|
||||||
rcl_get_error_string().str);
|
|
||||||
rcl_reset_error();
|
|
||||||
|
|
||||||
// Attempt to parse argument as log_rosout_disabled
|
|
||||||
ret = _rcl_parse_bool_arg(
|
|
||||||
argv[i], RCL_LOG_DISABLE_ROSOUT_ARG_RULE, &args_impl->log_rosout_disabled);
|
|
||||||
if (RCL_RET_OK == ret) {
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
|
||||||
"Couldn't parse arg %d (%s) as log_rosout_disabled rule. Error: %s", i, argv[i],
|
|
||||||
rcl_get_error_string().str);
|
|
||||||
rcl_reset_error();
|
|
||||||
|
|
||||||
// Attempt to parse argument as log_ext_lib_disabled
|
|
||||||
ret = _rcl_parse_bool_arg(
|
|
||||||
argv[i], RCL_LOG_DISABLE_EXT_LIB_ARG_RULE, &args_impl->log_ext_lib_disabled);
|
|
||||||
if (RCL_RET_OK == ret) {
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
|
||||||
"Couldn't parse arg %d (%s) as log_ext_lib_disabled rule. Error: %s", i, argv[i],
|
|
||||||
rcl_get_error_string().str);
|
|
||||||
rcl_reset_error();
|
|
||||||
|
|
||||||
|
|
||||||
// Argument wasn't parsed by any rule
|
|
||||||
args_impl->unparsed_args[args_impl->num_unparsed_args] = i;
|
|
||||||
++(args_impl->num_unparsed_args);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Shrink remap_rules array to match number of successfully parsed rules
|
// Shrink remap_rules array to match number of successfully parsed rules
|
||||||
|
@ -351,6 +381,7 @@ rcl_parse_arguments(
|
||||||
allocator.deallocate(args_impl->remap_rules, allocator.state);
|
allocator.deallocate(args_impl->remap_rules, allocator.state);
|
||||||
args_impl->remap_rules = NULL;
|
args_impl->remap_rules = NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Shrink Parameter files
|
// Shrink Parameter files
|
||||||
if (0 == args_impl->num_param_files_args) {
|
if (0 == args_impl->num_param_files_args) {
|
||||||
allocator.deallocate(args_impl->parameter_files, allocator.state);
|
allocator.deallocate(args_impl->parameter_files, allocator.state);
|
||||||
|
@ -363,6 +394,21 @@ rcl_parse_arguments(
|
||||||
goto fail;
|
goto fail;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Shrink unparsed_ros_args
|
||||||
|
if (0 == args_impl->num_unparsed_ros_args) {
|
||||||
|
// No unparsed ros args
|
||||||
|
allocator.deallocate(args_impl->unparsed_ros_args, allocator.state);
|
||||||
|
args_impl->unparsed_ros_args = NULL;
|
||||||
|
} else if (args_impl->num_unparsed_ros_args < argc) {
|
||||||
|
args_impl->unparsed_ros_args = rcutils_reallocf(
|
||||||
|
args_impl->unparsed_ros_args, sizeof(int) * args_impl->num_unparsed_ros_args, &allocator);
|
||||||
|
if (NULL == args_impl->unparsed_ros_args) {
|
||||||
|
ret = RCL_RET_BAD_ALLOC;
|
||||||
|
goto fail;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// Shrink unparsed_args
|
// Shrink unparsed_args
|
||||||
if (0 == args_impl->num_unparsed_args) {
|
if (0 == args_impl->num_unparsed_args) {
|
||||||
// No unparsed args
|
// No unparsed args
|
||||||
|
@ -424,6 +470,41 @@ rcl_arguments_get_unparsed(
|
||||||
return RCL_RET_OK;
|
return RCL_RET_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
int
|
||||||
|
rcl_arguments_get_count_unparsed_ros(
|
||||||
|
const rcl_arguments_t * args)
|
||||||
|
{
|
||||||
|
if (NULL == args || NULL == args->impl) {
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
return args->impl->num_unparsed_ros_args;
|
||||||
|
}
|
||||||
|
|
||||||
|
rcl_ret_t
|
||||||
|
rcl_arguments_get_unparsed_ros(
|
||||||
|
const rcl_arguments_t * args,
|
||||||
|
rcl_allocator_t allocator,
|
||||||
|
int ** output_unparsed_ros_indices)
|
||||||
|
{
|
||||||
|
RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
|
||||||
|
RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT);
|
||||||
|
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
|
||||||
|
RCL_CHECK_ARGUMENT_FOR_NULL(output_unparsed_ros_indices, RCL_RET_INVALID_ARGUMENT);
|
||||||
|
|
||||||
|
*output_unparsed_ros_indices = NULL;
|
||||||
|
if (args->impl->num_unparsed_ros_args) {
|
||||||
|
*output_unparsed_ros_indices = allocator.allocate(
|
||||||
|
sizeof(int) * args->impl->num_unparsed_ros_args, allocator.state);
|
||||||
|
if (NULL == *output_unparsed_ros_indices) {
|
||||||
|
return RCL_RET_BAD_ALLOC;
|
||||||
|
}
|
||||||
|
for (int i = 0; i < args->impl->num_unparsed_ros_args; ++i) {
|
||||||
|
(*output_unparsed_ros_indices)[i] = args->impl->unparsed_ros_args[i];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return RCL_RET_OK;
|
||||||
|
}
|
||||||
|
|
||||||
rcl_arguments_t
|
rcl_arguments_t
|
||||||
rcl_get_zero_initialized_arguments(void)
|
rcl_get_zero_initialized_arguments(void)
|
||||||
{
|
{
|
||||||
|
@ -502,6 +583,8 @@ rcl_arguments_copy(
|
||||||
args_out->impl->remap_rules = NULL;
|
args_out->impl->remap_rules = NULL;
|
||||||
args_out->impl->unparsed_args = NULL;
|
args_out->impl->unparsed_args = NULL;
|
||||||
args_out->impl->num_unparsed_args = 0;
|
args_out->impl->num_unparsed_args = 0;
|
||||||
|
args_out->impl->unparsed_ros_args = NULL;
|
||||||
|
args_out->impl->num_unparsed_ros_args = 0;
|
||||||
args_out->impl->parameter_files = NULL;
|
args_out->impl->parameter_files = NULL;
|
||||||
args_out->impl->num_param_files_args = 0;
|
args_out->impl->num_param_files_args = 0;
|
||||||
|
|
||||||
|
@ -521,6 +604,22 @@ rcl_arguments_copy(
|
||||||
args_out->impl->num_unparsed_args = args->impl->num_unparsed_args;
|
args_out->impl->num_unparsed_args = args->impl->num_unparsed_args;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (args->impl->num_unparsed_ros_args) {
|
||||||
|
// Copy unparsed ROS args
|
||||||
|
args_out->impl->unparsed_ros_args = allocator.allocate(
|
||||||
|
sizeof(int) * args->impl->num_unparsed_ros_args, allocator.state);
|
||||||
|
if (NULL == args_out->impl->unparsed_ros_args) {
|
||||||
|
if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
|
||||||
|
RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
|
||||||
|
}
|
||||||
|
return RCL_RET_BAD_ALLOC;
|
||||||
|
}
|
||||||
|
for (int i = 0; i < args->impl->num_unparsed_ros_args; ++i) {
|
||||||
|
args_out->impl->unparsed_ros_args[i] = args->impl->unparsed_ros_args[i];
|
||||||
|
}
|
||||||
|
args_out->impl->num_unparsed_ros_args = args->impl->num_unparsed_ros_args;
|
||||||
|
}
|
||||||
|
|
||||||
if (args->impl->num_remap_rules) {
|
if (args->impl->num_remap_rules) {
|
||||||
// Copy remap rules
|
// Copy remap rules
|
||||||
args_out->impl->remap_rules = allocator.allocate(
|
args_out->impl->remap_rules = allocator.allocate(
|
||||||
|
@ -596,6 +695,10 @@ rcl_arguments_fini(
|
||||||
args->impl->num_unparsed_args = 0;
|
args->impl->num_unparsed_args = 0;
|
||||||
args->impl->unparsed_args = NULL;
|
args->impl->unparsed_args = NULL;
|
||||||
|
|
||||||
|
args->impl->allocator.deallocate(args->impl->unparsed_ros_args, args->impl->allocator.state);
|
||||||
|
args->impl->num_unparsed_ros_args = 0;
|
||||||
|
args->impl->unparsed_ros_args = NULL;
|
||||||
|
|
||||||
if (args->impl->parameter_files) {
|
if (args->impl->parameter_files) {
|
||||||
for (int p = 0; p < args->impl->num_param_files_args; ++p) {
|
for (int p = 0; p < args->impl->num_param_files_args; ++p) {
|
||||||
args->impl->allocator.deallocate(
|
args->impl->allocator.deallocate(
|
||||||
|
|
|
@ -26,7 +26,12 @@ extern "C"
|
||||||
/// \internal
|
/// \internal
|
||||||
typedef struct rcl_arguments_impl_t
|
typedef struct rcl_arguments_impl_t
|
||||||
{
|
{
|
||||||
/// Array of indices that were not valid ROS arguments.
|
/// Array of indices to unknown ROS specific arguments.
|
||||||
|
int * unparsed_ros_args;
|
||||||
|
/// Length of unparsed_ros_args.
|
||||||
|
int num_unparsed_ros_args;
|
||||||
|
|
||||||
|
/// Array of indices to non-ROS arguments.
|
||||||
int * unparsed_args;
|
int * unparsed_args;
|
||||||
/// Length of unparsed_args.
|
/// Length of unparsed_args.
|
||||||
int num_unparsed_args;
|
int num_unparsed_args;
|
||||||
|
|
|
@ -49,6 +49,7 @@ public:
|
||||||
if (actual_num_unparsed > 0) { \
|
if (actual_num_unparsed > 0) { \
|
||||||
rcl_ret_t ret = rcl_arguments_get_unparsed(&parsed_args, alloc, &actual_unparsed); \
|
rcl_ret_t ret = rcl_arguments_get_unparsed(&parsed_args, alloc, &actual_unparsed); \
|
||||||
ASSERT_EQ(RCL_RET_OK, ret); \
|
ASSERT_EQ(RCL_RET_OK, ret); \
|
||||||
|
ASSERT_TRUE(NULL != actual_unparsed); \
|
||||||
} \
|
} \
|
||||||
std::stringstream expected; \
|
std::stringstream expected; \
|
||||||
expected << "["; \
|
expected << "["; \
|
||||||
|
@ -65,75 +66,107 @@ public:
|
||||||
if (NULL != actual_unparsed) { \
|
if (NULL != actual_unparsed) { \
|
||||||
alloc.deallocate(actual_unparsed, alloc.state); \
|
alloc.deallocate(actual_unparsed, alloc.state); \
|
||||||
} \
|
} \
|
||||||
EXPECT_STREQ(expected.str().c_str(), actual.str().c_str()); \
|
EXPECT_EQ(expected.str(), actual.str()); \
|
||||||
|
} while (0)
|
||||||
|
|
||||||
|
#define EXPECT_UNPARSED_ROS(parsed_args, ...) \
|
||||||
|
do { \
|
||||||
|
int expect_unparsed_ros[] = {__VA_ARGS__}; \
|
||||||
|
int expect_num_unparsed_ros = sizeof(expect_unparsed_ros) / sizeof(int); \
|
||||||
|
rcl_allocator_t alloc = rcl_get_default_allocator(); \
|
||||||
|
int actual_num_unparsed_ros = rcl_arguments_get_count_unparsed_ros(&parsed_args); \
|
||||||
|
int * actual_unparsed_ros = NULL; \
|
||||||
|
if (actual_num_unparsed_ros > 0) { \
|
||||||
|
rcl_ret_t ret = rcl_arguments_get_unparsed_ros(&parsed_args, alloc, &actual_unparsed_ros); \
|
||||||
|
ASSERT_EQ(RCL_RET_OK, ret); \
|
||||||
|
ASSERT_TRUE(NULL != actual_unparsed_ros); \
|
||||||
|
} \
|
||||||
|
std::stringstream expected; \
|
||||||
|
expected << "["; \
|
||||||
|
for (int e = 0; e < expect_num_unparsed_ros; ++e) { \
|
||||||
|
expected << expect_unparsed_ros[e] << ", "; \
|
||||||
|
} \
|
||||||
|
expected << "]"; \
|
||||||
|
std::stringstream actual; \
|
||||||
|
actual << "["; \
|
||||||
|
for (int a = 0; a < actual_num_unparsed_ros; ++a) { \
|
||||||
|
actual << actual_unparsed_ros[a] << ", "; \
|
||||||
|
} \
|
||||||
|
actual << "]"; \
|
||||||
|
if (NULL != actual_unparsed_ros) { \
|
||||||
|
alloc.deallocate(actual_unparsed_ros, alloc.state); \
|
||||||
|
} \
|
||||||
|
EXPECT_EQ(expected.str(), actual.str()); \
|
||||||
} while (0)
|
} while (0)
|
||||||
|
|
||||||
bool
|
bool
|
||||||
is_valid_arg(const char * arg)
|
is_valid_ros_arg(const char * arg)
|
||||||
{
|
{
|
||||||
const char * argv[] = {arg};
|
const char * argv[] = {"--ros-args", arg};
|
||||||
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
||||||
rcl_ret_t ret = rcl_parse_arguments(1, argv, rcl_get_default_allocator(), &parsed_args);
|
rcl_ret_t ret = rcl_parse_arguments(2, argv, rcl_get_default_allocator(), &parsed_args);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
bool is_valid = 0 == rcl_arguments_get_count_unparsed(&parsed_args);
|
bool is_valid = (
|
||||||
|
0 == rcl_arguments_get_count_unparsed(&parsed_args) &&
|
||||||
|
0 == rcl_arguments_get_count_unparsed_ros(&parsed_args));
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
||||||
return is_valid;
|
return is_valid;
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), check_valid_vs_invalid_args) {
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), check_valid_vs_invalid_args) {
|
||||||
EXPECT_TRUE(is_valid_arg("__node:=node_name"));
|
EXPECT_TRUE(is_valid_ros_arg("__node:=node_name"));
|
||||||
EXPECT_TRUE(is_valid_arg("old_name:__node:=node_name"));
|
EXPECT_TRUE(is_valid_ros_arg("old_name:__node:=node_name"));
|
||||||
EXPECT_TRUE(is_valid_arg("old_name:__node:=nodename123"));
|
EXPECT_TRUE(is_valid_ros_arg("old_name:__node:=nodename123"));
|
||||||
EXPECT_TRUE(is_valid_arg("__node:=nodename123"));
|
EXPECT_TRUE(is_valid_ros_arg("__node:=nodename123"));
|
||||||
EXPECT_TRUE(is_valid_arg("__ns:=/foo/bar"));
|
EXPECT_TRUE(is_valid_ros_arg("__ns:=/foo/bar"));
|
||||||
EXPECT_TRUE(is_valid_arg("__ns:=/"));
|
EXPECT_TRUE(is_valid_ros_arg("__ns:=/"));
|
||||||
EXPECT_TRUE(is_valid_arg("_:=kq"));
|
EXPECT_TRUE(is_valid_ros_arg("_:=kq"));
|
||||||
EXPECT_TRUE(is_valid_arg("nodename:__ns:=/foobar"));
|
EXPECT_TRUE(is_valid_ros_arg("nodename:__ns:=/foobar"));
|
||||||
EXPECT_TRUE(is_valid_arg("foo:=bar"));
|
EXPECT_TRUE(is_valid_ros_arg("foo:=bar"));
|
||||||
EXPECT_TRUE(is_valid_arg("~/foo:=~/bar"));
|
EXPECT_TRUE(is_valid_ros_arg("~/foo:=~/bar"));
|
||||||
EXPECT_TRUE(is_valid_arg("/foo/bar:=bar"));
|
EXPECT_TRUE(is_valid_ros_arg("/foo/bar:=bar"));
|
||||||
EXPECT_TRUE(is_valid_arg("foo:=/bar"));
|
EXPECT_TRUE(is_valid_ros_arg("foo:=/bar"));
|
||||||
EXPECT_TRUE(is_valid_arg("/foo123:=/bar123"));
|
EXPECT_TRUE(is_valid_ros_arg("/foo123:=/bar123"));
|
||||||
EXPECT_TRUE(is_valid_arg("node:/foo123:=/bar123"));
|
EXPECT_TRUE(is_valid_ros_arg("node:/foo123:=/bar123"));
|
||||||
EXPECT_TRUE(is_valid_arg("rostopic:=/foo/bar"));
|
EXPECT_TRUE(is_valid_ros_arg("rostopic:=/foo/bar"));
|
||||||
EXPECT_TRUE(is_valid_arg("rosservice:=baz"));
|
EXPECT_TRUE(is_valid_ros_arg("rosservice:=baz"));
|
||||||
EXPECT_TRUE(is_valid_arg("rostopic://rostopic:=rosservice"));
|
EXPECT_TRUE(is_valid_ros_arg("rostopic://rostopic:=rosservice"));
|
||||||
EXPECT_TRUE(is_valid_arg("rostopic:///rosservice:=rostopic"));
|
EXPECT_TRUE(is_valid_ros_arg("rostopic:///rosservice:=rostopic"));
|
||||||
EXPECT_TRUE(is_valid_arg("rostopic:///foo/bar:=baz"));
|
EXPECT_TRUE(is_valid_ros_arg("rostopic:///foo/bar:=baz"));
|
||||||
EXPECT_TRUE(is_valid_arg("__params:=file_name.yaml"));
|
EXPECT_TRUE(is_valid_ros_arg("__params:=file_name.yaml"));
|
||||||
|
|
||||||
EXPECT_FALSE(is_valid_arg(":="));
|
EXPECT_FALSE(is_valid_ros_arg(":="));
|
||||||
EXPECT_FALSE(is_valid_arg("foo:="));
|
EXPECT_FALSE(is_valid_ros_arg("foo:="));
|
||||||
EXPECT_FALSE(is_valid_arg(":=bar"));
|
EXPECT_FALSE(is_valid_ros_arg(":=bar"));
|
||||||
EXPECT_FALSE(is_valid_arg("__ns:="));
|
EXPECT_FALSE(is_valid_ros_arg("__ns:="));
|
||||||
EXPECT_FALSE(is_valid_arg("__node:="));
|
EXPECT_FALSE(is_valid_ros_arg("__node:="));
|
||||||
EXPECT_FALSE(is_valid_arg("__node:=/foo/bar"));
|
EXPECT_FALSE(is_valid_ros_arg("__node:=/foo/bar"));
|
||||||
EXPECT_FALSE(is_valid_arg("__ns:=foo"));
|
EXPECT_FALSE(is_valid_ros_arg("__ns:=foo"));
|
||||||
EXPECT_FALSE(is_valid_arg(":__node:=nodename"));
|
EXPECT_FALSE(is_valid_ros_arg(":__node:=nodename"));
|
||||||
EXPECT_FALSE(is_valid_arg("~:__node:=nodename"));
|
EXPECT_FALSE(is_valid_ros_arg("~:__node:=nodename"));
|
||||||
EXPECT_FALSE(is_valid_arg("}foo:=/bar"));
|
EXPECT_FALSE(is_valid_ros_arg("}foo:=/bar"));
|
||||||
EXPECT_FALSE(is_valid_arg("f oo:=/bar"));
|
EXPECT_FALSE(is_valid_ros_arg("f oo:=/bar"));
|
||||||
EXPECT_FALSE(is_valid_arg("foo:=/b ar"));
|
EXPECT_FALSE(is_valid_ros_arg("foo:=/b ar"));
|
||||||
EXPECT_FALSE(is_valid_arg("f{oo:=/bar"));
|
EXPECT_FALSE(is_valid_ros_arg("f{oo:=/bar"));
|
||||||
EXPECT_FALSE(is_valid_arg("foo:=/b}ar"));
|
EXPECT_FALSE(is_valid_ros_arg("foo:=/b}ar"));
|
||||||
EXPECT_FALSE(is_valid_arg("rostopic://:=rosservice"));
|
EXPECT_FALSE(is_valid_ros_arg("rostopic://:=rosservice"));
|
||||||
EXPECT_FALSE(is_valid_arg("rostopic::=rosservice"));
|
EXPECT_FALSE(is_valid_ros_arg("rostopic::=rosservice"));
|
||||||
EXPECT_FALSE(is_valid_arg("__param:=file_name.yaml"));
|
EXPECT_FALSE(is_valid_ros_arg("__param:=file_name.yaml"));
|
||||||
|
|
||||||
// Setting logger level
|
// Setting logger level
|
||||||
EXPECT_TRUE(is_valid_arg("__log_level:=UNSET"));
|
EXPECT_TRUE(is_valid_ros_arg("__log_level:=UNSET"));
|
||||||
EXPECT_TRUE(is_valid_arg("__log_level:=DEBUG"));
|
EXPECT_TRUE(is_valid_ros_arg("__log_level:=DEBUG"));
|
||||||
EXPECT_TRUE(is_valid_arg("__log_level:=INFO"));
|
EXPECT_TRUE(is_valid_ros_arg("__log_level:=INFO"));
|
||||||
EXPECT_TRUE(is_valid_arg("__log_level:=WARN"));
|
EXPECT_TRUE(is_valid_ros_arg("__log_level:=WARN"));
|
||||||
EXPECT_TRUE(is_valid_arg("__log_level:=ERROR"));
|
EXPECT_TRUE(is_valid_ros_arg("__log_level:=ERROR"));
|
||||||
EXPECT_TRUE(is_valid_arg("__log_level:=FATAL"));
|
EXPECT_TRUE(is_valid_ros_arg("__log_level:=FATAL"));
|
||||||
EXPECT_TRUE(is_valid_arg("__log_level:=debug"));
|
EXPECT_TRUE(is_valid_ros_arg("__log_level:=debug"));
|
||||||
EXPECT_TRUE(is_valid_arg("__log_level:=Info"));
|
EXPECT_TRUE(is_valid_ros_arg("__log_level:=Info"));
|
||||||
|
|
||||||
EXPECT_FALSE(is_valid_arg("__log:=foo"));
|
EXPECT_FALSE(is_valid_ros_arg("__log:=foo"));
|
||||||
EXPECT_FALSE(is_valid_arg("__loglevel:=foo"));
|
EXPECT_FALSE(is_valid_ros_arg("__loglevel:=foo"));
|
||||||
EXPECT_FALSE(is_valid_arg("__log_level:="));
|
EXPECT_FALSE(is_valid_ros_arg("__log_level:="));
|
||||||
EXPECT_FALSE(is_valid_arg("__log_level:=foo"));
|
EXPECT_FALSE(is_valid_ros_arg("__log_level:=foo"));
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_args) {
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_args) {
|
||||||
|
@ -141,6 +174,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_args) {
|
||||||
rcl_ret_t ret = rcl_parse_arguments(0, NULL, rcl_get_default_allocator(), &parsed_args);
|
rcl_ret_t ret = rcl_parse_arguments(0, NULL, rcl_get_default_allocator(), &parsed_args);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
EXPECT_EQ(0, rcl_arguments_get_count_unparsed(&parsed_args));
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed(&parsed_args));
|
||||||
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed_ros(&parsed_args));
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -160,30 +194,105 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_null_args_outpu
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_ros_args) {
|
||||||
|
const char * argv[] = {"process_name"};
|
||||||
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
|
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
||||||
|
rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
EXPECT_UNPARSED(parsed_args, 0);
|
||||||
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed_ros(&parsed_args));
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_zero_ros_args) {
|
||||||
|
const char * argv[] = {"process_name", "--ros-args"};
|
||||||
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
|
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
||||||
|
rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
EXPECT_UNPARSED(parsed_args, 0);
|
||||||
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed_ros(&parsed_args));
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_zero_ros_args_w_trailing_dashes) {
|
||||||
|
const char * argv[] = {"process_name", "--ros-args", "--"};
|
||||||
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
|
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
||||||
|
rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
EXPECT_UNPARSED(parsed_args, 0);
|
||||||
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed_ros(&parsed_args));
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
||||||
|
}
|
||||||
|
|
||||||
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap) {
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap) {
|
||||||
const char * argv[] = {"process_name", "/foo/bar:=/fiz/buz"};
|
const char * argv[] = {"process_name", "--ros-args", "/foo/bar:=/fiz/buz"};
|
||||||
int argc = sizeof(argv) / sizeof(const char *);
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
|
ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
EXPECT_UNPARSED(parsed_args, 0);
|
EXPECT_UNPARSED(parsed_args, 0);
|
||||||
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed_ros(&parsed_args));
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_mix_valid_invalid_rules) {
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap_two_ros_args) {
|
||||||
const char * argv[] = {"process_name", "/foo/bar:=", "bar:=/fiz/buz", "}bar:=fiz"};
|
const char * argv[] = {"process_name", "--ros-args", "--ros-args", "/foo/bar:=/fiz/buz"};
|
||||||
int argc = sizeof(argv) / sizeof(const char *);
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
|
ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
EXPECT_UNPARSED(parsed_args, 0, 1, 3);
|
EXPECT_UNPARSED(parsed_args, 0);
|
||||||
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed_ros(&parsed_args));
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap_w_trailing_dashes) {
|
||||||
|
const char * argv[] = {"process_name", "--ros-args", "/foo/bar:=/fiz/buz", "--"};
|
||||||
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
|
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
||||||
|
rcl_ret_t ret;
|
||||||
|
ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
EXPECT_UNPARSED(parsed_args, 0);
|
||||||
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed_ros(&parsed_args));
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap_w_two_trailing_dashes) {
|
||||||
|
const char * argv[] = {"process_name", "--ros-args", "/foo/bar:=/fiz/buz", "--", "--"};
|
||||||
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
|
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
||||||
|
rcl_ret_t ret;
|
||||||
|
ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
EXPECT_UNPARSED(parsed_args, 0, 4);
|
||||||
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed_ros(&parsed_args));
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_mix_valid_invalid_rules) {
|
||||||
|
const char * argv[] = {
|
||||||
|
"process_name", "--ros-args", "/foo/bar:=", "bar:=/fiz/buz", "}bar:=fiz", "--", "arg"
|
||||||
|
};
|
||||||
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
|
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
||||||
|
rcl_ret_t ret;
|
||||||
|
ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
EXPECT_UNPARSED(parsed_args, 0, 6);
|
||||||
|
EXPECT_UNPARSED_ROS(parsed_args, 2, 4);
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy) {
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy) {
|
||||||
const char * argv[] = {"process_name", "/foo/bar:=", "bar:=/fiz/buz", "__ns:=/foo"};
|
const char * argv[] = {
|
||||||
|
"process_name", "--ros-args", "/foo/bar:=", "bar:=/fiz/buz", "__ns:=/foo", "--", "arg"
|
||||||
|
};
|
||||||
int argc = sizeof(argv) / sizeof(const char *);
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
|
@ -195,10 +304,34 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy) {
|
||||||
ret = rcl_arguments_copy(&parsed_args, &copied_args);
|
ret = rcl_arguments_copy(&parsed_args, &copied_args);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
|
||||||
EXPECT_UNPARSED(parsed_args, 0, 1);
|
EXPECT_UNPARSED(parsed_args, 0, 6);
|
||||||
|
EXPECT_UNPARSED_ROS(parsed_args, 2);
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
||||||
|
|
||||||
EXPECT_UNPARSED(copied_args, 0, 1);
|
EXPECT_UNPARSED(copied_args, 0, 6);
|
||||||
|
EXPECT_UNPARSED_ROS(copied_args, 2);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&copied_args));
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy_no_ros_args) {
|
||||||
|
const char * argv[] = {"process_name", "--ros-args", "--", "arg", "--ros-args"};
|
||||||
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
|
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
||||||
|
rcl_ret_t ret;
|
||||||
|
|
||||||
|
ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
rcl_arguments_t copied_args = rcl_get_zero_initialized_arguments();
|
||||||
|
ret = rcl_arguments_copy(&parsed_args, &copied_args);
|
||||||
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
|
|
||||||
|
EXPECT_UNPARSED(parsed_args, 0, 3);
|
||||||
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed_ros(&parsed_args));
|
||||||
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
||||||
|
|
||||||
|
EXPECT_UNPARSED(copied_args, 0, 3);
|
||||||
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed_ros(&copied_args));
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&copied_args));
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&copied_args));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -222,24 +355,27 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy_no_args) {
|
||||||
rcl_ret_t ret = rcl_parse_arguments(0, NULL, allocator, &parsed_args);
|
rcl_ret_t ret = rcl_parse_arguments(0, NULL, allocator, &parsed_args);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
EXPECT_EQ(0, rcl_arguments_get_count_unparsed(&parsed_args));
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed(&parsed_args));
|
||||||
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed_ros(&parsed_args));
|
||||||
|
|
||||||
rcl_arguments_t copied_args = rcl_get_zero_initialized_arguments();
|
rcl_arguments_t copied_args = rcl_get_zero_initialized_arguments();
|
||||||
ret = rcl_arguments_copy(&parsed_args, &copied_args);
|
ret = rcl_arguments_copy(&parsed_args, &copied_args);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
EXPECT_EQ(0, rcl_arguments_get_count_unparsed(&copied_args));
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed(&copied_args));
|
||||||
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed_ros(&copied_args));
|
||||||
|
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&copied_args));
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&copied_args));
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_two_namespace) {
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_two_namespace) {
|
||||||
const char * argv[] = {"process_name", "__ns:=/foo/bar", "__ns:=/fiz/buz"};
|
const char * argv[] = {"process_name", "--ros-args", "__ns:=/foo/bar", "__ns:=/fiz/buz"};
|
||||||
int argc = sizeof(argv) / sizeof(const char *);
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments();
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
|
ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args);
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
EXPECT_UNPARSED(parsed_args, 0);
|
EXPECT_UNPARSED(parsed_args, 0);
|
||||||
|
EXPECT_EQ(0, rcl_arguments_get_count_unparsed_ros(&parsed_args));
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -255,7 +391,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_uninitialized_p
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_double_parse) {
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_double_parse) {
|
||||||
const char * argv[] = {"process_name", "__ns:=/foo/bar", "__ns:=/fiz/buz"};
|
const char * argv[] = {"process_name", "--ros-args", "__ns:=/foo/bar", "__ns:=/fiz/buz"};
|
||||||
int argc = sizeof(argv) / sizeof(const char *);
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
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,
|
||||||
|
@ -266,7 +402,6 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_double_parse) {
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
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) {
|
||||||
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_arguments_fini(NULL));
|
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_arguments_fini(NULL));
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
|
@ -290,8 +425,10 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_fini_twice) {
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remove_ros_args) {
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remove_ros_args) {
|
||||||
const char * argv[] =
|
const char * argv[] = {
|
||||||
{"process_name", "-d", "__ns:=/foo/bar", "__ns:=/fiz/buz", "--foo=bar", "--baz"};
|
"process_name", "-d", "--ros-args", "__ns:=/foo/bar", "__ns:=/fiz/buz", "--",
|
||||||
|
"--foo=bar", "--baz", "--ros-args", "--ros-args", "bar:=baz", "--", "--", "arg"
|
||||||
|
};
|
||||||
int argc = sizeof(argv) / sizeof(const char *);
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
|
|
||||||
rcl_allocator_t alloc = rcl_get_default_allocator();
|
rcl_allocator_t alloc = rcl_get_default_allocator();
|
||||||
|
@ -311,11 +448,13 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remove_ros_args
|
||||||
&nonros_argv);
|
&nonros_argv);
|
||||||
|
|
||||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||||
ASSERT_EQ(nonros_argc, 4);
|
ASSERT_EQ(nonros_argc, 6);
|
||||||
EXPECT_STREQ(nonros_argv[0], "process_name");
|
EXPECT_STREQ(nonros_argv[0], "process_name");
|
||||||
EXPECT_STREQ(nonros_argv[1], "-d");
|
EXPECT_STREQ(nonros_argv[1], "-d");
|
||||||
EXPECT_STREQ(nonros_argv[2], "--foo=bar");
|
EXPECT_STREQ(nonros_argv[2], "--foo=bar");
|
||||||
EXPECT_STREQ(nonros_argv[3], "--baz");
|
EXPECT_STREQ(nonros_argv[3], "--baz");
|
||||||
|
EXPECT_STREQ(nonros_argv[4], "--");
|
||||||
|
EXPECT_STREQ(nonros_argv[5], "arg");
|
||||||
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args));
|
||||||
|
|
||||||
if (NULL != nonros_argv) {
|
if (NULL != nonros_argv) {
|
||||||
|
@ -348,7 +487,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remove_ros_args
|
||||||
}
|
}
|
||||||
|
|
||||||
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_zero) {
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_zero) {
|
||||||
const char * argv[] = {"process_name", "__ns:=/namespace", "random:=arg"};
|
const char * argv[] = {"process_name", "--ros-args", "__ns:=/namespace", "random:=arg"};
|
||||||
int argc = sizeof(argv) / sizeof(const char *);
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
|
|
||||||
|
@ -365,7 +504,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_
|
||||||
|
|
||||||
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_single) {
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_single) {
|
||||||
const char * argv[] = {
|
const char * argv[] = {
|
||||||
"process_name", "__ns:=/namespace", "random:=arg", "__params:=parameter_filepath"
|
"process_name", "--ros-args", "__ns:=/namespace", "random:=arg", "__params:=parameter_filepath"
|
||||||
};
|
};
|
||||||
int argc = sizeof(argv) / sizeof(const char *);
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
|
@ -392,7 +531,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_
|
||||||
|
|
||||||
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_multiple) {
|
TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_multiple) {
|
||||||
const char * argv[] = {
|
const char * argv[] = {
|
||||||
"process_name", "__params:=parameter_filepath1", "__ns:=/namespace",
|
"process_name", "--ros-args", "__params:=parameter_filepath1", "__ns:=/namespace",
|
||||||
"random:=arg", "__params:=parameter_filepath2"
|
"random:=arg", "__params:=parameter_filepath2"
|
||||||
};
|
};
|
||||||
int argc = sizeof(argv) / sizeof(const char *);
|
int argc = sizeof(argv) / sizeof(const char *);
|
||||||
|
|
|
@ -42,7 +42,7 @@ public:
|
||||||
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_namespace_replacement) {
|
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_namespace_replacement) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(global_arguments, "process_name", "__ns:=/foo/bar");
|
SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "__ns:=/foo/bar");
|
||||||
|
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
ret = rcl_remap_node_namespace(
|
ret = rcl_remap_node_namespace(
|
||||||
|
@ -57,7 +57,11 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), nodename_prefix_namespac
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(
|
SCOPE_ARGS(
|
||||||
global_arguments,
|
global_arguments,
|
||||||
"process_name", "Node1:__ns:=/foo/bar", "Node2:__ns:=/this_one", "Node3:__ns:=/bar/foo");
|
"process_name",
|
||||||
|
"--ros-args",
|
||||||
|
"Node1:__ns:=/foo/bar",
|
||||||
|
"Node2:__ns:=/this_one",
|
||||||
|
"Node3:__ns:=/bar/foo");
|
||||||
|
|
||||||
{
|
{
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
|
@ -100,9 +104,9 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_namespace_replacement
|
||||||
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_namespace_replacement_before_global) {
|
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_namespace_replacement_before_global) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(global_arguments, "process_name", "__ns:=/global_args");
|
SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "__ns:=/global_args");
|
||||||
rcl_arguments_t local_arguments;
|
rcl_arguments_t local_arguments;
|
||||||
SCOPE_ARGS(local_arguments, "process_name", "__ns:=/local_args");
|
SCOPE_ARGS(local_arguments, "process_name", "--ros-args", "__ns:=/local_args");
|
||||||
|
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
ret = rcl_remap_node_namespace(
|
ret = rcl_remap_node_namespace(
|
||||||
|
@ -128,7 +132,12 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_names
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(
|
SCOPE_ARGS(
|
||||||
global_arguments, "process_name", "/foobar:=/foo/bar", "__ns:=/namespace", "__node:=new_name");
|
global_arguments,
|
||||||
|
"process_name",
|
||||||
|
"--ros-args",
|
||||||
|
"/foobar:=/foo/bar",
|
||||||
|
"__ns:=/namespace",
|
||||||
|
"__node:=new_name");
|
||||||
|
|
||||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
|
@ -141,7 +150,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_names
|
||||||
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_topic_name_replacement) {
|
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_topic_name_replacement) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(global_arguments, "process_name", "/bar/foo:=/foo/bar");
|
SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "/bar/foo:=/foo/bar");
|
||||||
|
|
||||||
{
|
{
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
|
@ -163,7 +172,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_topic_name_replac
|
||||||
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), relative_topic_name_remap) {
|
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), relative_topic_name_remap) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(global_arguments, "process_name", "foo:=bar");
|
SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "foo:=bar");
|
||||||
|
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
ret = rcl_remap_topic_name(
|
ret = rcl_remap_topic_name(
|
||||||
|
@ -178,7 +187,11 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), nodename_prefix_topic_re
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(
|
SCOPE_ARGS(
|
||||||
global_arguments,
|
global_arguments,
|
||||||
"process_name", "Node1:/foo:=/foo/bar", "Node2:/foo:=/this_one", "Node3:/foo:=/bar/foo");
|
"process_name",
|
||||||
|
"--ros-args",
|
||||||
|
"Node1:/foo:=/foo/bar",
|
||||||
|
"Node2:/foo:=/this_one",
|
||||||
|
"Node3:/foo:=/bar/foo");
|
||||||
|
|
||||||
{
|
{
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
|
@ -233,9 +246,9 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_topic_name_replacemen
|
||||||
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_topic_replacement_before_global) {
|
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_topic_replacement_before_global) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(global_arguments, "process_name", "/bar/foo:=/foo/global_args");
|
SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "/bar/foo:=/foo/global_args");
|
||||||
rcl_arguments_t local_arguments;
|
rcl_arguments_t local_arguments;
|
||||||
SCOPE_ARGS(local_arguments, "process_name", "/bar/foo:=/foo/local_args");
|
SCOPE_ARGS(local_arguments, "process_name", "--ros-args", "/bar/foo:=/foo/local_args");
|
||||||
|
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
ret = rcl_remap_topic_name(
|
ret = rcl_remap_topic_name(
|
||||||
|
@ -250,7 +263,11 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_topic
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(
|
SCOPE_ARGS(
|
||||||
global_arguments, "process_name", "__ns:=/namespace", "__node:=remap_name",
|
global_arguments,
|
||||||
|
"process_name",
|
||||||
|
"--ros-args",
|
||||||
|
"__ns:=/namespace",
|
||||||
|
"__node:=remap_name",
|
||||||
"/foobar:=/foo/bar");
|
"/foobar:=/foo/bar");
|
||||||
|
|
||||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||||
|
@ -265,7 +282,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_topic
|
||||||
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_service_name_replacement) {
|
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_service_name_replacement) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(global_arguments, "process_name", "/bar/foo:=/foo/bar");
|
SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "/bar/foo:=/foo/bar");
|
||||||
|
|
||||||
{
|
{
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
|
@ -287,7 +304,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_service_name_repl
|
||||||
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), relative_service_name_remap) {
|
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), relative_service_name_remap) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(global_arguments, "process_name", "foo:=bar");
|
SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "foo:=bar");
|
||||||
|
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
ret = rcl_remap_service_name(
|
ret = rcl_remap_service_name(
|
||||||
|
@ -302,7 +319,11 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), nodename_prefix_service_
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(
|
SCOPE_ARGS(
|
||||||
global_arguments,
|
global_arguments,
|
||||||
"process_name", "Node1:/foo:=/foo/bar", "Node2:/foo:=/this_one", "Node3:/foo:=/bar/foo");
|
"process_name",
|
||||||
|
"--ros-args",
|
||||||
|
"Node1:/foo:=/foo/bar",
|
||||||
|
"Node2:/foo:=/this_one",
|
||||||
|
"Node3:/foo:=/bar/foo");
|
||||||
|
|
||||||
{
|
{
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
|
@ -358,9 +379,9 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_service_name_replacem
|
||||||
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_service_replacement_before_global) {
|
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_service_replacement_before_global) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(global_arguments, "process_name", "/bar/foo:=/foo/global_args");
|
SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "/bar/foo:=/foo/global_args");
|
||||||
rcl_arguments_t local_arguments;
|
rcl_arguments_t local_arguments;
|
||||||
SCOPE_ARGS(local_arguments, "process_name", "/bar/foo:=/foo/local_args");
|
SCOPE_ARGS(local_arguments, "process_name", "--ros-args", "/bar/foo:=/foo/local_args");
|
||||||
|
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
ret = rcl_remap_service_name(
|
ret = rcl_remap_service_name(
|
||||||
|
@ -375,7 +396,11 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_servi
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(
|
SCOPE_ARGS(
|
||||||
global_arguments, "process_name", "__ns:=/namespace", "__node:=remap_name",
|
global_arguments,
|
||||||
|
"process_name",
|
||||||
|
"--ros-args",
|
||||||
|
"__ns:=/namespace",
|
||||||
|
"__node:=remap_name",
|
||||||
"/foobar:=/foo/bar");
|
"/foobar:=/foo/bar");
|
||||||
|
|
||||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||||
|
@ -390,7 +415,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_servi
|
||||||
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_nodename_replacement) {
|
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), global_nodename_replacement) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(global_arguments, "process_name", "__node:=globalname");
|
SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "__node:=globalname");
|
||||||
|
|
||||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
|
@ -415,9 +440,9 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_nodename_replacement)
|
||||||
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_nodename_replacement_before_global) {
|
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), local_nodename_replacement_before_global) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(global_arguments, "process_name", "__node:=global_name");
|
SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "__node:=global_name");
|
||||||
rcl_arguments_t local_arguments;
|
rcl_arguments_t local_arguments;
|
||||||
SCOPE_ARGS(local_arguments, "process_name", "__node:=local_name");
|
SCOPE_ARGS(local_arguments, "process_name", "--ros-args", "__node:=local_name");
|
||||||
|
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
ret = rcl_remap_node_name(
|
ret = rcl_remap_node_name(
|
||||||
|
@ -442,7 +467,12 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), no_use_global_nodename_r
|
||||||
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), use_first_nodename_rule) {
|
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), use_first_nodename_rule) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(global_arguments, "process_name", "__node:=firstname", "__node:=secondname");
|
SCOPE_ARGS(
|
||||||
|
global_arguments,
|
||||||
|
"process_name",
|
||||||
|
"--ros-args",
|
||||||
|
"__node:=firstname",
|
||||||
|
"__node:=secondname");
|
||||||
|
|
||||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
|
@ -456,7 +486,12 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_noden
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(
|
SCOPE_ARGS(
|
||||||
global_arguments, "process_name", "/foobar:=/foo", "__ns:=/namespace", "__node:=remap_name");
|
global_arguments,
|
||||||
|
"process_name",
|
||||||
|
"--ros-args",
|
||||||
|
"/foobar:=/foo",
|
||||||
|
"__ns:=/namespace",
|
||||||
|
"__node:=remap_name");
|
||||||
|
|
||||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
|
@ -469,7 +504,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), other_rules_before_noden
|
||||||
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), url_scheme_rosservice) {
|
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), url_scheme_rosservice) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(global_arguments, "process_name", "rosservice://foo:=bar");
|
SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "rosservice://foo:=bar");
|
||||||
|
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
ret = rcl_remap_service_name(
|
ret = rcl_remap_service_name(
|
||||||
|
@ -487,7 +522,7 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), url_scheme_rosservice) {
|
||||||
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), url_scheme_rostopic) {
|
TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), url_scheme_rostopic) {
|
||||||
rcl_ret_t ret;
|
rcl_ret_t ret;
|
||||||
rcl_arguments_t global_arguments;
|
rcl_arguments_t global_arguments;
|
||||||
SCOPE_ARGS(global_arguments, "process_name", "rostopic://foo:=bar");
|
SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "rostopic://foo:=bar");
|
||||||
|
|
||||||
char * output = NULL;
|
char * output = NULL;
|
||||||
ret = rcl_remap_topic_name(
|
ret = rcl_remap_topic_name(
|
||||||
|
|
|
@ -46,7 +46,12 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_g
|
||||||
int argc;
|
int argc;
|
||||||
char ** argv;
|
char ** argv;
|
||||||
SCOPE_GLOBAL_ARGS(
|
SCOPE_GLOBAL_ARGS(
|
||||||
argc, argv, "process_name", "__node:=new_name", "__ns:=/new_ns", "/foo/bar:=/bar/foo");
|
argc, argv,
|
||||||
|
"process_name",
|
||||||
|
"--ros-args",
|
||||||
|
"__node:=new_name",
|
||||||
|
"__ns:=/new_ns",
|
||||||
|
"/foo/bar:=/bar/foo");
|
||||||
|
|
||||||
rcl_node_t node = rcl_get_zero_initialized_node();
|
rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
rcl_node_options_t default_options = rcl_node_get_default_options();
|
rcl_node_options_t default_options = rcl_node_get_default_options();
|
||||||
|
@ -112,7 +117,12 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), ignore_global
|
||||||
int argc;
|
int argc;
|
||||||
char ** argv;
|
char ** argv;
|
||||||
SCOPE_GLOBAL_ARGS(
|
SCOPE_GLOBAL_ARGS(
|
||||||
argc, argv, "process_name", "__node:=new_name", "__ns:=/new_ns", "/foo/bar:=/bar/foo");
|
argc, argv,
|
||||||
|
"process_name",
|
||||||
|
"--ros-args",
|
||||||
|
"__node:=new_name",
|
||||||
|
"__ns:=/new_ns",
|
||||||
|
"/foo/bar:=/bar/foo");
|
||||||
rcl_arguments_t local_arguments;
|
rcl_arguments_t local_arguments;
|
||||||
SCOPE_ARGS(local_arguments, "local_process_name");
|
SCOPE_ARGS(local_arguments, "local_process_name");
|
||||||
|
|
||||||
|
@ -180,11 +190,20 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), local_rules_b
|
||||||
int argc;
|
int argc;
|
||||||
char ** argv;
|
char ** argv;
|
||||||
SCOPE_GLOBAL_ARGS(
|
SCOPE_GLOBAL_ARGS(
|
||||||
argc, argv, "process_name", "__node:=global_name", "__ns:=/global_ns", "/foo/bar:=/bar/global");
|
argc, argv,
|
||||||
|
"process_name",
|
||||||
|
"--ros-args",
|
||||||
|
"__node:=global_name",
|
||||||
|
"__ns:=/global_ns",
|
||||||
|
"/foo/bar:=/bar/global");
|
||||||
rcl_arguments_t local_arguments;
|
rcl_arguments_t local_arguments;
|
||||||
SCOPE_ARGS(
|
SCOPE_ARGS(
|
||||||
local_arguments,
|
local_arguments,
|
||||||
"process_name", "__node:=local_name", "__ns:=/local_ns", "/foo/bar:=/bar/local");
|
"process_name",
|
||||||
|
"--ros-args",
|
||||||
|
"__node:=local_name",
|
||||||
|
"__ns:=/local_ns",
|
||||||
|
"/foo/bar:=/bar/local");
|
||||||
|
|
||||||
rcl_node_t node = rcl_get_zero_initialized_node();
|
rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
rcl_node_options_t options = rcl_node_get_default_options();
|
rcl_node_options_t options = rcl_node_get_default_options();
|
||||||
|
@ -248,7 +267,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), local_rules_b
|
||||||
TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relative_topic) {
|
TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_relative_topic) {
|
||||||
int argc;
|
int argc;
|
||||||
char ** argv;
|
char ** argv;
|
||||||
SCOPE_GLOBAL_ARGS(argc, argv, "process_name", "/foo/bar:=remap/global");
|
SCOPE_GLOBAL_ARGS(argc, argv, "process_name", "--ros-args", "/foo/bar:=remap/global");
|
||||||
|
|
||||||
rcl_node_t node = rcl_get_zero_initialized_node();
|
rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
rcl_node_options_t default_options = rcl_node_get_default_options();
|
rcl_node_options_t default_options = rcl_node_get_default_options();
|
||||||
|
@ -303,7 +322,7 @@ TEST_F(CLASSNAME(TestRemapIntegrationFixture, RMW_IMPLEMENTATION), remap_using_n
|
||||||
int argc;
|
int argc;
|
||||||
char ** argv;
|
char ** argv;
|
||||||
SCOPE_GLOBAL_ARGS(
|
SCOPE_GLOBAL_ARGS(
|
||||||
argc, argv, "process_name", "original_name:__ns:=/new_ns");
|
argc, argv, "process_name", "--ros-args", "original_name:__ns:=/new_ns");
|
||||||
|
|
||||||
rcl_node_t node = rcl_get_zero_initialized_node();
|
rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
rcl_node_options_t default_options = rcl_node_get_default_options();
|
rcl_node_options_t default_options = rcl_node_get_default_options();
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue