Support parameter overrides and remap rules flags on command line (#483)
* Support rcl_params_t copies. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Parse parameter overrides from command line. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Parameter overrides' tests passing. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Test rcl_yaml_node_struct_copy() function Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Export rcl_yaml_param_parser as rcl dependency. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Zero initialize parameter overrides before rcl arguments copy. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Initialize local variables early enough. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Simplify rcl package.xml Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Assert arguments sanity in rcl args parsing internal functions. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Extend rcl_yaml_param_parser tests to all parameter types. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Address peer review comments. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Support --remap/-r flags. Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> * Please cpplint Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
This commit is contained in:
parent
d07003847b
commit
6f989433bc
10 changed files with 838 additions and 201 deletions
|
@ -393,6 +393,186 @@ rcl_params_t * rcl_yaml_node_struct_init(
|
|||
return params_st;
|
||||
}
|
||||
|
||||
///
|
||||
/// Copy the rcl_params_t parameter structure
|
||||
///
|
||||
rcl_params_t * rcl_yaml_node_struct_copy(
|
||||
const rcl_params_t * params_st)
|
||||
{
|
||||
RCUTILS_CHECK_ARGUMENT_FOR_NULL(params_st, NULL);
|
||||
|
||||
rcutils_allocator_t allocator = params_st->allocator;
|
||||
rcl_params_t * out_params_st = rcl_yaml_node_struct_init(allocator);
|
||||
|
||||
if (NULL == out_params_st) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
rcutils_ret_t ret;
|
||||
for (size_t node_idx = 0U; node_idx < params_st->num_nodes; ++node_idx) {
|
||||
out_params_st->node_names[node_idx] =
|
||||
rcutils_strdup(params_st->node_names[node_idx], allocator);
|
||||
if (NULL == out_params_st->node_names[node_idx]) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
goto fail;
|
||||
}
|
||||
out_params_st->num_nodes++;
|
||||
|
||||
rcl_node_params_t * node_params_st = &(params_st->params[node_idx]);
|
||||
rcl_node_params_t * out_node_params_st = &(out_params_st->params[node_idx]);
|
||||
ret = node_params_init(out_node_params_st, allocator);
|
||||
if (RCUTILS_RET_OK != ret) {
|
||||
if (RCUTILS_RET_BAD_ALLOC == ret) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
}
|
||||
goto fail;
|
||||
}
|
||||
for (size_t parameter_idx = 0U; parameter_idx < node_params_st->num_params; ++parameter_idx) {
|
||||
out_node_params_st->parameter_names[parameter_idx] =
|
||||
rcutils_strdup(node_params_st->parameter_names[parameter_idx], allocator);
|
||||
if (NULL == out_node_params_st->parameter_names[parameter_idx]) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
goto fail;
|
||||
}
|
||||
out_node_params_st->num_params++;
|
||||
|
||||
rcl_variant_t * param_var = &(node_params_st->parameter_values[parameter_idx]);
|
||||
rcl_variant_t * out_param_var = &(out_node_params_st->parameter_values[parameter_idx]);
|
||||
if (NULL != param_var->bool_value) {
|
||||
out_param_var->bool_value = allocator.allocate(sizeof(bool), allocator.state);
|
||||
if (NULL == out_param_var->bool_value) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
goto fail;
|
||||
}
|
||||
*(out_param_var->bool_value) = *(param_var->bool_value);
|
||||
} else if (NULL != param_var->integer_value) {
|
||||
out_param_var->integer_value = allocator.allocate(sizeof(int64_t), allocator.state);
|
||||
if (NULL == out_param_var->integer_value) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
goto fail;
|
||||
}
|
||||
*(out_param_var->integer_value) = *(param_var->integer_value);
|
||||
} else if (NULL != param_var->double_value) {
|
||||
out_param_var->double_value = allocator.allocate(sizeof(double), allocator.state);
|
||||
if (NULL == out_param_var->double_value) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
goto fail;
|
||||
}
|
||||
*(out_param_var->double_value) = *(param_var->double_value);
|
||||
} else if (NULL != param_var->string_value) {
|
||||
out_param_var->string_value =
|
||||
rcutils_strdup(param_var->string_value, allocator);
|
||||
if (NULL == out_param_var->string_value) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
goto fail;
|
||||
}
|
||||
} else if (NULL != param_var->bool_array_value) {
|
||||
out_param_var->bool_array_value =
|
||||
allocator.allocate(sizeof(rcl_bool_array_t), allocator.state);
|
||||
if (NULL == out_param_var->bool_array_value) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
goto fail;
|
||||
}
|
||||
if (0U != param_var->bool_array_value->size) {
|
||||
out_param_var->bool_array_value->values = allocator.allocate(
|
||||
sizeof(bool) * param_var->bool_array_value->size, allocator.state);
|
||||
if (NULL == out_param_var->bool_array_value->values) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
goto fail;
|
||||
}
|
||||
memcpy(
|
||||
out_param_var->bool_array_value->values,
|
||||
param_var->bool_array_value->values,
|
||||
sizeof(bool) * param_var->bool_array_value->size);
|
||||
} else {
|
||||
out_param_var->bool_array_value->values = NULL;
|
||||
}
|
||||
out_param_var->bool_array_value->size = param_var->bool_array_value->size;
|
||||
} else if (NULL != param_var->integer_array_value) {
|
||||
out_param_var->integer_array_value =
|
||||
allocator.allocate(sizeof(rcl_int64_array_t), allocator.state);
|
||||
if (NULL == out_param_var->integer_array_value) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
goto fail;
|
||||
}
|
||||
if (0U != param_var->integer_array_value->size) {
|
||||
out_param_var->integer_array_value->values = allocator.allocate(
|
||||
sizeof(int64_t) * param_var->integer_array_value->size, allocator.state);
|
||||
if (NULL == out_param_var->integer_array_value->values) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
goto fail;
|
||||
}
|
||||
memcpy(
|
||||
out_param_var->integer_array_value->values,
|
||||
param_var->integer_array_value->values,
|
||||
sizeof(int64_t) * param_var->integer_array_value->size);
|
||||
} else {
|
||||
out_param_var->integer_array_value->values = NULL;
|
||||
}
|
||||
out_param_var->integer_array_value->size = param_var->integer_array_value->size;
|
||||
} else if (NULL != param_var->double_array_value) {
|
||||
out_param_var->double_array_value =
|
||||
allocator.allocate(sizeof(rcl_double_array_t), allocator.state);
|
||||
if (NULL == out_param_var->double_array_value) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
goto fail;
|
||||
}
|
||||
if (0U != param_var->double_array_value->size) {
|
||||
out_param_var->double_array_value->values = allocator.allocate(
|
||||
sizeof(double) * param_var->double_array_value->size, allocator.state);
|
||||
if (NULL == out_param_var->double_array_value->values) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
goto fail;
|
||||
}
|
||||
memcpy(
|
||||
out_param_var->double_array_value->values,
|
||||
param_var->double_array_value->values,
|
||||
sizeof(double) * param_var->double_array_value->size);
|
||||
} else {
|
||||
out_param_var->double_array_value->values = NULL;
|
||||
}
|
||||
out_param_var->double_array_value->size = param_var->double_array_value->size;
|
||||
} else if (NULL != param_var->string_array_value) {
|
||||
out_param_var->string_array_value =
|
||||
allocator.allocate(sizeof(rcutils_string_array_t), allocator.state);
|
||||
if (NULL == param_var->string_array_value) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
goto fail;
|
||||
}
|
||||
*(out_param_var->string_array_value) = rcutils_get_zero_initialized_string_array();
|
||||
ret = rcutils_string_array_init(
|
||||
out_param_var->string_array_value,
|
||||
param_var->string_array_value->size,
|
||||
&(param_var->string_array_value->allocator));
|
||||
if (RCUTILS_RET_OK != ret) {
|
||||
if (RCUTILS_RET_BAD_ALLOC == ret) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
}
|
||||
goto fail;
|
||||
}
|
||||
for (size_t str_idx = 0U; str_idx < param_var->string_array_value->size; ++str_idx) {
|
||||
out_param_var->string_array_value->data[str_idx] = rcutils_strdup(
|
||||
param_var->string_array_value->data[str_idx],
|
||||
out_param_var->string_array_value->allocator);
|
||||
if (NULL == out_param_var->string_array_value->data[str_idx]) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
/// Nothing to do to keep pclint happy
|
||||
}
|
||||
}
|
||||
}
|
||||
return out_params_st;
|
||||
|
||||
fail:
|
||||
rcl_yaml_node_struct_fini(out_params_st);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
||||
///
|
||||
/// Free param structure
|
||||
/// NOTE: If there is an error, would recommend just to safely exit the process instead
|
||||
|
@ -1574,6 +1754,10 @@ bool rcl_parse_yaml_value(
|
|||
RCUTILS_CHECK_ARGUMENT_FOR_NULL(param_name, false);
|
||||
RCUTILS_CHECK_ARGUMENT_FOR_NULL(yaml_value, false);
|
||||
|
||||
if (0U == strlen(node_name) || 0U == strlen(param_name) || 0U == strlen(yaml_value)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (NULL == params_st) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Pass an initialized parameter structure");
|
||||
return false;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue