Increase rcl_yaml_param_parser test coverage (#656)
* Cleanup and address issues in parser.c Signed-off-by: Stephen Brawner <stephenbrawner@verbsurgical.com> squash! Cleanup and address issues in parser.c * Increase test coverage of parser Signed-off-by: Stephen Brawner <stephenbrawner@verbsurgical.com> * PR Fixup Signed-off-by: Stephen Brawner <stephenbrawner@verbsurgical.com> * PR Fixup Signed-off-by: Stephen Brawner <stephenbrawner@verbsurgical.com> Co-authored-by: Stephen Brawner <stephenbrawner@verbsurgical.com>
This commit is contained in:
parent
7146919c3f
commit
65c2d46ee0
5 changed files with 742 additions and 113 deletions
|
@ -63,6 +63,18 @@ if(BUILD_TESTING)
|
|||
PRIVATE ${osrf_testing_tools_cpp_INCLUDE_DIRS})
|
||||
endif()
|
||||
|
||||
ament_add_gtest(test_parser
|
||||
test/test_parser.cpp
|
||||
WORKING_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}"
|
||||
)
|
||||
if(TARGET test_parser)
|
||||
ament_target_dependencies(test_parser
|
||||
"rcutils"
|
||||
"osrf_testing_tools_cpp"
|
||||
)
|
||||
target_link_libraries(test_parser ${PROJECT_NAME})
|
||||
endif()
|
||||
|
||||
endif()
|
||||
|
||||
ament_export_dependencies(ament_cmake libyaml_vendor)
|
||||
|
|
|
@ -76,6 +76,14 @@ static rcutils_ret_t node_params_init(
|
|||
rcl_node_params_t * node_params,
|
||||
const rcutils_allocator_t allocator);
|
||||
|
||||
static void rcl_yaml_variant_fini(
|
||||
rcl_variant_t * param_var,
|
||||
const rcutils_allocator_t allocator);
|
||||
|
||||
static void rcl_yaml_node_params_fini(
|
||||
rcl_node_params_t * node_params,
|
||||
const rcutils_allocator_t allocator);
|
||||
|
||||
static rcutils_ret_t add_val_to_bool_arr(
|
||||
rcl_bool_array_t * const val_array,
|
||||
bool * value,
|
||||
|
@ -267,7 +275,7 @@ static rcutils_ret_t rem_name_from_ns(
|
|||
next_str = strstr(cur_ns, sep_str);
|
||||
while (NULL != next_str) {
|
||||
if (next_str > end_ptr) {
|
||||
RCUTILS_SET_ERROR_MSG("Internal error. Crossing arrau boundary");
|
||||
RCUTILS_SET_ERROR_MSG("Internal error. Crossing array boundary");
|
||||
return RCUTILS_RET_ERROR;
|
||||
}
|
||||
last_idx = next_str;
|
||||
|
@ -311,14 +319,20 @@ static rcutils_ret_t replace_ns(
|
|||
if (NULL != ns_tracker->node_ns) {
|
||||
allocator.deallocate(ns_tracker->node_ns, allocator.state);
|
||||
}
|
||||
ns_tracker->node_ns = new_ns;
|
||||
ns_tracker->node_ns = rcutils_strdup(new_ns, allocator);
|
||||
if (NULL == ns_tracker->node_ns) {
|
||||
return RCUTILS_RET_BAD_ALLOC;
|
||||
}
|
||||
ns_tracker->num_node_ns = new_ns_count;
|
||||
break;
|
||||
case NS_TYPE_PARAM:
|
||||
if (NULL != ns_tracker->parameter_ns) {
|
||||
allocator.deallocate(ns_tracker->parameter_ns, allocator.state);
|
||||
}
|
||||
ns_tracker->parameter_ns = new_ns;
|
||||
ns_tracker->parameter_ns = rcutils_strdup(new_ns, allocator);
|
||||
if (NULL == ns_tracker->parameter_ns) {
|
||||
return RCUTILS_RET_BAD_ALLOC;
|
||||
}
|
||||
ns_tracker->num_parameter_ns = new_ns_count;
|
||||
break;
|
||||
default:
|
||||
|
@ -349,6 +363,7 @@ static rcutils_ret_t node_params_init(
|
|||
MAX_NUM_PARAMS_PER_NODE, sizeof(rcl_variant_t), allocator.state);
|
||||
if (NULL == node_params->parameter_values) {
|
||||
allocator.deallocate(node_params->parameter_names, allocator.state);
|
||||
node_params->parameter_names = NULL;
|
||||
return RCUTILS_RET_BAD_ALLOC;
|
||||
}
|
||||
|
||||
|
@ -364,15 +379,17 @@ rcl_params_t * rcl_yaml_node_struct_init(
|
|||
RCUTILS_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return NULL);
|
||||
rcl_params_t * params_st = allocator.zero_allocate(1, sizeof(rcl_params_t), allocator.state);
|
||||
if (NULL == params_st) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
params_st->allocator = allocator;
|
||||
|
||||
params_st->node_names = allocator.zero_allocate(
|
||||
MAX_NUM_NODE_ENTRIES, sizeof(char *), allocator.state);
|
||||
if (NULL == params_st->node_names) {
|
||||
rcl_yaml_node_struct_fini(params_st);
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
@ -380,13 +397,10 @@ rcl_params_t * rcl_yaml_node_struct_init(
|
|||
MAX_NUM_NODE_ENTRIES, sizeof(rcl_node_params_t), allocator.state);
|
||||
if (NULL == params_st->params) {
|
||||
rcl_yaml_node_struct_fini(params_st);
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
params_st->num_nodes = 0U;
|
||||
params_st->allocator = allocator;
|
||||
|
||||
return params_st;
|
||||
}
|
||||
|
||||
|
@ -402,7 +416,7 @@ rcl_params_t * rcl_yaml_node_struct_copy(
|
|||
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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
@ -411,7 +425,7 @@ rcl_params_t * rcl_yaml_node_struct_copy(
|
|||
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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
goto fail;
|
||||
}
|
||||
out_params_st->num_nodes++;
|
||||
|
@ -421,7 +435,7 @@ rcl_params_t * rcl_yaml_node_struct_copy(
|
|||
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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
}
|
||||
goto fail;
|
||||
}
|
||||
|
@ -429,7 +443,7 @@ rcl_params_t * rcl_yaml_node_struct_copy(
|
|||
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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
goto fail;
|
||||
}
|
||||
out_node_params_st->num_params++;
|
||||
|
@ -439,21 +453,21 @@ rcl_params_t * rcl_yaml_node_struct_copy(
|
|||
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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
goto fail;
|
||||
}
|
||||
*(out_param_var->double_value) = *(param_var->double_value);
|
||||
|
@ -461,21 +475,21 @@ rcl_params_t * rcl_yaml_node_struct_copy(
|
|||
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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
goto fail;
|
||||
}
|
||||
memcpy(
|
||||
|
@ -490,14 +504,14 @@ rcl_params_t * rcl_yaml_node_struct_copy(
|
|||
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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
goto fail;
|
||||
}
|
||||
memcpy(
|
||||
|
@ -512,14 +526,14 @@ rcl_params_t * rcl_yaml_node_struct_copy(
|
|||
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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
goto fail;
|
||||
}
|
||||
memcpy(
|
||||
|
@ -533,8 +547,8 @@ rcl_params_t * rcl_yaml_node_struct_copy(
|
|||
} 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");
|
||||
if (NULL == out_param_var->string_array_value) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
goto fail;
|
||||
}
|
||||
*(out_param_var->string_array_value) = rcutils_get_zero_initialized_string_array();
|
||||
|
@ -544,7 +558,7 @@ rcl_params_t * rcl_yaml_node_struct_copy(
|
|||
&(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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
}
|
||||
goto fail;
|
||||
}
|
||||
|
@ -553,7 +567,7 @@ rcl_params_t * rcl_yaml_node_struct_copy(
|
|||
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");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
goto fail;
|
||||
}
|
||||
}
|
||||
|
@ -569,39 +583,14 @@ fail:
|
|||
return NULL;
|
||||
}
|
||||
|
||||
|
||||
///
|
||||
/// Free param structure
|
||||
/// NOTE: If there is an error, would recommend just to safely exit the process instead
|
||||
/// of calling this free function and continuing
|
||||
///
|
||||
void rcl_yaml_node_struct_fini(
|
||||
rcl_params_t * params_st)
|
||||
void rcl_yaml_variant_fini(
|
||||
rcl_variant_t * param_var,
|
||||
const rcutils_allocator_t allocator)
|
||||
{
|
||||
if (NULL == params_st) {
|
||||
if (NULL == param_var) {
|
||||
return;
|
||||
}
|
||||
rcutils_allocator_t allocator = params_st->allocator;
|
||||
for (size_t node_idx = 0U; node_idx < params_st->num_nodes; node_idx++) {
|
||||
char * node_name = params_st->node_names[node_idx];
|
||||
if (NULL != node_name) {
|
||||
allocator.deallocate(node_name, allocator.state);
|
||||
}
|
||||
|
||||
if (NULL != params_st->params) {
|
||||
rcl_node_params_t * node_params_st = &(params_st->params[node_idx]);
|
||||
for (size_t parameter_idx = 0U; parameter_idx < node_params_st->num_params; parameter_idx++) {
|
||||
if (
|
||||
(NULL != node_params_st->parameter_names) &&
|
||||
(NULL != node_params_st->parameter_values))
|
||||
{
|
||||
char * param_name = node_params_st->parameter_names[parameter_idx];
|
||||
rcl_variant_t * param_var = &(node_params_st->parameter_values[parameter_idx]);
|
||||
if (NULL != param_name) {
|
||||
allocator.deallocate(param_name, allocator.state);
|
||||
}
|
||||
|
||||
if (NULL != param_var) {
|
||||
if (NULL != param_var->bool_value) {
|
||||
allocator.deallocate(param_var->bool_value, allocator.state);
|
||||
} else if (NULL != param_var->integer_value) {
|
||||
|
@ -634,25 +623,75 @@ void rcl_yaml_node_struct_fini(
|
|||
} else {
|
||||
/// Nothing to do to keep pclint happy
|
||||
}
|
||||
} // if (param_var)
|
||||
}
|
||||
} // for (parameter_idx)
|
||||
if (NULL != node_params_st->parameter_values) {
|
||||
allocator.deallocate(node_params_st->parameter_values, allocator.state);
|
||||
|
||||
void rcl_yaml_node_params_fini(
|
||||
rcl_node_params_t * node_params_st,
|
||||
const rcutils_allocator_t allocator)
|
||||
{
|
||||
if (NULL == node_params_st) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (NULL != node_params_st->parameter_names) {
|
||||
allocator.deallocate(node_params_st->parameter_names, allocator.state);
|
||||
for (size_t parameter_idx = 0U; parameter_idx < node_params_st->num_params;
|
||||
parameter_idx++)
|
||||
{
|
||||
char * param_name = node_params_st->parameter_names[parameter_idx];
|
||||
if (NULL != param_name) {
|
||||
allocator.deallocate(param_name, allocator.state);
|
||||
}
|
||||
} // if (params)
|
||||
} // for (node_idx)
|
||||
}
|
||||
allocator.deallocate(node_params_st->parameter_names, allocator.state);
|
||||
node_params_st->parameter_names = NULL;
|
||||
}
|
||||
|
||||
if (NULL != node_params_st->parameter_values) {
|
||||
for (size_t parameter_idx = 0U; parameter_idx < node_params_st->num_params;
|
||||
parameter_idx++)
|
||||
{
|
||||
rcl_yaml_variant_fini(&(node_params_st->parameter_values[parameter_idx]), allocator);
|
||||
}
|
||||
|
||||
allocator.deallocate(node_params_st->parameter_values, allocator.state);
|
||||
node_params_st->parameter_values = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
///
|
||||
/// Free param structure
|
||||
/// NOTE: If there is an error, would recommend just to safely exit the process instead
|
||||
/// of calling this free function and continuing
|
||||
///
|
||||
void rcl_yaml_node_struct_fini(
|
||||
rcl_params_t * params_st)
|
||||
{
|
||||
if (NULL == params_st) {
|
||||
return;
|
||||
}
|
||||
rcutils_allocator_t allocator = params_st->allocator;
|
||||
|
||||
if (NULL != params_st->node_names) {
|
||||
for (size_t node_idx = 0U; node_idx < params_st->num_nodes; node_idx++) {
|
||||
char * node_name = params_st->node_names[node_idx];
|
||||
if (NULL != node_name) {
|
||||
allocator.deallocate(node_name, allocator.state);
|
||||
}
|
||||
}
|
||||
|
||||
allocator.deallocate(params_st->node_names, allocator.state);
|
||||
params_st->node_names = NULL;
|
||||
}
|
||||
|
||||
if (NULL != params_st->params) {
|
||||
for (size_t node_idx = 0U; node_idx < params_st->num_nodes; node_idx++) {
|
||||
rcl_yaml_node_params_fini(&(params_st->params[node_idx]), allocator);
|
||||
} // for (node_idx)
|
||||
|
||||
allocator.deallocate(params_st->params, allocator.state);
|
||||
params_st->params = NULL;
|
||||
}
|
||||
} // if (params)
|
||||
|
||||
params_st->num_nodes = 0U;
|
||||
allocator.deallocate(params_st, allocator.state);
|
||||
}
|
||||
|
@ -715,6 +754,10 @@ static rcutils_ret_t find_parameter(
|
|||
}
|
||||
// Parameter not found, add it.
|
||||
rcutils_allocator_t allocator = param_st->allocator;
|
||||
if (NULL != node_param_st->parameter_names[*parameter_idx]) {
|
||||
param_st->allocator.deallocate(
|
||||
node_param_st->parameter_names[*parameter_idx], param_st->allocator.state);
|
||||
}
|
||||
node_param_st->parameter_names[*parameter_idx] = rcutils_strdup(parameter_name, allocator);
|
||||
if (NULL == node_param_st->parameter_names[*parameter_idx]) {
|
||||
return RCUTILS_RET_BAD_ALLOC;
|
||||
|
@ -844,14 +887,15 @@ static rcutils_ret_t add_val_to_bool_arr(
|
|||
|
||||
if (NULL == val_array->values) {
|
||||
val_array->values = value;
|
||||
val_array->size++;
|
||||
val_array->size = 1;
|
||||
} else {
|
||||
/// Increase the array size by one and add the new value
|
||||
bool * tmp_arr = val_array->values;
|
||||
val_array->values = allocator.zero_allocate(
|
||||
val_array->size + 1U, sizeof(bool), allocator.state);
|
||||
if (NULL == val_array->values) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
val_array->values = tmp_arr;
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
return RCUTILS_RET_BAD_ALLOC;
|
||||
}
|
||||
memmove(val_array->values, tmp_arr, (val_array->size * sizeof(bool)));
|
||||
|
@ -885,7 +929,8 @@ static rcutils_ret_t add_val_to_int_arr(
|
|||
val_array->values = allocator.zero_allocate(
|
||||
val_array->size + 1U, sizeof(int64_t), allocator.state);
|
||||
if (NULL == val_array->values) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
val_array->values = tmp_arr;
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
return RCUTILS_RET_BAD_ALLOC;
|
||||
}
|
||||
memmove(val_array->values, tmp_arr, (val_array->size * sizeof(int64_t)));
|
||||
|
@ -919,7 +964,8 @@ static rcutils_ret_t add_val_to_double_arr(
|
|||
val_array->values = allocator.zero_allocate(
|
||||
val_array->size + 1U, sizeof(double), allocator.state);
|
||||
if (NULL == val_array->values) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
val_array->values = tmp_arr;
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
return RCUTILS_RET_BAD_ALLOC;
|
||||
}
|
||||
memmove(val_array->values, tmp_arr, (val_array->size * sizeof(double)));
|
||||
|
@ -956,7 +1002,7 @@ static rcutils_ret_t add_val_to_string_arr(
|
|||
val_array->data,
|
||||
((val_array->size + 1U) * sizeof(char *)), allocator.state);
|
||||
if (NULL == val_array->data) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
return RCUTILS_RET_BAD_ALLOC;
|
||||
}
|
||||
val_array->data[val_array->size] = value;
|
||||
|
@ -1146,14 +1192,24 @@ static rcutils_ret_t parse_value(
|
|||
break;
|
||||
case DATA_TYPE_BOOL:
|
||||
if (false == is_seq) {
|
||||
if (NULL != param_value->bool_value) {
|
||||
// Overwriting, deallocate original
|
||||
allocator.deallocate(param_value->bool_value, allocator.state);
|
||||
}
|
||||
param_value->bool_value = (bool *)ret_val;
|
||||
} else {
|
||||
if (DATA_TYPE_UNKNOWN == *seq_data_type) {
|
||||
*seq_data_type = val_type;
|
||||
if (NULL != param_value->bool_array_value) {
|
||||
allocator.deallocate(param_value->bool_array_value->values, allocator.state);
|
||||
allocator.deallocate(param_value->bool_array_value, allocator.state);
|
||||
param_value->bool_array_value = NULL;
|
||||
}
|
||||
param_value->bool_array_value =
|
||||
allocator.zero_allocate(1U, sizeof(rcl_bool_array_t), allocator.state);
|
||||
if (NULL == param_value->bool_array_value) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
allocator.deallocate(ret_val, allocator.state);
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
ret = RCUTILS_RET_BAD_ALLOC;
|
||||
break;
|
||||
}
|
||||
|
@ -1177,14 +1233,24 @@ static rcutils_ret_t parse_value(
|
|||
break;
|
||||
case DATA_TYPE_INT64:
|
||||
if (false == is_seq) {
|
||||
if (NULL != param_value->integer_value) {
|
||||
// Overwriting, deallocate original
|
||||
allocator.deallocate(param_value->integer_value, allocator.state);
|
||||
}
|
||||
param_value->integer_value = (int64_t *)ret_val;
|
||||
} else {
|
||||
if (DATA_TYPE_UNKNOWN == *seq_data_type) {
|
||||
if (NULL != param_value->integer_array_value) {
|
||||
allocator.deallocate(param_value->integer_array_value->values, allocator.state);
|
||||
allocator.deallocate(param_value->integer_array_value, allocator.state);
|
||||
param_value->integer_array_value = NULL;
|
||||
}
|
||||
*seq_data_type = val_type;
|
||||
param_value->integer_array_value =
|
||||
allocator.zero_allocate(1U, sizeof(rcl_int64_array_t), allocator.state);
|
||||
if (NULL == param_value->integer_array_value) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
allocator.deallocate(ret_val, allocator.state);
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
ret = RCUTILS_RET_BAD_ALLOC;
|
||||
break;
|
||||
}
|
||||
|
@ -1208,14 +1274,24 @@ static rcutils_ret_t parse_value(
|
|||
break;
|
||||
case DATA_TYPE_DOUBLE:
|
||||
if (false == is_seq) {
|
||||
if (NULL != param_value->double_value) {
|
||||
// Overwriting, deallocate original
|
||||
allocator.deallocate(param_value->double_value, allocator.state);
|
||||
}
|
||||
param_value->double_value = (double *)ret_val;
|
||||
} else {
|
||||
if (DATA_TYPE_UNKNOWN == *seq_data_type) {
|
||||
if (NULL != param_value->double_array_value) {
|
||||
allocator.deallocate(param_value->double_array_value->values, allocator.state);
|
||||
allocator.deallocate(param_value->double_array_value, allocator.state);
|
||||
param_value->double_array_value = NULL;
|
||||
}
|
||||
*seq_data_type = val_type;
|
||||
param_value->double_array_value =
|
||||
allocator.zero_allocate(1U, sizeof(rcl_double_array_t), allocator.state);
|
||||
if (NULL == param_value->double_array_value) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
allocator.deallocate(ret_val, allocator.state);
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
ret = RCUTILS_RET_BAD_ALLOC;
|
||||
break;
|
||||
}
|
||||
|
@ -1239,17 +1315,27 @@ static rcutils_ret_t parse_value(
|
|||
break;
|
||||
case DATA_TYPE_STRING:
|
||||
if (false == is_seq) {
|
||||
if (NULL != param_value->string_value) {
|
||||
// Overwriting, deallocate original
|
||||
allocator.deallocate(param_value->string_value, allocator.state);
|
||||
}
|
||||
param_value->string_value = (char *)ret_val;
|
||||
} else {
|
||||
if (DATA_TYPE_UNKNOWN == *seq_data_type) {
|
||||
if (NULL != param_value->string_array_value) {
|
||||
if (RCUTILS_RET_OK != rcutils_string_array_fini(param_value->string_array_value)) {
|
||||
// Log and continue ...
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error deallocating string array");
|
||||
}
|
||||
allocator.deallocate(param_value->string_array_value, allocator.state);
|
||||
param_value->string_array_value = NULL;
|
||||
}
|
||||
*seq_data_type = val_type;
|
||||
param_value->string_array_value =
|
||||
allocator.zero_allocate(1U, sizeof(rcutils_string_array_t), allocator.state);
|
||||
if (NULL == param_value->string_array_value) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem");
|
||||
if (NULL != ret_val) {
|
||||
allocator.deallocate(ret_val, allocator.state);
|
||||
}
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n");
|
||||
ret = RCUTILS_RET_BAD_ALLOC;
|
||||
break;
|
||||
}
|
||||
|
@ -1275,6 +1361,7 @@ static rcutils_ret_t parse_value(
|
|||
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(
|
||||
"Unknown data type of value %s at line %d", value, line_num);
|
||||
ret = RCUTILS_RET_ERROR;
|
||||
allocator.deallocate(ret_val, allocator.state);
|
||||
break;
|
||||
}
|
||||
return ret;
|
||||
|
@ -1361,8 +1448,8 @@ static rcutils_ret_t parse_key(
|
|||
break;
|
||||
case MAP_PARAMS_LVL:
|
||||
{
|
||||
char * parameter_ns;
|
||||
char * param_name;
|
||||
char * parameter_ns = NULL;
|
||||
char * param_name = NULL;
|
||||
|
||||
/// If it is a new map, the previous key is param namespace
|
||||
if (true == *is_new_map) {
|
||||
|
@ -1422,6 +1509,11 @@ static rcutils_ret_t parse_key(
|
|||
memmove((param_name + params_ns_len + 1U), value, param_name_len);
|
||||
param_name[tot_len - 1U] = '\0';
|
||||
|
||||
if (NULL != params_st->params[*node_idx].parameter_names[*parameter_idx]) {
|
||||
// This memory was allocated in find_parameter(), and its pointer is being overwritten
|
||||
allocator.deallocate(
|
||||
params_st->params[*node_idx].parameter_names[*parameter_idx], allocator.state);
|
||||
}
|
||||
params_st->params[*node_idx].parameter_names[*parameter_idx] = param_name;
|
||||
}
|
||||
}
|
||||
|
@ -1701,7 +1793,6 @@ bool rcl_parse_yaml_file(
|
|||
|
||||
yaml_parser_delete(&parser);
|
||||
|
||||
if (RCUTILS_RET_OK != ret) {
|
||||
rcutils_allocator_t allocator = params_st->allocator;
|
||||
if (NULL != ns_tracker.node_ns) {
|
||||
allocator.deallocate(ns_tracker.node_ns, allocator.state);
|
||||
|
@ -1709,6 +1800,8 @@ bool rcl_parse_yaml_file(
|
|||
if (NULL != ns_tracker.parameter_ns) {
|
||||
allocator.deallocate(ns_tracker.parameter_ns, allocator.state);
|
||||
}
|
||||
|
||||
if (RCUTILS_RET_OK != ret) {
|
||||
rcl_yaml_node_struct_fini(params_st);
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -44,12 +44,14 @@ TEST(test_parser, correct_syntax) {
|
|||
ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path;
|
||||
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
|
||||
ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str;
|
||||
|
||||
// Parse correct_config.yaml as expected
|
||||
bool res = rcl_parse_yaml_file(path, params_hdl);
|
||||
ASSERT_TRUE(res) << rcutils_get_error_string().str;
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
rcl_yaml_node_struct_fini(params_hdl);
|
||||
});
|
||||
bool res = rcl_parse_yaml_file(path, params_hdl);
|
||||
ASSERT_TRUE(res) << rcutils_get_error_string().str;
|
||||
|
||||
char * another_path = rcutils_join_path(test_path, "overlay.yaml", allocator);
|
||||
ASSERT_TRUE(NULL != another_path) << rcutils_get_error_string().str;
|
||||
|
@ -58,6 +60,8 @@ TEST(test_parser, correct_syntax) {
|
|||
allocator.deallocate(another_path, allocator.state);
|
||||
});
|
||||
ASSERT_TRUE(rcutils_exists(another_path)) << "No test YAML file found at " << another_path;
|
||||
|
||||
// Parse overlay.yaml using the same params_hdl, expect them to merge nicely
|
||||
res = rcl_parse_yaml_file(another_path, params_hdl);
|
||||
ASSERT_TRUE(res) << rcutils_get_error_string().str;
|
||||
|
||||
|
@ -311,6 +315,7 @@ TEST(test_file_parser, seq_map1) {
|
|||
bool res = rcl_parse_yaml_file(path, params_hdl);
|
||||
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
|
||||
EXPECT_FALSE(res);
|
||||
// No cleanup, rcl_parse_yaml_file takes care of that if it fails.
|
||||
}
|
||||
|
||||
TEST(test_file_parser, seq_map2) {
|
||||
|
@ -335,6 +340,7 @@ TEST(test_file_parser, seq_map2) {
|
|||
bool res = rcl_parse_yaml_file(path, params_hdl);
|
||||
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
|
||||
EXPECT_FALSE(res);
|
||||
// No cleanup, rcl_parse_yaml_file takes care of that if it fails
|
||||
}
|
||||
|
||||
TEST(test_file_parser, params_with_no_node) {
|
||||
|
@ -359,6 +365,7 @@ TEST(test_file_parser, params_with_no_node) {
|
|||
bool res = rcl_parse_yaml_file(path, params_hdl);
|
||||
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
|
||||
EXPECT_FALSE(res);
|
||||
// No cleanup, rcl_parse_yaml_file takes care of that if it fails.
|
||||
}
|
||||
|
||||
TEST(test_file_parser, no_alias_support) {
|
||||
|
@ -383,6 +390,7 @@ TEST(test_file_parser, no_alias_support) {
|
|||
bool res = rcl_parse_yaml_file(path, params_hdl);
|
||||
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
|
||||
EXPECT_FALSE(res);
|
||||
// No cleanup, rcl_parse_yaml_file takes care of that if it fails.
|
||||
}
|
||||
|
||||
TEST(test_file_parser, empty_string) {
|
||||
|
@ -404,6 +412,10 @@ TEST(test_file_parser, empty_string) {
|
|||
ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path;
|
||||
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
|
||||
ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str;
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
rcl_yaml_node_struct_fini(params_hdl);
|
||||
});
|
||||
bool res = rcl_parse_yaml_file(path, params_hdl);
|
||||
EXPECT_TRUE(res) << rcutils_get_error_string().str;
|
||||
rcl_yaml_node_struct_print(params_hdl);
|
||||
|
@ -431,6 +443,7 @@ TEST(test_file_parser, no_value1) {
|
|||
bool res = rcl_parse_yaml_file(path, params_hdl);
|
||||
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
|
||||
EXPECT_FALSE(res);
|
||||
// No cleanup, rcl_parse_yaml_file takes care of that if it fails.
|
||||
}
|
||||
|
||||
TEST(test_file_parser, indented_ns) {
|
||||
|
@ -455,6 +468,7 @@ TEST(test_file_parser, indented_ns) {
|
|||
bool res = rcl_parse_yaml_file(path, params_hdl);
|
||||
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
|
||||
EXPECT_FALSE(res);
|
||||
// No cleanup, rcl_parse_yaml_file takes care of that if it fails.
|
||||
}
|
||||
|
||||
// Regression test for https://github.com/ros2/rcl/issues/419
|
||||
|
@ -480,6 +494,7 @@ TEST(test_file_parser, maximum_number_parameters) {
|
|||
bool res = rcl_parse_yaml_file(path, params_hdl);
|
||||
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
|
||||
EXPECT_FALSE(res);
|
||||
// No cleanup, rcl_parse_yaml_file takes care of that if it fails.
|
||||
}
|
||||
|
||||
int32_t main(int32_t argc, char ** argv)
|
||||
|
|
363
rcl_yaml_param_parser/test/test_parser.cpp
Normal file
363
rcl_yaml_param_parser/test/test_parser.cpp
Normal file
|
@ -0,0 +1,363 @@
|
|||
// Copyright 2020 Open Source Robotics Foundation, Inc.
|
||||
//
|
||||
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||
// you may not use this file except in compliance with the License.
|
||||
// You may obtain a copy of the License at
|
||||
//
|
||||
// http://www.apache.org/licenses/LICENSE-2.0
|
||||
//
|
||||
// Unless required by applicable law or agreed to in writing, software
|
||||
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
// See the License for the specific language governing permissions and
|
||||
// limitations under the License.
|
||||
|
||||
#include "gtest/gtest.h"
|
||||
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
||||
#include "rcl_yaml_param_parser/parser.h"
|
||||
#include "rcutils/error_handling.h"
|
||||
#include "rcutils/filesystem.h"
|
||||
#include "./time_bomb_allocator_testing_utils.h"
|
||||
|
||||
TEST(RclYamlParamParser, node_init_fini) {
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
|
||||
rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator);
|
||||
EXPECT_NE(params_st, nullptr);
|
||||
rcl_yaml_node_struct_fini(params_st);
|
||||
|
||||
allocator = get_time_bomb_allocator();
|
||||
// Bad alloc of params_st
|
||||
set_time_bomb_allocator_calloc_count(allocator, 0);
|
||||
// This cleans up after itself if it fails so no need to call fini()
|
||||
EXPECT_EQ(rcl_yaml_node_struct_init(allocator), nullptr);
|
||||
|
||||
// Bad alloc of params_st->node_names
|
||||
set_time_bomb_allocator_calloc_count(allocator, 1);
|
||||
EXPECT_EQ(rcl_yaml_node_struct_init(allocator), nullptr);
|
||||
|
||||
// Bad alloc of params_st->params
|
||||
set_time_bomb_allocator_calloc_count(allocator, 2);
|
||||
EXPECT_EQ(rcl_yaml_node_struct_init(allocator), nullptr);
|
||||
|
||||
// Check this doesn't die.
|
||||
rcl_yaml_node_struct_fini(nullptr);
|
||||
}
|
||||
|
||||
TEST(RclYamlParamParser, node_copy) {
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator);
|
||||
EXPECT_NE(params_st, nullptr);
|
||||
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(nullptr));
|
||||
|
||||
const char node_name[] = "node name";
|
||||
const char param_name[] = "param name";
|
||||
const char yaml_value[] = "true";
|
||||
EXPECT_TRUE(rcl_parse_yaml_value(node_name, param_name, yaml_value, params_st));
|
||||
|
||||
rcl_params_t * copy = rcl_yaml_node_struct_copy(params_st);
|
||||
EXPECT_NE(copy, nullptr);
|
||||
rcl_yaml_node_struct_fini(copy);
|
||||
|
||||
params_st->allocator = get_time_bomb_allocator();
|
||||
|
||||
// init of out_params_st fails
|
||||
set_time_bomb_allocator_calloc_count(params_st->allocator, 0);
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
|
||||
|
||||
set_time_bomb_allocator_calloc_count(params_st->allocator, 1);
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
|
||||
|
||||
constexpr int expected_num_calloc_calls = 5;
|
||||
for (int i = 0; i < expected_num_calloc_calls; ++i) {
|
||||
// Check various locations for allocation failures
|
||||
set_time_bomb_allocator_calloc_count(params_st->allocator, i);
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
|
||||
}
|
||||
// Check that the expected number of calloc calls occur
|
||||
set_time_bomb_allocator_calloc_count(params_st->allocator, expected_num_calloc_calls);
|
||||
copy = rcl_yaml_node_struct_copy(params_st);
|
||||
EXPECT_NE(nullptr, copy);
|
||||
rcl_yaml_node_struct_fini(copy);
|
||||
|
||||
// Reset calloc countdown
|
||||
set_time_bomb_allocator_calloc_count(params_st->allocator, -1);
|
||||
|
||||
constexpr int expected_num_malloc_calls = 3;
|
||||
for (int i = 0; i < expected_num_malloc_calls; ++i) {
|
||||
set_time_bomb_allocator_malloc_count(params_st->allocator, i);
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
|
||||
}
|
||||
|
||||
// Check that the expected number of malloc calls occur
|
||||
set_time_bomb_allocator_malloc_count(params_st->allocator, expected_num_malloc_calls);
|
||||
copy = rcl_yaml_node_struct_copy(params_st);
|
||||
EXPECT_NE(nullptr, copy);
|
||||
rcl_yaml_node_struct_fini(copy);
|
||||
|
||||
constexpr int num_malloc_calls_until_copy_param = 2;
|
||||
|
||||
// Check integer value
|
||||
int64_t temp_int = 42;
|
||||
if (params_st->params->parameter_values[0].bool_value != nullptr) {
|
||||
// Since this bool was allocated above in rcl_parse_yaml_value, it needs to be freed.
|
||||
params_st->allocator.deallocate(
|
||||
params_st->params->parameter_values[0].bool_value, params_st->allocator.state);
|
||||
params_st->params->parameter_values[0].bool_value = nullptr;
|
||||
}
|
||||
set_time_bomb_allocator_malloc_count(params_st->allocator, num_malloc_calls_until_copy_param);
|
||||
params_st->params->parameter_values[0].integer_value = &temp_int;
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
|
||||
params_st->params->parameter_values[0].integer_value = nullptr;
|
||||
|
||||
// Check double value
|
||||
double temp_double = 42.0;
|
||||
set_time_bomb_allocator_malloc_count(params_st->allocator, num_malloc_calls_until_copy_param);
|
||||
params_st->params->parameter_values[0].double_value = &temp_double;
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
|
||||
params_st->params->parameter_values[0].double_value = nullptr;
|
||||
|
||||
// Check string value
|
||||
char temp_string[] = "stringy string";
|
||||
set_time_bomb_allocator_malloc_count(params_st->allocator, num_malloc_calls_until_copy_param);
|
||||
params_st->params->parameter_values[0].string_value = temp_string;
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
|
||||
params_st->params->parameter_values[0].string_value = nullptr;
|
||||
|
||||
// Check bool_array_value array pointer is allocated
|
||||
bool bool_array[] = {true};
|
||||
rcl_bool_array_s temp_bool_array = {bool_array, 1};
|
||||
set_time_bomb_allocator_malloc_count(params_st->allocator, num_malloc_calls_until_copy_param);
|
||||
params_st->params->parameter_values[0].bool_array_value = &temp_bool_array;
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
|
||||
|
||||
// Check bool_array_value->values is allocated
|
||||
set_time_bomb_allocator_malloc_count(
|
||||
params_st->allocator, num_malloc_calls_until_copy_param + 1);
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
|
||||
|
||||
// Check bool_array_value->values is set to null if size is 0
|
||||
set_time_bomb_allocator_malloc_count(params_st->allocator, -1);
|
||||
params_st->params->parameter_values[0].bool_array_value->size = 0u;
|
||||
copy = rcl_yaml_node_struct_copy(params_st);
|
||||
EXPECT_NE(nullptr, copy);
|
||||
EXPECT_EQ(nullptr, copy->params->parameter_values[0].bool_array_value->values);
|
||||
rcl_yaml_node_struct_fini(copy);
|
||||
params_st->params->parameter_values[0].bool_array_value = nullptr;
|
||||
|
||||
// Check integer_array array pointer is allocated
|
||||
int64_t integer_array[] = {42};
|
||||
rcl_int64_array_s temp_integer_array = {integer_array, 1};
|
||||
set_time_bomb_allocator_malloc_count(params_st->allocator, num_malloc_calls_until_copy_param);
|
||||
params_st->params->parameter_values[0].integer_array_value = &temp_integer_array;
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
|
||||
|
||||
// Check integer_array->values is allocated
|
||||
set_time_bomb_allocator_malloc_count(
|
||||
params_st->allocator, num_malloc_calls_until_copy_param + 1);
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
|
||||
|
||||
// Check integer_array->values is set to null if size is 0
|
||||
params_st->params->parameter_values[0].integer_array_value->size = 0u;
|
||||
copy = rcl_yaml_node_struct_copy(params_st);
|
||||
EXPECT_NE(nullptr, copy);
|
||||
EXPECT_EQ(nullptr, copy->params->parameter_values[0].integer_array_value->values);
|
||||
rcl_yaml_node_struct_fini(copy);
|
||||
params_st->params->parameter_values[0].integer_array_value = nullptr;
|
||||
|
||||
|
||||
double double_array[] = {42.0};
|
||||
rcl_double_array_s temp_double_array = {double_array, 1};
|
||||
set_time_bomb_allocator_malloc_count(params_st->allocator, num_malloc_calls_until_copy_param);
|
||||
params_st->params->parameter_values[0].double_array_value = &temp_double_array;
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
|
||||
|
||||
set_time_bomb_allocator_malloc_count(
|
||||
params_st->allocator, num_malloc_calls_until_copy_param + 1);
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
|
||||
|
||||
params_st->params->parameter_values[0].double_array_value->size = 0u;
|
||||
copy = rcl_yaml_node_struct_copy(params_st);
|
||||
EXPECT_NE(nullptr, copy);
|
||||
EXPECT_EQ(nullptr, copy->params->parameter_values[0].double_array_value->values);
|
||||
rcl_yaml_node_struct_fini(copy);
|
||||
params_st->params->parameter_values[0].double_array_value = nullptr;
|
||||
|
||||
char s[] = "stringy string";
|
||||
char * string_array[] = {s};
|
||||
rcutils_string_array_t temp_string_array = {1, string_array, allocator};
|
||||
set_time_bomb_allocator_malloc_count(params_st->allocator, num_malloc_calls_until_copy_param);
|
||||
params_st->params->parameter_values[0].string_array_value = &temp_string_array;
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
|
||||
params_st->params->parameter_values[0].string_array_value = nullptr;
|
||||
|
||||
for (int i = 0; i < 5; ++i) {
|
||||
set_time_bomb_allocator_calloc_count(params_st->allocator, i);
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_copy(params_st));
|
||||
}
|
||||
|
||||
rcl_yaml_node_struct_fini(params_st);
|
||||
}
|
||||
// // This just tests a couple of basic failures that test_parse_yaml.cpp misses.
|
||||
// // See that file for more thorough testing of bad yaml files
|
||||
TEST(RclYamlParamParser, test_file) {
|
||||
// file path is null
|
||||
EXPECT_FALSE(rcl_parse_yaml_file(nullptr, nullptr));
|
||||
const char bad_file_path[] = "not_a_file.yaml";
|
||||
|
||||
// params_st is null
|
||||
EXPECT_FALSE(rcl_parse_yaml_file(bad_file_path, nullptr));
|
||||
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator);
|
||||
EXPECT_FALSE(rcl_parse_yaml_file(bad_file_path, params_st));
|
||||
|
||||
rcl_yaml_node_struct_fini(params_st);
|
||||
}
|
||||
|
||||
TEST(RclYamlParamParser, test_parse_yaml_value) {
|
||||
const char node_name[] = "node name";
|
||||
const char param_name[] = "param name";
|
||||
const char yaml_value[] = "true";
|
||||
const char empty_string[] = "\0";
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
|
||||
rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator);
|
||||
EXPECT_NE(params_st, nullptr);
|
||||
|
||||
// Check null arguments
|
||||
EXPECT_FALSE(rcl_parse_yaml_value(nullptr, param_name, yaml_value, params_st));
|
||||
EXPECT_FALSE(rcl_parse_yaml_value(node_name, nullptr, yaml_value, params_st));
|
||||
EXPECT_FALSE(rcl_parse_yaml_value(node_name, param_name, nullptr, params_st));
|
||||
EXPECT_FALSE(rcl_parse_yaml_value(node_name, param_name, yaml_value, nullptr));
|
||||
|
||||
// Check strings are empty
|
||||
EXPECT_FALSE(rcl_parse_yaml_value(empty_string, param_name, yaml_value, params_st));
|
||||
EXPECT_FALSE(rcl_parse_yaml_value(node_name, empty_string, yaml_value, params_st));
|
||||
EXPECT_FALSE(rcl_parse_yaml_value(node_name, param_name, empty_string, params_st));
|
||||
|
||||
// Check allocating params_st->node_names[*node_idx] fails
|
||||
params_st->allocator = get_time_bomb_allocator();
|
||||
set_time_bomb_allocator_malloc_count(params_st->allocator, 0);
|
||||
EXPECT_FALSE(rcl_parse_yaml_value(node_name, param_name, yaml_value, params_st));
|
||||
|
||||
// Check allocating node_params->parameter_names fails
|
||||
allocator = get_time_bomb_allocator();
|
||||
set_time_bomb_allocator_calloc_count(params_st->allocator, 0);
|
||||
EXPECT_FALSE(rcl_parse_yaml_value(node_name, param_name, yaml_value, params_st));
|
||||
|
||||
// Check allocating node_params->parameter_values fails
|
||||
allocator = get_time_bomb_allocator();
|
||||
set_time_bomb_allocator_calloc_count(params_st->allocator, 1);
|
||||
EXPECT_FALSE(rcl_parse_yaml_value(node_name, param_name, yaml_value, params_st));
|
||||
|
||||
allocator = rcutils_get_default_allocator();
|
||||
EXPECT_TRUE(rcl_parse_yaml_value(node_name, param_name, yaml_value, params_st));
|
||||
|
||||
rcl_yaml_node_struct_fini(params_st);
|
||||
}
|
||||
|
||||
TEST(RclYamlParamParser, test_yaml_node_struct_get) {
|
||||
const char node_name[] = "node name";
|
||||
const char param_name[] = "param name";
|
||||
const char yaml_value[] = "true";
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
|
||||
rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator);
|
||||
ASSERT_NE(params_st, nullptr);
|
||||
EXPECT_TRUE(rcl_parse_yaml_value(node_name, param_name, yaml_value, params_st));
|
||||
|
||||
// Check null arguments
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_get(nullptr, param_name, params_st));
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_get(node_name, nullptr, params_st));
|
||||
EXPECT_EQ(nullptr, rcl_yaml_node_struct_get(node_name, param_name, nullptr));
|
||||
|
||||
rcl_variant_t * result = rcl_yaml_node_struct_get(node_name, param_name, params_st);
|
||||
ASSERT_NE(nullptr, result->bool_value);
|
||||
EXPECT_TRUE(*result->bool_value);
|
||||
|
||||
EXPECT_EQ(nullptr, result->integer_value);
|
||||
EXPECT_EQ(nullptr, result->double_value);
|
||||
EXPECT_EQ(nullptr, result->string_value);
|
||||
EXPECT_EQ(nullptr, result->byte_array_value);
|
||||
EXPECT_EQ(nullptr, result->bool_array_value);
|
||||
EXPECT_EQ(nullptr, result->integer_array_value);
|
||||
EXPECT_EQ(nullptr, result->double_array_value);
|
||||
EXPECT_EQ(nullptr, result->string_array_value);
|
||||
rcl_yaml_node_struct_fini(params_st);
|
||||
}
|
||||
|
||||
// Just testing basic parameters, this is exercised more in test_parse_yaml.cpp
|
||||
TEST(RclYamlParamParser, test_yaml_node_struct_print) {
|
||||
rcl_yaml_node_struct_print(nullptr);
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator);
|
||||
rcl_yaml_node_struct_print(params_st);
|
||||
rcl_yaml_node_struct_fini(params_st);
|
||||
}
|
||||
|
||||
TEST(RclYamlParamParser, test_parse_file_with_bad_allocator) {
|
||||
char cur_dir[1024];
|
||||
rcutils_reset_error();
|
||||
EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)) << rcutils_get_error_string().str;
|
||||
rcutils_allocator_t allocator = rcutils_get_default_allocator();
|
||||
char * test_path = rcutils_join_path(cur_dir, "test", allocator);
|
||||
ASSERT_TRUE(NULL != test_path) << rcutils_get_error_string().str;
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
allocator.deallocate(test_path, allocator.state);
|
||||
});
|
||||
char * path = rcutils_join_path(test_path, "correct_config.yaml", allocator);
|
||||
ASSERT_TRUE(NULL != path) << rcutils_get_error_string().str;
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
allocator.deallocate(path, allocator.state);
|
||||
});
|
||||
ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path;
|
||||
|
||||
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
|
||||
EXPECT_TRUE(rcl_parse_yaml_file(path, params_hdl));
|
||||
rcl_yaml_node_struct_fini(params_hdl);
|
||||
params_hdl = NULL;
|
||||
|
||||
// Check sporadic failing malloc calls
|
||||
for (int i = 0; i < 100; ++i) {
|
||||
params_hdl = rcl_yaml_node_struct_init(get_time_bomb_allocator());
|
||||
ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str;
|
||||
|
||||
set_time_bomb_allocator_malloc_count(params_hdl->allocator, i);
|
||||
bool res = rcl_parse_yaml_file(path, params_hdl);
|
||||
// Not verifying res is true or false here, because eventually it will come back with an ok
|
||||
// result. We're just trying to make sure that bad allocations are properly handled
|
||||
if (res) {
|
||||
// This is already freed in the case of a non-ok error in rcl_parse_yaml_file
|
||||
rcl_yaml_node_struct_fini(params_hdl);
|
||||
params_hdl = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
// Check sporadic failing calloc calls
|
||||
for (int i = 0; i < 100; ++i) {
|
||||
params_hdl = rcl_yaml_node_struct_init(get_time_bomb_allocator());
|
||||
ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str;
|
||||
|
||||
set_time_bomb_allocator_calloc_count(params_hdl->allocator, i);
|
||||
|
||||
bool res = rcl_parse_yaml_file(path, params_hdl);
|
||||
// Not verifying res is true or false here, because eventually it will come back with an ok
|
||||
// result. We're just trying to make sure that bad allocations are properly handled
|
||||
if (res) {
|
||||
// This is already freed in the case of a non-ok error in rcl_parse_yaml_file
|
||||
rcl_yaml_node_struct_fini(params_hdl);
|
||||
params_hdl = NULL;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
int32_t main(int32_t argc, char ** argv)
|
||||
{
|
||||
::testing::InitGoogleTest(&argc, argv);
|
||||
return RUN_ALL_TESTS();
|
||||
}
|
146
rcl_yaml_param_parser/test/time_bomb_allocator_testing_utils.h
Normal file
146
rcl_yaml_param_parser/test/time_bomb_allocator_testing_utils.h
Normal file
|
@ -0,0 +1,146 @@
|
|||
// Copyright 2020 Open Source Robotics Foundation, Inc.
|
||||
//
|
||||
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||
// you may not use this file except in compliance with the License.
|
||||
// You may obtain a copy of the License at
|
||||
//
|
||||
// http://www.apache.org/licenses/LICENSE-2.0
|
||||
//
|
||||
// Unless required by applicable law or agreed to in writing, software
|
||||
// distributed under the License is distributed on an "AS IS" BASIS,
|
||||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
// See the License for the specific language governing permissions and
|
||||
// limitations under the License.
|
||||
|
||||
#ifndef TIME_BOMB_ALLOCATOR_TESTING_UTILS_H_
|
||||
#define TIME_BOMB_ALLOCATOR_TESTING_UTILS_H_
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
#include <stddef.h>
|
||||
|
||||
#include "rcutils/allocator.h"
|
||||
|
||||
typedef struct __time_bomb_allocator_state
|
||||
{
|
||||
// Set these to negative if you want to disable time bomb for the associated function call.
|
||||
int malloc_count_until_failure;
|
||||
int realloc_count_until_failure;
|
||||
int free_count_until_failure;
|
||||
int calloc_count_until_failure;
|
||||
} __time_bomb_allocator_state;
|
||||
|
||||
static void *
|
||||
time_bomb_malloc(size_t size, void * state)
|
||||
{
|
||||
if (((__time_bomb_allocator_state *)state)->malloc_count_until_failure >= 0 &&
|
||||
((__time_bomb_allocator_state *)state)->malloc_count_until_failure-- == 0)
|
||||
{
|
||||
printf("Malloc time bomb countdown reached 0, returning nullptr\n");
|
||||
return nullptr;
|
||||
}
|
||||
return rcutils_get_default_allocator().allocate(size, rcutils_get_default_allocator().state);
|
||||
}
|
||||
|
||||
static void *
|
||||
time_bomb_realloc(void * pointer, size_t size, void * state)
|
||||
{
|
||||
if (((__time_bomb_allocator_state *)state)->realloc_count_until_failure >= 0 &&
|
||||
((__time_bomb_allocator_state *)state)->realloc_count_until_failure-- == 0)
|
||||
{
|
||||
printf("Realloc time bomb countdown reached 0, returning nullptr\n");
|
||||
return nullptr;
|
||||
}
|
||||
return rcutils_get_default_allocator().reallocate(
|
||||
pointer, size, rcutils_get_default_allocator().state);
|
||||
}
|
||||
|
||||
static void
|
||||
time_bomb_free(void * pointer, void * state)
|
||||
{
|
||||
if (((__time_bomb_allocator_state *)state)->free_count_until_failure >= 0 &&
|
||||
((__time_bomb_allocator_state *)state)->free_count_until_failure-- == 0)
|
||||
{
|
||||
printf("Free time bomb countdown reached 0, not freeing memory\n");
|
||||
return;
|
||||
}
|
||||
rcutils_get_default_allocator().deallocate(pointer, rcutils_get_default_allocator().state);
|
||||
}
|
||||
|
||||
static void *
|
||||
time_bomb_calloc(size_t number_of_elements, size_t size_of_element, void * state)
|
||||
{
|
||||
if (((__time_bomb_allocator_state *)state)->calloc_count_until_failure >= 0 &&
|
||||
((__time_bomb_allocator_state *)state)->calloc_count_until_failure-- == 0)
|
||||
{
|
||||
printf("Calloc time bomb countdown reached 0, returning nullptr\n");
|
||||
return nullptr;
|
||||
}
|
||||
return rcutils_get_default_allocator().zero_allocate(
|
||||
number_of_elements, size_of_element, rcutils_get_default_allocator().state);
|
||||
}
|
||||
|
||||
/**
|
||||
* This allocator uses the rcutils default allocator functions, but decrements a time bomb counter
|
||||
* for each function call. When the counter reaches 0, that call will fail.
|
||||
* In the case of the allocating functions, it will return a nullptr. In the case of free,
|
||||
* it will fail to free the memory.
|
||||
*
|
||||
* Use this allocator when you need a fixed amount of calls to succeed before it fails.
|
||||
*
|
||||
* Set the count to negative for the time bomb effect to be disabled for that function.
|
||||
*/
|
||||
static inline rcutils_allocator_t
|
||||
get_time_bomb_allocator(void)
|
||||
{
|
||||
static __time_bomb_allocator_state state;
|
||||
state.malloc_count_until_failure = -1;
|
||||
state.realloc_count_until_failure = -1;
|
||||
state.free_count_until_failure = -1;
|
||||
state.calloc_count_until_failure = -1;
|
||||
auto time_bomb_allocator = rcutils_get_default_allocator();
|
||||
time_bomb_allocator.allocate = time_bomb_malloc;
|
||||
time_bomb_allocator.deallocate = time_bomb_free;
|
||||
time_bomb_allocator.reallocate = time_bomb_realloc;
|
||||
time_bomb_allocator.zero_allocate = time_bomb_calloc;
|
||||
time_bomb_allocator.state = &state;
|
||||
return time_bomb_allocator;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set count to the number of times you want the call to succeed before it fails.
|
||||
* After it fails once, it will succeed until this count is reset.
|
||||
* Set it to a negative value to disable the time bomb effect for that function.
|
||||
*/
|
||||
static inline void
|
||||
set_time_bomb_allocator_malloc_count(rcutils_allocator_t & time_bomb_allocator, int count)
|
||||
{
|
||||
((__time_bomb_allocator_state *)time_bomb_allocator.state)->malloc_count_until_failure = count;
|
||||
}
|
||||
|
||||
static inline void
|
||||
set_time_bomb_allocator_realloc_count(rcutils_allocator_t & time_bomb_allocator, int count)
|
||||
{
|
||||
((__time_bomb_allocator_state *)time_bomb_allocator.state)->realloc_count_until_failure = count;
|
||||
}
|
||||
|
||||
static inline void
|
||||
set_time_bomb_allocator_free_count(rcutils_allocator_t & time_bomb_allocator, int count)
|
||||
{
|
||||
((__time_bomb_allocator_state *)time_bomb_allocator.state)->free_count_until_failure = count;
|
||||
}
|
||||
|
||||
static inline void
|
||||
set_time_bomb_allocator_calloc_count(rcutils_allocator_t & time_bomb_allocator, int count)
|
||||
{
|
||||
((__time_bomb_allocator_state *)time_bomb_allocator.state)->calloc_count_until_failure = count;
|
||||
}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // TIME_BOMB_ALLOCATOR_TESTING_UTILS_H_
|
Loading…
Add table
Add a link
Reference in a new issue