Skip to content

Commit

Permalink
Clean up allocations in rcl_yaml_param_parser package tests.
Browse files Browse the repository at this point in the history
Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
  • Loading branch information
hidmic committed Jul 11, 2019
1 parent a1a833f commit 9aa69f4
Show file tree
Hide file tree
Showing 4 changed files with 145 additions and 51 deletions.
3 changes: 3 additions & 0 deletions rcl_yaml_param_parser/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ install(TARGETS ${PROJECT_NAME}
if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_lint_auto REQUIRED)
find_package(osrf_testing_tools_cpp REQUIRED)
ament_lint_auto_find_test_dependencies()

# Gtests
Expand All @@ -57,6 +58,8 @@ if(BUILD_TESTING)
)
if(TARGET test_parse_yaml)
target_link_libraries(test_parse_yaml ${PROJECT_NAME})
target_include_directories(test_parse_yaml
PRIVATE ${osrf_testing_tools_cpp_INCLUDE_DIRS})
endif()

endif()
Expand Down
1 change: 1 addition & 0 deletions rcl_yaml_param_parser/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>osrf_testing_tools_cpp</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
16 changes: 8 additions & 8 deletions rcl_yaml_param_parser/src/parser.c
Original file line number Diff line number Diff line change
Expand Up @@ -420,14 +420,14 @@ void rcl_yaml_node_struct_fini(
}

if (NULL != params_st->params) {
rcl_node_params_t * node_params_st = &params_st->params[node_idx];
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];
rcl_variant_t * param_var = &(node_params_st->parameter_values[parameter_idx]);
if (NULL != param_name) {
allocator.deallocate(param_name, allocator.state);
}
Expand Down Expand Up @@ -513,7 +513,7 @@ static rcutils_ret_t find_node(
if (NULL == param_st->node_names[*node_idx]) {
return RCUTILS_RET_BAD_ALLOC;
}
rcutils_ret_t ret = node_params_init(&param_st->params[*node_idx], allocator);
rcutils_ret_t ret = node_params_init(&(param_st->params[*node_idx]), allocator);
if (RCUTILS_RET_OK != ret) {
allocator.deallocate(param_st->node_names[*node_idx], allocator.state);
return ret;
Expand All @@ -537,7 +537,7 @@ static rcutils_ret_t find_parameter(

assert(node_idx < param_st->num_nodes);

rcl_node_params_t * node_param_st = &param_st->params[node_idx];
rcl_node_params_t * node_param_st = &(param_st->params[node_idx]);
for (*parameter_idx = 0U; *parameter_idx < node_param_st->num_params; (*parameter_idx)++) {
if (0 == strcmp(node_param_st->parameter_names[*parameter_idx], parameter_name)) {
// Parameter found.
Expand Down Expand Up @@ -571,7 +571,7 @@ rcl_variant_t * rcl_yaml_node_struct_get(
size_t parameter_idx = 0U;
ret = find_parameter(node_idx, param_name, params_st, &parameter_idx);
if (RCUTILS_RET_OK == ret) {
param_value = &params_st->params[node_idx].parameter_values[parameter_idx];
param_value = &(params_st->params[node_idx].parameter_values[parameter_idx]);
}
}
return param_value;
Expand All @@ -597,14 +597,14 @@ void rcl_yaml_node_struct_print(
}

if (NULL != params_st->params) {
rcl_node_params_t * node_params_st = &params_st->params[node_idx];
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];
rcl_variant_t * param_var = &(node_params_st->parameter_values[parameter_idx]);
if (NULL != param_name) {
printf("%*s", param_col, param_name);
}
Expand Down Expand Up @@ -1296,7 +1296,6 @@ static rcutils_ret_t parse_file_events(
rcl_params_t * params_st)
{
int32_t done_parsing = 0;
yaml_event_t event;
bool is_key = true;
bool is_seq = false;
uint32_t line_num = 0;
Expand All @@ -1311,6 +1310,7 @@ static rcutils_ret_t parse_file_events(
RCUTILS_CHECK_ALLOCATOR_WITH_MSG(
&allocator, "invalid allocator", return RCUTILS_RET_INVALID_ARGUMENT);

yaml_event_t event;
rcutils_ret_t ret = RCUTILS_RET_OK;
while (0 == done_parsing) {
if (RCUTILS_RET_OK != ret) {
Expand Down
Loading

0 comments on commit 9aa69f4

Please sign in to comment.