From f28d0cc8f948f1ba03f23148726df09f244b630e Mon Sep 17 00:00:00 2001 From: bpwilcox Date: Fri, 25 Oct 2019 16:14:37 -0700 Subject: [PATCH] cleanup, added test cases for descriptors, fixed namespaced descriptors remove MAX_STRING_SIZE comparisons for rebase add new lines Signed-off-by: bpwilcox change to/from to min/max Signed-off-by: bpwilcox --- rcl_yaml_param_parser/CMakeLists.txt | 9 - .../include/rcl_yaml_param_parser/parser.h | 11 + .../include/rcl_yaml_param_parser/types.h | 10 +- rcl_yaml_param_parser/src/parser.c | 280 +++++++++++------- .../test/assign_param_in_descriptors.yaml | 6 + .../test/correct_config.yaml | 2 - .../test/correct_param_descriptors.yaml | 32 ++ .../test/invalid_param_descriptor_key.yaml | 6 + .../test/invalid_param_descriptor_type.yaml | 5 + .../test/no_value_descriptor.yaml | 5 + .../test/overlay_descriptors.yaml | 16 + .../test/parameter_descriptors.yaml | 19 -- .../test/test_parse_yaml.cpp | 179 +++++++++++ .../test/test_parse_yaml_descriptors.cpp | 60 ---- 14 files changed, 446 insertions(+), 194 deletions(-) create mode 100644 rcl_yaml_param_parser/test/assign_param_in_descriptors.yaml create mode 100644 rcl_yaml_param_parser/test/correct_param_descriptors.yaml create mode 100644 rcl_yaml_param_parser/test/invalid_param_descriptor_key.yaml create mode 100644 rcl_yaml_param_parser/test/invalid_param_descriptor_type.yaml create mode 100644 rcl_yaml_param_parser/test/no_value_descriptor.yaml create mode 100644 rcl_yaml_param_parser/test/overlay_descriptors.yaml delete mode 100644 rcl_yaml_param_parser/test/parameter_descriptors.yaml delete mode 100644 rcl_yaml_param_parser/test/test_parse_yaml_descriptors.cpp diff --git a/rcl_yaml_param_parser/CMakeLists.txt b/rcl_yaml_param_parser/CMakeLists.txt index 09ddb3b0b6..89b089b9f5 100644 --- a/rcl_yaml_param_parser/CMakeLists.txt +++ b/rcl_yaml_param_parser/CMakeLists.txt @@ -63,15 +63,6 @@ if(BUILD_TESTING) PRIVATE ${osrf_testing_tools_cpp_INCLUDE_DIRS}) endif() - ament_add_gtest(test_parse_yaml_descriptors - test/test_parse_yaml_descriptors.cpp - ) - if(TARGET test_parse_yaml_descriptors) - target_link_libraries(test_parse_yaml_descriptors ${PROJECT_NAME}) - target_include_directories(test_parse_yaml_descriptors - PRIVATE ${osrf_testing_tools_cpp_INCLUDE_DIRS}) - endif() - endif() ament_export_dependencies(ament_cmake) diff --git a/rcl_yaml_param_parser/include/rcl_yaml_param_parser/parser.h b/rcl_yaml_param_parser/include/rcl_yaml_param_parser/parser.h index 24e331e0de..fda645eaae 100644 --- a/rcl_yaml_param_parser/include/rcl_yaml_param_parser/parser.h +++ b/rcl_yaml_param_parser/include/rcl_yaml_param_parser/parser.h @@ -79,6 +79,17 @@ rcl_variant_t * rcl_yaml_node_struct_get( const char * param_name, rcl_params_t * params_st); +/// \brief Get the descriptor struct for a given parameter +/// \param[in] node_name is the name of the node to which the parameter belongs +/// \param[in] param_name is the name of the parameter whose value is to be retrieved +/// \param[inout] params_st points to the populated (or to be populated) parameter struct +/// \return parameter descriptor struct on success and NULL on failure +RCL_YAML_PARAM_PARSER_PUBLIC +rcl_param_descriptor_t * rcl_yaml_node_struct_get_descriptor( + const char * node_name, + const char * param_name, + rcl_params_t * params_st); + /// \brief Print the parameter structure to stdout /// \param[in] params_st points to the populated parameter struct RCL_YAML_PARAM_PARSER_PUBLIC diff --git a/rcl_yaml_param_parser/include/rcl_yaml_param_parser/types.h b/rcl_yaml_param_parser/include/rcl_yaml_param_parser/types.h index 7e5fc0eda5..9854435962 100644 --- a/rcl_yaml_param_parser/include/rcl_yaml_param_parser/types.h +++ b/rcl_yaml_param_parser/include/rcl_yaml_param_parser/types.h @@ -83,11 +83,11 @@ typedef struct rcl_param_descriptor_s uint8_t * type; char * description; char * additional_constraints; - double * from_value_float; - double * to_value_float; - double * step_float; - int64_t * from_value_int; - int64_t * to_value_int; + double * min_value_double; + double * max_value_double; + double * step_double; + int64_t * min_value_int; + int64_t * max_value_int; int64_t * step_int; } rcl_param_descriptor_t; diff --git a/rcl_yaml_param_parser/src/parser.c b/rcl_yaml_param_parser/src/parser.c index a48a067293..7b423456e6 100644 --- a/rcl_yaml_param_parser/src/parser.c +++ b/rcl_yaml_param_parser/src/parser.c @@ -38,8 +38,7 @@ typedef enum yaml_map_lvl_e MAP_UNINIT_LVL = 0U, MAP_NODE_NAME_LVL = 1U, MAP_PARAMS_LVL = 2U, - MAP_PARAMS_DESCRIPTORS_LVL = 3U, - + MAP_PARAMS_DESCRIPTORS_LVL = 3U } yaml_map_lvl_t; /// Basic supported data types in the yaml file @@ -170,6 +169,9 @@ static rcutils_ret_t parse_value_events( const size_t parameter_idx, rcl_params_t * params_st); +static rcutils_ret_t cleanup_parameter_names( + rcl_params_t * params_st); + /// /// Add name to namespace tracker /// @@ -404,13 +406,6 @@ static rcutils_ret_t node_params_descriptors_init( return RCUTILS_RET_BAD_ALLOC; } - // node_descriptors->parameter_descriptors_keys = allocator.zero_allocate( - // MAX_NUM_PARAMS_PER_NODE, sizeof(rcl_param_descriptor_keys_t), allocator.state); - // if (NULL == node_descriptors->parameter_descriptors_keys) { - // allocator.deallocate(node_descriptors->parameter_descriptors_keys, allocator.state); - // return RCUTILS_RET_BAD_ALLOC; - // } - return RCUTILS_RET_OK; } @@ -688,38 +683,39 @@ rcl_params_t * rcl_yaml_node_struct_copy( } *(out_param_descriptor->type) = *(param_descriptor->type); } - if (NULL != param_descriptor->from_value_int) { - out_param_descriptor->from_value_int = allocator.allocate(sizeof(int64_t), allocator.state); - if (NULL == out_param_descriptor->from_value_int) { + if (NULL != param_descriptor->min_value_int) { + out_param_descriptor->min_value_int = allocator.allocate(sizeof(int64_t), allocator.state); + if (NULL == out_param_descriptor->min_value_int) { RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); goto fail; } - *(out_param_descriptor->from_value_int) = *(param_descriptor->from_value_int); + *(out_param_descriptor->min_value_int) = *(param_descriptor->min_value_int); } - if (NULL != param_descriptor->from_value_float) { - out_param_descriptor->from_value_float = + if (NULL != param_descriptor->min_value_double) { + out_param_descriptor->min_value_double = allocator.allocate(sizeof(double), allocator.state); - if (NULL == out_param_descriptor->from_value_float) { + if (NULL == out_param_descriptor->min_value_double) { RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); goto fail; } - *(out_param_descriptor->from_value_float) = *(param_descriptor->from_value_float); + *(out_param_descriptor->min_value_double) = *(param_descriptor->min_value_double); } - if (NULL != param_descriptor->to_value_int) { - out_param_descriptor->to_value_int = allocator.allocate(sizeof(int64_t), allocator.state); - if (NULL == out_param_descriptor->to_value_int) { + if (NULL != param_descriptor->max_value_int) { + out_param_descriptor->max_value_int = allocator.allocate(sizeof(int64_t), allocator.state); + if (NULL == out_param_descriptor->max_value_int) { RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); goto fail; } - *(out_param_descriptor->to_value_int) = *(param_descriptor->to_value_int); + *(out_param_descriptor->max_value_int) = *(param_descriptor->max_value_int); } - if (NULL != param_descriptor->to_value_float) { - out_param_descriptor->to_value_float = allocator.allocate(sizeof(double), allocator.state); - if (NULL == out_param_descriptor->to_value_float) { + if (NULL != param_descriptor->max_value_double) { + out_param_descriptor->max_value_double = + allocator.allocate(sizeof(double), allocator.state); + if (NULL == out_param_descriptor->max_value_double) { RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); goto fail; } - *(out_param_descriptor->to_value_float) = *(param_descriptor->to_value_float); + *(out_param_descriptor->max_value_double) = *(param_descriptor->max_value_double); } if (NULL != param_descriptor->step_int) { out_param_descriptor->step_int = allocator.allocate(sizeof(int64_t), allocator.state); @@ -729,13 +725,13 @@ rcl_params_t * rcl_yaml_node_struct_copy( } *(out_param_descriptor->step_int) = *(param_descriptor->step_int); } - if (NULL != param_descriptor->step_float) { - out_param_descriptor->step_float = allocator.allocate(sizeof(double), allocator.state); - if (NULL == out_param_descriptor->step_float) { + if (NULL != param_descriptor->step_double) { + out_param_descriptor->step_double = allocator.allocate(sizeof(double), allocator.state); + if (NULL == out_param_descriptor->step_double) { RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); goto fail; } - *(out_param_descriptor->step_float) = *(param_descriptor->step_float); + *(out_param_descriptor->step_double) = *(param_descriptor->step_double); } if (NULL != param_descriptor->read_only) { out_param_descriptor->read_only = allocator.allocate(sizeof(bool), allocator.state); @@ -865,20 +861,20 @@ void rcl_yaml_node_struct_fini( if (NULL != param_descriptor->additional_constraints) { allocator.deallocate(param_descriptor->additional_constraints, allocator.state); } - if (NULL != param_descriptor->from_value_float) { - allocator.deallocate(param_descriptor->from_value_float, allocator.state); + if (NULL != param_descriptor->min_value_double) { + allocator.deallocate(param_descriptor->min_value_double, allocator.state); } - if (NULL != param_descriptor->to_value_float) { - allocator.deallocate(param_descriptor->to_value_float, allocator.state); + if (NULL != param_descriptor->max_value_double) { + allocator.deallocate(param_descriptor->max_value_double, allocator.state); } - if (NULL != param_descriptor->step_float) { - allocator.deallocate(param_descriptor->step_float, allocator.state); + if (NULL != param_descriptor->step_double) { + allocator.deallocate(param_descriptor->step_double, allocator.state); } - if (NULL != param_descriptor->from_value_int) { - allocator.deallocate(param_descriptor->from_value_int, allocator.state); + if (NULL != param_descriptor->min_value_int) { + allocator.deallocate(param_descriptor->min_value_int, allocator.state); } - if (NULL != param_descriptor->to_value_int) { - allocator.deallocate(param_descriptor->to_value_int, allocator.state); + if (NULL != param_descriptor->max_value_int) { + allocator.deallocate(param_descriptor->max_value_int, allocator.state); } if (NULL != param_descriptor->step_int) { allocator.deallocate(param_descriptor->step_int, allocator.state); @@ -1011,7 +1007,7 @@ static rcutils_ret_t find_descriptor( if (NULL == node_descriptors_st->parameter_names[*parameter_idx]) { return RCUTILS_RET_BAD_ALLOC; } - node_descriptors_st->num_params++; + // node_descriptors_st->num_params++; return RCUTILS_RET_OK; } @@ -1038,6 +1034,28 @@ rcl_variant_t * rcl_yaml_node_struct_get( return param_value; } +rcl_param_descriptor_t * rcl_yaml_node_struct_get_descriptor( + const char * node_name, + const char * param_name, + rcl_params_t * params_st) +{ + RCUTILS_CHECK_ARGUMENT_FOR_NULL(node_name, NULL); + RCUTILS_CHECK_ARGUMENT_FOR_NULL(param_name, NULL); + RCUTILS_CHECK_ARGUMENT_FOR_NULL(params_st, NULL); + + rcl_param_descriptor_t * param_descriptor = NULL; + + size_t node_idx = 0U; + rcutils_ret_t ret = find_node(node_name, params_st, &node_idx); + if (RCUTILS_RET_OK == ret) { + size_t parameter_idx = 0U; + ret = find_descriptor(node_idx, param_name, params_st, ¶meter_idx); + if (RCUTILS_RET_OK == ret) { + param_descriptor = &(params_st->descriptors[node_idx].parameter_descriptors[parameter_idx]); + } + } + return param_descriptor; +} /// /// Dump the param structure @@ -1156,29 +1174,29 @@ void rcl_yaml_node_struct_print( printf("\n%*stype: ", param_col + 2, ""); printf("%d", *(descriptor->type)); } - if (NULL != descriptor->from_value_int) { - printf("\n%*sfrom_value: ", param_col + 2, ""); - printf("%ld", *(descriptor->from_value_int)); + if (NULL != descriptor->min_value_int) { + printf("\n%*smin_value: ", param_col + 2, ""); + printf("%ld", *(descriptor->min_value_int)); } - if (NULL != descriptor->from_value_float) { - printf("\n%*sfrom_value: ", param_col + 2, ""); - printf("%lf", *(descriptor->from_value_float)); + if (NULL != descriptor->min_value_double) { + printf("\n%*smin_value: ", param_col + 2, ""); + printf("%lf", *(descriptor->min_value_double)); } - if (NULL != descriptor->to_value_int) { - printf("\n%*sto_value: ", param_col + 2, ""); - printf("%ld", *(descriptor->to_value_int)); + if (NULL != descriptor->max_value_int) { + printf("\n%*smax_value: ", param_col + 2, ""); + printf("%ld", *(descriptor->max_value_int)); } - if (NULL != descriptor->to_value_float) { - printf("\n%*sto_value: ", param_col + 2, ""); - printf("%lf", *(descriptor->to_value_float)); + if (NULL != descriptor->max_value_double) { + printf("\n%*smax_value: ", param_col + 2, ""); + printf("%lf", *(descriptor->max_value_double)); } if (NULL != descriptor->step_int) { printf("\n%*sstep: ", param_col + 2, ""); printf("%ld", *(descriptor->step_int)); } - if (NULL != descriptor->step_float) { + if (NULL != descriptor->step_double) { printf("\n%*sstep: ", param_col + 2, ""); - printf("%lf", *(descriptor->step_float)); + printf("%lf", *(descriptor->step_double)); } if (NULL != descriptor->read_only) { printf("\n%*sread_only: ", param_col + 2, ""); @@ -1668,22 +1686,15 @@ static rcutils_ret_t parse_descriptor( RCUTILS_CHECK_FOR_NULL_WITH_MSG( value, "event argument has no value", return RCUTILS_RET_INVALID_ARGUMENT); - if (val_size > MAX_STRING_SIZE) { - RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( - "Scalar value at line %u has %zu bytes which is bigger than the compile " - "time limit of %u bytes", line_num, val_size, MAX_STRING_SIZE); + if (style != YAML_SINGLE_QUOTED_SCALAR_STYLE && + style != YAML_DOUBLE_QUOTED_SCALAR_STYLE && + 0U == val_size) + { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING("No value at line %d", line_num); return RCUTILS_RET_ERROR; - } else { - if (style != YAML_SINGLE_QUOTED_SCALAR_STYLE && - style != YAML_DOUBLE_QUOTED_SCALAR_STYLE && - 0U == val_size) - { - RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING("No value at line %d", line_num); - return RCUTILS_RET_ERROR; - } } - if (NULL == params_st->params[node_idx].parameter_values) { + if (NULL == params_st->descriptors[node_idx].parameter_descriptors) { RCUTILS_SET_ERROR_MSG("Internal error: Invalid mem"); return RCUTILS_RET_BAD_ALLOC; } @@ -1700,51 +1711,95 @@ static rcutils_ret_t parse_descriptor( } if (NULL == ns_tracker->parameter_ns) { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Parameter assignment at line %d unallowed in parameter__descriptors", line_num); return RCUTILS_RET_ERROR; + } else { + // If parsing a yaml value, then current parameter namespace must be parameter name + allocator.deallocate(params_st->descriptors[node_idx].parameter_names[parameter_idx], + allocator.state); + params_st->descriptors[node_idx].parameter_names[parameter_idx] = + rcutils_strdup(ns_tracker->parameter_ns, allocator); + } + if (NULL == param_descriptor->name) { + param_descriptor->name = + rcutils_strdup(params_st->descriptors[node_idx].parameter_names[parameter_idx], allocator); + rcl_node_params_descriptors_t * node_descriptors_st = &(params_st->descriptors[node_idx]); + node_descriptors_st->num_params++; } - param_descriptor->name = - rcutils_strdup(params_st->descriptors[node_idx].parameter_names[parameter_idx], allocator); if (true == is_seq) { RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( "Sequences not supported for parameter descriptors at line %d", line_num); return RCUTILS_RET_ERROR; } - if (0 == strncmp("type", ns_tracker->descriptor_key_ns, strlen("type"))) { + if (0 == strncmp("additional_constraints", ns_tracker->descriptor_key_ns, + strlen("additional_constraints"))) + { + if (val_type == DATA_TYPE_STRING) { + param_descriptor->additional_constraints = (char *)ret_val; + if (NULL == param_descriptor->additional_constraints) { + RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); + return RCUTILS_RET_BAD_ALLOC; + } + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Value type 'string' expected at line %d for " + "parameter__descriptors key: additional_constraints", + line_num); + return RCUTILS_RET_ERROR; + } + } else if (0 == strncmp("type", ns_tracker->descriptor_key_ns, strlen("type"))) { if (val_type == DATA_TYPE_INT64) { param_descriptor->type = (uint8_t *)ret_val; if (NULL == param_descriptor->type) { RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); return RCUTILS_RET_BAD_ALLOC; } + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Value type 'integer' expected at line %d for parameter__descriptors key: type", line_num); + return RCUTILS_RET_ERROR; } } else if (0 == strncmp("min_value", ns_tracker->descriptor_key_ns, strlen("min_value"))) { if (val_type == DATA_TYPE_INT64) { - param_descriptor->from_value_int = (int64_t *)ret_val; - if (NULL == param_descriptor->from_value_int) { + param_descriptor->min_value_int = (int64_t *)ret_val; + if (NULL == param_descriptor->min_value_int) { RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); return RCUTILS_RET_BAD_ALLOC; } } else if (val_type == DATA_TYPE_DOUBLE) { - param_descriptor->from_value_float = (double *)ret_val; - if (NULL == param_descriptor->from_value_float) { + param_descriptor->min_value_double = (double *)ret_val; + if (NULL == param_descriptor->min_value_double) { RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); return RCUTILS_RET_BAD_ALLOC; } + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Value type 'integer' or 'double' expected at line %d for " + "parameter__descriptors key: min_value", + line_num); + return RCUTILS_RET_ERROR; } } else if (0 == strncmp("max_value", ns_tracker->descriptor_key_ns, strlen("max_value"))) { if (val_type == DATA_TYPE_INT64) { - param_descriptor->to_value_int = (int64_t *)ret_val; - if (NULL == param_descriptor->to_value_int) { + param_descriptor->max_value_int = (int64_t *)ret_val; + if (NULL == param_descriptor->max_value_int) { RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); return RCUTILS_RET_BAD_ALLOC; } } else if (val_type == DATA_TYPE_DOUBLE) { - param_descriptor->to_value_float = (double *)ret_val; - if (NULL == param_descriptor->to_value_float) { + param_descriptor->max_value_double = (double *)ret_val; + if (NULL == param_descriptor->max_value_double) { RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); return RCUTILS_RET_BAD_ALLOC; } + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Value type 'integer' or 'double' expected at line %d for " + "parameter__descriptors key: max_value", + line_num); + return RCUTILS_RET_ERROR; } } else if (0 == strncmp("read_only", ns_tracker->descriptor_key_ns, strlen("read_only"))) { if (val_type == DATA_TYPE_BOOL) { @@ -1753,6 +1808,11 @@ static rcutils_ret_t parse_descriptor( RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); return RCUTILS_RET_BAD_ALLOC; } + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Value type 'bool' expected at line %d for parameter__descriptors key: read_only", + line_num); + return RCUTILS_RET_ERROR; } } else if (0 == strncmp("description", ns_tracker->descriptor_key_ns, strlen("description"))) { if (val_type == DATA_TYPE_STRING) { @@ -1761,17 +1821,11 @@ static rcutils_ret_t parse_descriptor( RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); return RCUTILS_RET_BAD_ALLOC; } - } - } else if (0 == - strncmp("additional_constraints", ns_tracker->descriptor_key_ns, - strlen("additional_constraints"))) - { - if (val_type == DATA_TYPE_STRING) { - param_descriptor->additional_constraints = (char *)ret_val; - if (NULL == param_descriptor->additional_constraints) { - RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); - return RCUTILS_RET_BAD_ALLOC; - } + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Value type 'string' expected at line %d for parameter__descriptors key: description", + line_num); + return RCUTILS_RET_ERROR; } } else if (0 == strncmp("step", ns_tracker->descriptor_key_ns, strlen("step"))) { if (val_type == DATA_TYPE_INT64) { @@ -1781,14 +1835,21 @@ static rcutils_ret_t parse_descriptor( return RCUTILS_RET_BAD_ALLOC; } } else if (val_type == DATA_TYPE_DOUBLE) { - param_descriptor->step_float = (double *)ret_val; - if (NULL == param_descriptor->step_float) { + param_descriptor->step_double = (double *)ret_val; + if (NULL == param_descriptor->step_double) { RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); return RCUTILS_RET_BAD_ALLOC; } + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Value type 'integer' or 'double' expected at line %d for parameter__descriptors key: step", + line_num); + return RCUTILS_RET_ERROR; } } else { - printf("\n value does not match any parameter descriptor key!\n"); + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Descriptor key at line %d does not match any valid parameter__descriptors key", line_num); + return RCUTILS_RET_ERROR; } return RCUTILS_RET_OK; @@ -2004,13 +2065,6 @@ static rcutils_ret_t parse_key( const size_t param_name_len = strlen(value); const size_t tot_len = (params_ns_len + param_name_len + 2U); - if (tot_len > MAX_STRING_SIZE) { - RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( - "The name length exceeds the MAX size %d at line %d", MAX_STRING_SIZE, line_num); - ret = RCUTILS_RET_ERROR; - break; - } - param_name = allocator.zero_allocate(1U, tot_len, allocator.state); if (NULL == param_name) { ret = RCUTILS_RET_BAD_ALLOC; @@ -2018,6 +2072,9 @@ static rcutils_ret_t parse_key( } memmove(param_name, parameter_ns, params_ns_len); + param_name[params_ns_len] = '.'; + memmove((param_name + params_ns_len + 1U), value, param_name_len); + param_name[tot_len - 1U] = '\0'; params_st->descriptors[*node_idx].parameter_names[*parameter_idx] = param_name; } @@ -2330,11 +2387,36 @@ bool rcl_parse_yaml_file( } rcl_yaml_node_struct_fini(params_st); return false; + } else { + // Clean up parameter descriptor names + cleanup_parameter_names(params_st); } return true; } +static rcutils_ret_t cleanup_parameter_names(rcl_params_t * params_st) +{ + rcutils_allocator_t allocator = params_st->allocator; + for (size_t node_idx = 0U; node_idx < params_st->num_nodes; ++node_idx) { + rcl_node_params_descriptors_t * node_descriptors_st = &(params_st->descriptors[node_idx]); + allocator.deallocate(node_descriptors_st->parameter_names, allocator.state); + node_descriptors_st->parameter_names = allocator.zero_allocate( + MAX_NUM_PARAMS_PER_NODE, sizeof(char *), allocator.state); + if (NULL == node_descriptors_st->parameter_names) { + return RCUTILS_RET_BAD_ALLOC; + } + for (size_t parameter_idx = 0U; parameter_idx < node_descriptors_st->num_params; + parameter_idx++) + { + rcl_param_descriptor_t * param_descriptor = + &(node_descriptors_st->parameter_descriptors[parameter_idx]); + node_descriptors_st->parameter_names[parameter_idx] = + rcutils_strdup(param_descriptor->name, allocator); + } + } + return RCUTILS_RET_OK; +} /// /// Parse a YAML string and populate params_st /// diff --git a/rcl_yaml_param_parser/test/assign_param_in_descriptors.yaml b/rcl_yaml_param_parser/test/assign_param_in_descriptors.yaml new file mode 100644 index 0000000000..80b92bb8e4 --- /dev/null +++ b/rcl_yaml_param_parser/test/assign_param_in_descriptors.yaml @@ -0,0 +1,6 @@ +node1: + ros__parameters: + parameter__descriptors: + bar: 42 + foo: + read_only: true diff --git a/rcl_yaml_param_parser/test/correct_config.yaml b/rcl_yaml_param_parser/test/correct_config.yaml index 4ce0362c3a..51d1bb6183 100644 --- a/rcl_yaml_param_parser/test/correct_config.yaml +++ b/rcl_yaml_param_parser/test/correct_config.yaml @@ -12,8 +12,6 @@ lidar_ns: dy: 2.30 fr_sensor_specs: [12, 3, 0, 7] bk_sensor_specs: [12.1, -2.3, 5.2, 9.0] - foo: - bar: 2 is_front: true driver2: dx: 1.23 diff --git a/rcl_yaml_param_parser/test/correct_param_descriptors.yaml b/rcl_yaml_param_parser/test/correct_param_descriptors.yaml new file mode 100644 index 0000000000..0eada751c6 --- /dev/null +++ b/rcl_yaml_param_parser/test/correct_param_descriptors.yaml @@ -0,0 +1,32 @@ +# config/test_yaml +--- + +node_ns: + node1: + ros__parameters: + parameter__descriptors: + param1: + type: 2 + min_value: 5 + max_value: 100 + step: 5 + read_only: false + description: "int parameter" + additional_constraints: "only multiples of 5" + param2: + min_value: 1.0 + max_value: 10.0 + description: "double parameter" + node2: + ros__parameters: + foo: + bar: 10 + baz: "hello" + parameter__descriptors: + foo: + bar: + description: "namespaced parameter" + read_only: false + baz: + description: "another namespaced parameter" + foobar: true diff --git a/rcl_yaml_param_parser/test/invalid_param_descriptor_key.yaml b/rcl_yaml_param_parser/test/invalid_param_descriptor_key.yaml new file mode 100644 index 0000000000..100b94d4d2 --- /dev/null +++ b/rcl_yaml_param_parser/test/invalid_param_descriptor_key.yaml @@ -0,0 +1,6 @@ +node1: + ros__parameters: + parameter__descriptors: + foo: + read_only: true + invalid_description: "This is an invalid descriptor key" diff --git a/rcl_yaml_param_parser/test/invalid_param_descriptor_type.yaml b/rcl_yaml_param_parser/test/invalid_param_descriptor_type.yaml new file mode 100644 index 0000000000..31cd226bc3 --- /dev/null +++ b/rcl_yaml_param_parser/test/invalid_param_descriptor_type.yaml @@ -0,0 +1,5 @@ +node1: + ros__parameters: + parameter__descriptors: + foo: + min_value: "5" diff --git a/rcl_yaml_param_parser/test/no_value_descriptor.yaml b/rcl_yaml_param_parser/test/no_value_descriptor.yaml new file mode 100644 index 0000000000..213a8070cf --- /dev/null +++ b/rcl_yaml_param_parser/test/no_value_descriptor.yaml @@ -0,0 +1,5 @@ +node1: + ros__parameters: + parameter__descriptors: + foo: + description: diff --git a/rcl_yaml_param_parser/test/overlay_descriptors.yaml b/rcl_yaml_param_parser/test/overlay_descriptors.yaml new file mode 100644 index 0000000000..8ad6d6b9ea --- /dev/null +++ b/rcl_yaml_param_parser/test/overlay_descriptors.yaml @@ -0,0 +1,16 @@ +node_ns: + node1: + ros__parameters: + parameter__descriptors: + param1: + max_value: 200 + param2: + min_value: -2.0 + node2: + ros__parameters: + parameter__descriptors: + foo: + bar: + read_only: true + baz: + description: "other namespaced parameter" diff --git a/rcl_yaml_param_parser/test/parameter_descriptors.yaml b/rcl_yaml_param_parser/test/parameter_descriptors.yaml deleted file mode 100644 index 8de889bd7c..0000000000 --- a/rcl_yaml_param_parser/test/parameter_descriptors.yaml +++ /dev/null @@ -1,19 +0,0 @@ -# config/test_yaml ---- - -node1: - ros__parameters: - parameter__descriptors: - param1: - type: 2 - min_value: 5 - max_value: 25 - read_only: false - description: "int parameter" - additional_constraints: "only multiples of 5" - param2: - type: 3 - min_value: 1.0 - max_value: 10.0 - read_only: true - description: "double parameter" diff --git a/rcl_yaml_param_parser/test/test_parse_yaml.cpp b/rcl_yaml_param_parser/test/test_parse_yaml.cpp index 3450fd5493..86753988e6 100644 --- a/rcl_yaml_param_parser/test/test_parse_yaml.cpp +++ b/rcl_yaml_param_parser/test/test_parse_yaml.cpp @@ -452,6 +452,185 @@ TEST(test_file_parser, maximum_number_parameters) { EXPECT_FALSE(res); } +TEST(test_parser, correct_syntax_descriptors) { + 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_param_descriptors.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); + 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); + ASSERT_TRUE(res) << rcutils_get_error_string().str; + + char * another_path = rcutils_join_path(test_path, "overlay_descriptors.yaml", allocator); + ASSERT_TRUE(NULL != another_path) << rcutils_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + allocator.deallocate(another_path, allocator.state); + }); + ASSERT_TRUE(rcutils_exists(another_path)) << "No test YAML file found at " << another_path; + res = rcl_parse_yaml_file(another_path, params_hdl); + ASSERT_TRUE(res) << rcutils_get_error_string().str; + + rcl_params_t * copy_of_params_hdl = rcl_yaml_node_struct_copy(params_hdl); + ASSERT_TRUE(NULL != copy_of_params_hdl) << rcutils_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + rcl_yaml_node_struct_fini(copy_of_params_hdl); + }); + + rcl_params_t * params_hdl_set[] = {params_hdl, copy_of_params_hdl}; + for (rcl_params_t * params : params_hdl_set) { + rcl_param_descriptor_t * param_descriptor = NULL; + param_descriptor = rcl_yaml_node_struct_get_descriptor("node_ns/node1", "param1", params); + ASSERT_TRUE(NULL != param_descriptor); + ASSERT_TRUE(NULL != param_descriptor->name); + EXPECT_STREQ("param1", param_descriptor->name); + ASSERT_TRUE(NULL != param_descriptor->description); + EXPECT_STREQ("int parameter", param_descriptor->description); + ASSERT_TRUE(NULL != param_descriptor->additional_constraints); + EXPECT_STREQ("only multiples of 5", param_descriptor->additional_constraints); + ASSERT_TRUE(NULL != param_descriptor->type); + EXPECT_EQ(2U, *param_descriptor->type); + ASSERT_TRUE(NULL != param_descriptor->min_value_int); + EXPECT_EQ(5, *param_descriptor->min_value_int); + ASSERT_TRUE(NULL != param_descriptor->max_value_int); + EXPECT_EQ(200, *param_descriptor->max_value_int); + ASSERT_TRUE(NULL != param_descriptor->step_int); + EXPECT_EQ(5, *param_descriptor->step_int); + ASSERT_TRUE(NULL != param_descriptor->read_only); + EXPECT_FALSE(*param_descriptor->read_only); + + param_descriptor = rcl_yaml_node_struct_get_descriptor("node_ns/node1", "param2", params); + ASSERT_TRUE(NULL != param_descriptor); + ASSERT_TRUE(NULL != param_descriptor->name); + EXPECT_STREQ("param2", param_descriptor->name); + ASSERT_TRUE(NULL != param_descriptor->description); + EXPECT_STREQ("double parameter", param_descriptor->description); + ASSERT_TRUE(NULL != param_descriptor->min_value_double); + EXPECT_DOUBLE_EQ(-2.0, *param_descriptor->min_value_double); + ASSERT_TRUE(NULL != param_descriptor->max_value_double); + EXPECT_DOUBLE_EQ(10.0, *param_descriptor->max_value_double); + + param_descriptor = rcl_yaml_node_struct_get_descriptor("node_ns/node2", "foo.bar", params); + ASSERT_TRUE(NULL != param_descriptor); + ASSERT_TRUE(NULL != param_descriptor->name); + EXPECT_STREQ("foo.bar", param_descriptor->name); + ASSERT_TRUE(NULL != param_descriptor->description); + EXPECT_STREQ("namespaced parameter", param_descriptor->description); + ASSERT_TRUE(NULL != param_descriptor->read_only); + EXPECT_TRUE(*param_descriptor->read_only); + + param_descriptor = rcl_yaml_node_struct_get_descriptor("node_ns/node2", "foo.baz", params); + ASSERT_TRUE(NULL != param_descriptor); + ASSERT_TRUE(NULL != param_descriptor->name); + EXPECT_STREQ("foo.baz", param_descriptor->name); + ASSERT_TRUE(NULL != param_descriptor->description); + EXPECT_STREQ("other namespaced parameter", param_descriptor->description); + + rcl_yaml_node_struct_print(params); + } +} + +TEST(test_parser, param_assign_in_descriptors) { + 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, "assign_param_in_descriptors.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); + ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str; + bool res = rcl_parse_yaml_file(path, params_hdl); + fprintf(stderr, "%s\n", rcutils_get_error_string().str); + EXPECT_FALSE(res); +} + +TEST(test_parser, invalid_param_descriptor_key) { + 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, "invalid_param_descriptor_key.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); + ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str; + bool res = rcl_parse_yaml_file(path, params_hdl); + fprintf(stderr, "%s\n", rcutils_get_error_string().str); + EXPECT_FALSE(res); +} + +TEST(test_parser, invalid_param_descriptor_type) { + 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, "invalid_param_descriptor_type.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); + ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str; + bool res = rcl_parse_yaml_file(path, params_hdl); + fprintf(stderr, "%s\n", rcutils_get_error_string().str); + EXPECT_FALSE(res); +} + +TEST(test_parser, no_value_descriptor) { + 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, "no_value_descriptor.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); + ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str; + bool res = rcl_parse_yaml_file(path, params_hdl); + fprintf(stderr, "%s\n", rcutils_get_error_string().str); + EXPECT_FALSE(res); +} + int32_t main(int32_t argc, char ** argv) { ::testing::InitGoogleTest(&argc, argv); diff --git a/rcl_yaml_param_parser/test/test_parse_yaml_descriptors.cpp b/rcl_yaml_param_parser/test/test_parse_yaml_descriptors.cpp deleted file mode 100644 index 12920b1db3..0000000000 --- a/rcl_yaml_param_parser/test/test_parse_yaml_descriptors.cpp +++ /dev/null @@ -1,60 +0,0 @@ -// Copyright 2018 Apex.AI, 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 -#include - -#include "osrf_testing_tools_cpp/scope_exit.hpp" - -#include "rcl_yaml_param_parser/parser.h" - -#include "rcutils/allocator.h" -#include "rcutils/error_handling.h" -#include "rcutils/filesystem.h" - -static char cur_dir[1024]; - -TEST(test_parser, correct_syntax) { - 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 * test_path = "/home/brian/ros2_ws/src/ros2/rcl/rcl_yaml_param_parser/test/"; - char * path = rcutils_join_path(test_path, "parameter_descriptors.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); - 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); - ASSERT_TRUE(res) << rcutils_get_error_string().str; - - rcl_yaml_node_struct_print(params_hdl); -} - - -int32_t main(int32_t argc, char ** argv) -{ - ::testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -}