From 218504307007d7dff2aa4f826044c41d1132d9d1 Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Sat, 13 Mar 2021 00:12:22 +0000 Subject: [PATCH 01/19] add param_descriptor type Signed-off-by: Brian Wilcox --- .../include/rcl_yaml_param_parser/types.h | 28 +++++++++++++++++++ 1 file changed, 28 insertions(+) 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 e0e4b5f1c..dd8c1142a 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 @@ -95,6 +95,33 @@ typedef struct rcl_node_params_s size_t capacity_params; ///< Capacity of parameters in the node } rcl_node_params_t; +/// \typedef rcl_param_descriptor_t +/// \brief param_descriptor_t stores the descriptor of a parameter +typedef struct rcl_param_descriptor_s +{ + char * name; + bool * read_only; + uint8_t * type; + char * description; + char * additional_constraints; + 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; + +/// \typedef rcl_node_params_descriptors_t +/// \brief node_params_descriptors_t stores all the parameter descriptors of a single node +typedef struct rcl_node_params_descriptors_s +{ + char ** parameter_names; ///< Array of parameter names (keys) + rcl_param_descriptor_t * parameter_descriptors; ///< Array of corresponding parameter descriptors + size_t num_params; ///< Number of parameters in the node + size_t capacity_descriptors; ///< Capacity of parameters in the node +} rcl_node_params_descriptors_t; + /// stores all the parameters of all nodes of a process /* * \typedef rcl_params_t @@ -103,6 +130,7 @@ typedef struct rcl_params_s { char ** node_names; ///< List of names of the node rcl_node_params_t * params; ///< Array of parameters + rcl_node_params_descriptors_t * descriptors; ///< Array of parameter descriptors size_t num_nodes; ///< Number of nodes size_t capacity_nodes; ///< Capacity of nodes rcutils_allocator_t allocator; ///< Allocator used From d5712fdda615e798741344571c4623fe81f38656 Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Sat, 13 Mar 2021 00:16:27 +0000 Subject: [PATCH 02/19] add parameter descriptors map level and namespace key Signed-off-by: Brian Wilcox --- rcl_yaml_param_parser/src/impl/types.h | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/rcl_yaml_param_parser/src/impl/types.h b/rcl_yaml_param_parser/src/impl/types.h index 4776dc128..c9ca94a81 100644 --- a/rcl_yaml_param_parser/src/impl/types.h +++ b/rcl_yaml_param_parser/src/impl/types.h @@ -28,6 +28,7 @@ extern "C" #endif #define PARAMS_KEY "ros__parameters" +#define PARAMS_DESCRIPTORS_KEY "parameter__descriptors" #define NODE_NS_SEPERATOR "/" #define PARAMETER_NS_SEPERATOR "." @@ -36,6 +37,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, } yaml_map_lvl_t; /// Basic supported data types in the yaml file @@ -51,7 +53,8 @@ typedef enum data_types_e typedef enum namespace_type_e { NS_TYPE_NODE = 1U, - NS_TYPE_PARAM = 2U + NS_TYPE_PARAM = 2U, + NS_TYPE_DESCRIPTOR = 3U } namespace_type_t; /// Keep track of node and parameter name spaces @@ -61,6 +64,8 @@ typedef struct namespace_tracker_s uint32_t num_node_ns; char * parameter_ns; uint32_t num_parameter_ns; + char * descriptor_key_ns; + uint32_t num_descriptor_key_ns; } namespace_tracker_t; #ifdef __cplusplus From 2ab8f0986bdc24bdf5c0595dd6026fd79ba464af Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Sat, 13 Mar 2021 01:26:34 +0000 Subject: [PATCH 03/19] add param descriptor copy and deallocation Signed-off-by: Brian Wilcox --- .../src/impl/yaml_descriptor.h | 49 +++++ rcl_yaml_param_parser/src/yaml_descriptor.c | 174 ++++++++++++++++++ 2 files changed, 223 insertions(+) create mode 100644 rcl_yaml_param_parser/src/impl/yaml_descriptor.h create mode 100644 rcl_yaml_param_parser/src/yaml_descriptor.c diff --git a/rcl_yaml_param_parser/src/impl/yaml_descriptor.h b/rcl_yaml_param_parser/src/impl/yaml_descriptor.h new file mode 100644 index 000000000..3b200e24f --- /dev/null +++ b/rcl_yaml_param_parser/src/impl/yaml_descriptor.h @@ -0,0 +1,49 @@ +// 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. + +#ifndef IMPL__YAML_DESCRIPTOR_H_ +#define IMPL__YAML_DESCRIPTOR_H_ + +#include "rcutils/allocator.h" + +#include "./types.h" +#include "rcl_yaml_param_parser/types.h" +#include "rcl_yaml_param_parser/visibility_control.h" + +#ifdef __cplusplus +extern "C" +{ +#endif + +/// +/// Finalize an rcl_param_descriptor_t +/// +RCL_YAML_PARAM_PARSER_PUBLIC +void rcl_yaml_descriptor_fini( + rcl_param_descriptor_t * param_desc, + const rcutils_allocator_t allocator); + +/// +/// Copy a rcl_param_descriptor_t from param_desc to out_param_desc +/// +RCL_YAML_PARAM_PARSER_PUBLIC +RCUTILS_WARN_UNUSED +bool rcl_yaml_descriptor_copy( + rcl_param_descriptor_t * out_param_desc, const rcl_param_descriptor_t * param_desc, rcutils_allocator_t allocator); + +#ifdef __cplusplus +} +#endif + +#endif // IMPL__YAML_DESCRIPTOR_H_ diff --git a/rcl_yaml_param_parser/src/yaml_descriptor.c b/rcl_yaml_param_parser/src/yaml_descriptor.c new file mode 100644 index 000000000..4be921d48 --- /dev/null +++ b/rcl_yaml_param_parser/src/yaml_descriptor.c @@ -0,0 +1,174 @@ +// 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 "rcutils/allocator.h" +#include "rcutils/strdup.h" +#include "rcutils/types.h" + +#include "./impl/types.h" +#include "./impl/yaml_descriptor.h" +#include "rcl_yaml_param_parser/types.h" + +void rcl_yaml_descriptor_fini( + rcl_param_descriptor_t * param_descriptor, + const rcutils_allocator_t allocator) +{ + if (NULL == param_descriptor) { + return; + } + + if (NULL != param_descriptor->name) { + allocator.deallocate(param_descriptor->name, allocator.state); + param_descriptor->name = NULL; + } + if (NULL != param_descriptor->read_only) { + allocator.deallocate(param_descriptor->read_only, allocator.state); + param_descriptor->read_only = NULL; + } + if (NULL != param_descriptor->type) { + allocator.deallocate(param_descriptor->type, allocator.state); + param_descriptor->type = NULL; + } + if (NULL != param_descriptor->description) { + allocator.deallocate(param_descriptor->description, allocator.state); + param_descriptor->description = NULL; + } + if (NULL != param_descriptor->additional_constraints) { + allocator.deallocate(param_descriptor->additional_constraints, allocator.state); + param_descriptor->additional_constraints = NULL; + } + if (NULL != param_descriptor->min_value_double) { + allocator.deallocate(param_descriptor->min_value_double, allocator.state); + param_descriptor->min_value_double = NULL; + } + if (NULL != param_descriptor->max_value_double) { + allocator.deallocate(param_descriptor->max_value_double, allocator.state); + param_descriptor->max_value_double = NULL; + } + if (NULL != param_descriptor->step_double) { + allocator.deallocate(param_descriptor->step_double, allocator.state); + param_descriptor->step_double = NULL; + } + if (NULL != param_descriptor->min_value_int) { + allocator.deallocate(param_descriptor->min_value_int, allocator.state); + param_descriptor->min_value_int = NULL; + } + if (NULL != param_descriptor->max_value_int) { + allocator.deallocate(param_descriptor->max_value_int, allocator.state); + param_descriptor->max_value_int = NULL; + } + if (NULL != param_descriptor->step_int) { + allocator.deallocate(param_descriptor->step_int, allocator.state); + param_descriptor->step_int = NULL; + } +} + +bool rcl_yaml_descriptor_copy( + rcl_param_descriptor_t * out_param_descriptor, const rcl_param_descriptor_t * param_descriptor, rcutils_allocator_t allocator) +{ + if (NULL == param_descriptor || NULL == out_param_descriptor) { + return false; + } + if (NULL != param_descriptor->name) { + out_param_descriptor->name = + rcutils_strdup(param_descriptor->name, allocator); + if (NULL == out_param_descriptor->name) { + RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); + return false; + } + } + if (NULL != param_descriptor->description) { + out_param_descriptor->description = + rcutils_strdup(param_descriptor->description, allocator); + if (NULL == out_param_descriptor->description) { + RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); + return false; + } + } + if (NULL != param_descriptor->additional_constraints) { + out_param_descriptor->additional_constraints = + rcutils_strdup(param_descriptor->additional_constraints, allocator); + if (NULL == out_param_descriptor->additional_constraints) { + RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); + return false; + } + } + if (NULL != param_descriptor->type) { + out_param_descriptor->type = allocator.allocate(sizeof(uint8_t), allocator.state); + if (NULL == out_param_descriptor->type) { + RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); + return false; + } + *(out_param_descriptor->type) = *(param_descriptor->type); + } + 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"); + return false; + } + *(out_param_descriptor->min_value_int) = *(param_descriptor->min_value_int); + } + if (NULL != param_descriptor->min_value_double) { + out_param_descriptor->min_value_double = + allocator.allocate(sizeof(double), allocator.state); + if (NULL == out_param_descriptor->min_value_double) { + RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); + return false; + } + *(out_param_descriptor->min_value_double) = *(param_descriptor->min_value_double); + } + 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"); + return false; + } + *(out_param_descriptor->max_value_int) = *(param_descriptor->max_value_int); + } + 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"); + return false; + } + *(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); + if (NULL == out_param_descriptor->step_int) { + RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); + return false; + } + *(out_param_descriptor->step_int) = *(param_descriptor->step_int); + } + 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"); + return false; + } + *(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); + if (NULL == out_param_descriptor->read_only) { + RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); + return false; + } + *(out_param_descriptor->read_only) = *(param_descriptor->read_only); + } + return true; +} From f337a6ac40cceba8b75c0bd45536d2a3b2587197 Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Sat, 13 Mar 2021 01:32:49 +0000 Subject: [PATCH 04/19] add node_params_descriptors init and re/deallocation Signed-off-by: Brian Wilcox --- .../src/impl/node_params_descriptors.h | 69 +++++++++ .../src/node_params_descriptors.c | 145 ++++++++++++++++++ 2 files changed, 214 insertions(+) create mode 100644 rcl_yaml_param_parser/src/impl/node_params_descriptors.h create mode 100644 rcl_yaml_param_parser/src/node_params_descriptors.c diff --git a/rcl_yaml_param_parser/src/impl/node_params_descriptors.h b/rcl_yaml_param_parser/src/impl/node_params_descriptors.h new file mode 100644 index 000000000..7e50b7cdf --- /dev/null +++ b/rcl_yaml_param_parser/src/impl/node_params_descriptors.h @@ -0,0 +1,69 @@ +// 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. + +#ifndef IMPL__NODE_PARAMS_DESCRIPTORS_H_ +#define IMPL__NODE_PARAMS_DESCRIPTORS_H_ + +#include "rcl_yaml_param_parser/types.h" +#include "rcl_yaml_param_parser/visibility_control.h" + +#ifdef __cplusplus +extern "C" +{ +#endif + +/// +/// Create rcl_node_params_descriptors_t structure +/// +RCL_YAML_PARAM_PARSER_PUBLIC +RCUTILS_WARN_UNUSED +rcutils_ret_t node_params_descriptors_init( + rcl_node_params_descriptors_t * node_descriptors, + const rcutils_allocator_t allocator); + +/// +/// Create rcl_node_params_descriptors_t structure with a capacity +/// +RCL_YAML_PARAM_PARSER_PUBLIC +RCUTILS_WARN_UNUSED +rcutils_ret_t node_params_descriptors_init_with_capacity( + rcl_node_params_descriptors_t * node_descriptors, + size_t capacity, + const rcutils_allocator_t allocator); + +/// +/// Reallocate rcl_node_params_descriptors_t structure with a new capacity +/// \post the address of \p parameter_names in \p node_params might be changed +/// even if the result value is `RCL_RET_BAD_ALLOC`. +/// +RCL_YAML_PARAM_PARSER_PUBLIC +RCUTILS_WARN_UNUSED +rcutils_ret_t node_params_descriptors_reallocate( + rcl_node_params_descriptors_t * node_descriptors, + size_t new_capacity, + const rcutils_allocator_t allocator); + +/// +/// Finalize rcl_node_params_descriptors_t structure +/// +RCL_YAML_PARAM_PARSER_PUBLIC +void rcl_yaml_node_params_descriptors_fini( + rcl_node_params_descriptors_t * node_descriptors, + const rcutils_allocator_t allocator); + +#ifdef __cplusplus +} +#endif + +#endif // IMPL__NODE_PARAMS_DESCRIPTORS_H_ diff --git a/rcl_yaml_param_parser/src/node_params_descriptors.c b/rcl_yaml_param_parser/src/node_params_descriptors.c new file mode 100644 index 000000000..272074746 --- /dev/null +++ b/rcl_yaml_param_parser/src/node_params_descriptors.c @@ -0,0 +1,145 @@ +// 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 "./impl/node_params_descriptors.h" +#include "./impl/types.h" +#include "./impl/yaml_descriptor.h" + +#define INIT_NUM_PARAMS_DESCRIPTORS_PER_NODE 128U + +rcutils_ret_t node_params_descriptors_init( + rcl_node_params_descriptors_t * node_descriptors, + const rcutils_allocator_t allocator) +{ + return node_params_descriptors_init_with_capacity(node_descriptors, INIT_NUM_PARAMS_DESCRIPTORS_PER_NODE, allocator); +} + +rcutils_ret_t node_params_descriptors_init_with_capacity( + rcl_node_params_descriptors_t * node_descriptors, + size_t capacity, + const rcutils_allocator_t allocator) +{ + RCUTILS_CHECK_ARGUMENT_FOR_NULL(node_descriptors, RCUTILS_RET_INVALID_ARGUMENT); + RCUTILS_CHECK_ALLOCATOR_WITH_MSG( + &allocator, "invalid allocator", return RCUTILS_RET_INVALID_ARGUMENT); + if (capacity == 0) { + RCUTILS_SET_ERROR_MSG("capacity can't be zero"); + return RCUTILS_RET_INVALID_ARGUMENT; + } + + node_descriptors->parameter_names = allocator.zero_allocate( + capacity, sizeof(char *), allocator.state); + if (NULL == node_descriptors->parameter_names) { + RCUTILS_SET_ERROR_MSG("Failed to allocate memory for node parameter names"); + return RCUTILS_RET_BAD_ALLOC; + } + + node_descriptors->parameter_descriptors = allocator.zero_allocate( + capacity, sizeof(rcl_param_descriptor_t), allocator.state); + if (NULL == node_descriptors->parameter_descriptors) { + allocator.deallocate(node_descriptors->parameter_names, allocator.state); + node_descriptors->parameter_names = NULL; + RCUTILS_SET_ERROR_MSG("Failed to allocate memory for node parameter values"); + return RCUTILS_RET_BAD_ALLOC; + } + + node_descriptors->num_params = 0U; + node_descriptors->capacity_descriptors = capacity; + return RCUTILS_RET_OK; +} + +rcutils_ret_t node_params_descriptors_reallocate( + rcl_node_params_descriptors_t * node_descriptors, + size_t new_capacity, + const rcutils_allocator_t allocator) +{ + RCUTILS_CHECK_ARGUMENT_FOR_NULL(node_descriptors, RCUTILS_RET_INVALID_ARGUMENT); + RCUTILS_CHECK_ALLOCATOR_WITH_MSG( + &allocator, "invalid allocator", return RCUTILS_RET_INVALID_ARGUMENT); + // invalid if new_capacity is less than num_params + if (new_capacity < node_descriptors->num_params) { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "new capacity '%zu' must be greater than or equal to '%zu'", + new_capacity, + node_descriptors->num_params); + return RCUTILS_RET_INVALID_ARGUMENT; + } + + void * parameter_names = allocator.reallocate( + node_descriptors->parameter_names, new_capacity * sizeof(char *), allocator.state); + if (NULL == parameter_names) { + RCUTILS_SET_ERROR_MSG("Failed to reallocate node parameter names"); + return RCUTILS_RET_BAD_ALLOC; + } + node_descriptors->parameter_names = parameter_names; + // zero initialization for the added memory + if (new_capacity > node_descriptors->capacity_descriptors) { + memset( + node_descriptors->parameter_names + node_descriptors->capacity_descriptors, 0, + (new_capacity - node_descriptors->capacity_descriptors) * sizeof(char *)); + } + + void * parameter_descriptors = allocator.reallocate( + node_descriptors->parameter_descriptors, new_capacity * sizeof(rcl_param_descriptor_t), allocator.state); + if (NULL == parameter_descriptors) { + RCUTILS_SET_ERROR_MSG("Failed to reallocate node parameter values"); + return RCUTILS_RET_BAD_ALLOC; + } + node_descriptors->parameter_descriptors = parameter_descriptors; + // zero initialization for the added memory + if (new_capacity > node_descriptors->capacity_descriptors) { + memset( + &node_descriptors->parameter_descriptors[node_descriptors->capacity_descriptors], 0, + (new_capacity - node_descriptors->capacity_descriptors) * sizeof(rcl_param_descriptor_t)); + } + + node_descriptors->capacity_descriptors = new_capacity; + return RCUTILS_RET_OK; +} + +void rcl_yaml_node_params_descriptors_fini( + rcl_node_params_descriptors_t * node_descriptors, + const rcutils_allocator_t allocator) +{ + if (NULL == node_descriptors) { + return; + } + + if (NULL != node_descriptors->parameter_names) { + for (size_t parameter_idx = 0U; parameter_idx < node_descriptors->num_params; + parameter_idx++) + { + char * param_name = node_descriptors->parameter_names[parameter_idx]; + if (NULL != param_name) { + allocator.deallocate(param_name, allocator.state); + } + } + allocator.deallocate(node_descriptors->parameter_names, allocator.state); + node_descriptors->parameter_names = NULL; + } + + if (NULL != node_descriptors->parameter_descriptors) { + for (size_t parameter_idx = 0U; parameter_idx < node_descriptors->num_params; + parameter_idx++) + { + rcl_yaml_descriptor_fini(&(node_descriptors->parameter_descriptors[parameter_idx]), allocator); + } + + allocator.deallocate(node_descriptors->parameter_descriptors, allocator.state); + node_descriptors->parameter_descriptors = NULL; + } + + node_descriptors->num_params = 0; + node_descriptors->capacity_descriptors = 0; +} From 702c448ca1edeb81c6fc90024c2eb652b0af4d7f Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Tue, 16 Mar 2021 05:20:32 +0000 Subject: [PATCH 05/19] add find_descriptor, parse_desriptor, and modify parse file events and parse key for descriptor map level Signed-off-by: Brian Wilcox --- rcl_yaml_param_parser/src/impl/parse.h | 18 ++ rcl_yaml_param_parser/src/parse.c | 336 ++++++++++++++++++++++++- 2 files changed, 345 insertions(+), 9 deletions(-) diff --git a/rcl_yaml_param_parser/src/impl/parse.h b/rcl_yaml_param_parser/src/impl/parse.h index 781e8f52d..b65673b64 100644 --- a/rcl_yaml_param_parser/src/impl/parse.h +++ b/rcl_yaml_param_parser/src/impl/parse.h @@ -46,6 +46,16 @@ rcutils_ret_t parse_value( data_types_t * seq_data_type, rcl_params_t * params_st); +RCL_YAML_PARAM_PARSER_PUBLIC +RCUTILS_WARN_UNUSED +rcutils_ret_t parse_descriptor( + namespace_tracker_t * ns_tracker, + const yaml_event_t event, + const bool is_seq, + const size_t node_idx, + const size_t parameter_idx, + rcl_params_t * params_st); + RCL_YAML_PARAM_PARSER_PUBLIC RCUTILS_WARN_UNUSED rcutils_ret_t parse_key( @@ -87,6 +97,14 @@ rcutils_ret_t find_parameter( rcl_params_t * param_st, size_t * parameter_idx); +RCL_YAML_PARAM_PARSER_PUBLIC +RCUTILS_WARN_UNUSED +rcutils_ret_t find_descriptor( + const size_t node_idx, + const char * parameter_name, + rcl_params_t * param_st, + size_t * parameter_idx); + #ifdef __cplusplus } #endif diff --git a/rcl_yaml_param_parser/src/parse.c b/rcl_yaml_param_parser/src/parse.c index acce68a92..03d007aa3 100644 --- a/rcl_yaml_param_parser/src/parse.c +++ b/rcl_yaml_param_parser/src/parse.c @@ -29,6 +29,7 @@ #include "./impl/parse.h" #include "./impl/namespace.h" #include "./impl/node_params.h" +#include "./impl/node_params_descriptors.h" #include "rcl_yaml_param_parser/parser.h" #include "rcl_yaml_param_parser/visibility_control.h" @@ -445,6 +446,165 @@ rcutils_ret_t parse_value( return ret; } +rcutils_ret_t parse_descriptor( + namespace_tracker_t * ns_tracker, + const yaml_event_t event, + const bool is_seq, + const size_t node_idx, + const size_t parameter_idx, + rcl_params_t * params_st) +{ + RCUTILS_CHECK_ARGUMENT_FOR_NULL(params_st, RCUTILS_RET_INVALID_ARGUMENT); + + rcutils_allocator_t allocator = params_st->allocator; + RCUTILS_CHECK_ALLOCATOR_WITH_MSG( + &allocator, "invalid allocator", return RCUTILS_RET_INVALID_ARGUMENT); + + if (0U == params_st->num_nodes) { + RCUTILS_SET_ERROR_MSG("No node to update"); + return RCUTILS_RET_INVALID_ARGUMENT; + } + + const size_t val_size = event.data.scalar.length; + const char * value = (char *)event.data.scalar.value; + yaml_scalar_style_t style = event.data.scalar.style; + const uint32_t line_num = ((uint32_t)(event.start_mark.line) + 1U); + + RCUTILS_CHECK_FOR_NULL_WITH_MSG( + value, "event argument has no value", return RCUTILS_RET_INVALID_ARGUMENT); + + if (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 (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->descriptors[node_idx].parameter_descriptors) { + RCUTILS_SET_ERROR_MSG("Internal error: Invalid mem"); + return RCUTILS_RET_BAD_ALLOC; + } + + rcl_param_descriptor_t * param_descriptor = + &(params_st->descriptors[node_idx].parameter_descriptors[parameter_idx]); + + data_types_t val_type; + void * ret_val = get_value(value, style, &val_type, allocator); + if (NULL == ret_val) { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Error parsing value %s at line %d", value, line_num); + return RCUTILS_RET_ERROR; + } + + if (NULL == ns_tracker->parameter_ns) { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Parameter assignment at line %d unallowed in " PARAMS_DESCRIPTORS_KEY, line_num); + return RCUTILS_RET_ERROR; + } + // 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++; + } + + 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; + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Value type 'string' expected at line %d for " + PARAMS_DESCRIPTORS_KEY " 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; + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Value type 'integer' expected at line %d for " PARAMS_DESCRIPTORS_KEY " 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->min_value_int = (int64_t *)ret_val; + } else if (val_type == DATA_TYPE_DOUBLE) { + param_descriptor->min_value_double = (double *)ret_val; + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Value type 'integer' or 'double' expected at line %d for " + PARAMS_DESCRIPTORS_KEY " 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->max_value_int = (int64_t *)ret_val; + } else if (val_type == DATA_TYPE_DOUBLE) { + param_descriptor->max_value_double = (double *)ret_val; + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Value type 'integer' or 'double' expected at line %d for " + PARAMS_DESCRIPTORS_KEY " 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) { + param_descriptor->read_only = (bool *)ret_val; + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Value type 'bool' expected at line %d for " PARAMS_DESCRIPTORS_KEY " 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) { + param_descriptor->description = (char *)ret_val; + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Value type 'string' expected at line %d for " PARAMS_DESCRIPTORS_KEY " 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) { + param_descriptor->step_int = (int64_t *)ret_val; + } else if (val_type == DATA_TYPE_DOUBLE) { + param_descriptor->step_double = (double *)ret_val; + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Value type 'integer' or 'double' expected at line %d for " PARAMS_DESCRIPTORS_KEY " key: step", + line_num); + return RCUTILS_RET_ERROR; + } + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Descriptor key at line %d does not match any valid " PARAMS_DESCRIPTORS_KEY " key", + line_num); + return RCUTILS_RET_ERROR; + } + + return RCUTILS_RET_OK; +} + rcutils_ret_t _validate_namespace(const char * namespace_) { @@ -616,18 +776,39 @@ rcutils_ret_t parse_key( break; case MAP_NODE_NAME_LVL: { - /// Till we get PARAMS_KEY, keep adding to node namespace - if (0 != strncmp(PARAMS_KEY, value, strlen(PARAMS_KEY))) { - ret = add_name_to_ns(ns_tracker, value, NS_TYPE_NODE, allocator); + /// Till we get PARAMS_KEY or PARAMS_DESCRIPTORS_KEY, keep adding to node namespace + if (0 == strncmp(PARAMS_KEY, value, strlen(PARAMS_KEY))) { + if (0U == ns_tracker->num_node_ns) { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "There are no node names before %s at line %d", PARAMS_KEY, line_num); + ret = RCUTILS_RET_ERROR; + break; + } + /// The previous key(last name in namespace) was the node name. Remove it + /// from the namespace + char * node_name_ns = rcutils_strdup(ns_tracker->node_ns, allocator); + if (NULL == node_name_ns) { + ret = RCUTILS_RET_BAD_ALLOC; + break; + } + + ret = find_node(node_name_ns, params_st, node_idx); + if (RCUTILS_RET_OK != ret) { + break; + } + + ret = rem_name_from_ns(ns_tracker, NS_TYPE_NODE, allocator); if (RCUTILS_RET_OK != ret) { RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( "Internal error adding node namespace at line %d", line_num); break; } - } else { + /// Bump the map level to PARAMS + (*map_level)++; + } else if (0 == strncmp(PARAMS_DESCRIPTORS_KEY, value, strlen(PARAMS_DESCRIPTORS_KEY))) { if (0U == ns_tracker->num_node_ns) { RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( - "There are no node names before %s at line %d", PARAMS_KEY, line_num); + "There are no node names before %s at line %d", PARAMS_DESCRIPTORS_KEY, line_num); ret = RCUTILS_RET_ERROR; break; } @@ -652,13 +833,20 @@ rcutils_ret_t parse_key( } ret = rem_name_from_ns(ns_tracker, NS_TYPE_NODE, allocator); + if (RCUTILS_RET_OK != ret) { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Internal error adding node namespace at line %d", line_num); + break; + } + /// Bump the map level to PARAMS_DESCRIPTOR + *map_level = 3U; + } else { + ret = add_name_to_ns(ns_tracker, value, NS_TYPE_NODE, allocator); if (RCUTILS_RET_OK != ret) { RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( "Internal error adding node namespace at line %d", line_num); break; } - /// Bump the map level to PARAMS - (*map_level)++; } } break; @@ -725,6 +913,74 @@ rcutils_ret_t parse_key( } } break; + case MAP_PARAMS_DESCRIPTORS_LVL: + { + char * parameter_ns = NULL; + char * param_name = NULL; + + /// If it is a new map, the previous key is param namespace + if (*is_new_map) { + parameter_ns = params_st->descriptors[*node_idx].parameter_names[*parameter_idx]; + if (NULL == parameter_ns) { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Internal error creating param namespace at line %d", line_num); + ret = RCUTILS_RET_ERROR; + break; + } + ret = replace_ns(ns_tracker, parameter_ns, (ns_tracker->num_parameter_ns + 1U), + NS_TYPE_PARAM, allocator); + if (RCUTILS_RET_OK != ret) { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Internal error replacing namespace at line %d", line_num); + ret = RCUTILS_RET_ERROR; + break; + } + *is_new_map = false; + } + + /// Add a parameter name into the node parameter descriptors + parameter_ns = ns_tracker->parameter_ns; + if (NULL == parameter_ns) { + ret = find_descriptor(*node_idx, value, params_st, parameter_idx); + if (ret != RCUTILS_RET_OK) { + break; + } + } else { + ret = find_descriptor(*node_idx, parameter_ns, params_st, parameter_idx); + if (ret != RCUTILS_RET_OK) { + break; + } + + ret = + replace_ns(ns_tracker, rcutils_strdup(value, allocator), + (ns_tracker->num_descriptor_key_ns + 1U), + NS_TYPE_DESCRIPTOR, allocator); + if (RCUTILS_RET_OK != ret) { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Internal error replacing namespace at line %d", line_num); + ret = RCUTILS_RET_ERROR; + break; + } + + const size_t params_ns_len = strlen(parameter_ns); + const size_t param_name_len = strlen(value); + const size_t tot_len = (params_ns_len + param_name_len + 2U); + + param_name = allocator.zero_allocate(1U, tot_len, allocator.state); + if (NULL == param_name) { + ret = RCUTILS_RET_BAD_ALLOC; + break; + } + + memcpy(param_name, parameter_ns, params_ns_len); + param_name[params_ns_len] = '.'; + memcpy((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; + } + } + break; default: RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING("Unknown map level at line %d", line_num); ret = RCUTILS_RET_ERROR; @@ -801,13 +1057,18 @@ rcutils_ret_t parse_file_events( yaml_event_delete(&event); return RCUTILS_RET_ERROR; } - if (0U == params_st->params[node_idx].num_params) { + if (0U == params_st->params[node_idx].num_params && map_level != 3U) { RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( "Cannot have a value before %s at line %d", PARAMS_KEY, line_num); yaml_event_delete(&event); return RCUTILS_RET_ERROR; } - ret = parse_value(event, is_seq, node_idx, parameter_idx, &seq_data_type, params_st); + if (map_level != 3U) { + ret = parse_value(event, is_seq, node_idx, parameter_idx, &seq_data_type, params_st); + } else { + ret = parse_descriptor(ns_tracker, event, is_seq, node_idx, parameter_idx, + params_st); + } if (RCUTILS_RET_OK != ret) { break; } @@ -847,6 +1108,11 @@ rcutils_ret_t parse_file_events( { is_new_map = false; } + if ((MAP_PARAMS_DESCRIPTORS_LVL == map_level) && + ((map_depth - (ns_tracker->num_node_ns + 1U)) == 2U)) + { + is_new_map = false; + } break; case YAML_MAPPING_END_EVENT: if (MAP_PARAMS_LVL == map_level) { @@ -861,6 +1127,18 @@ rcutils_ret_t parse_file_events( } else { map_level--; } + } else if (MAP_PARAMS_DESCRIPTORS_LVL == map_level) { + if (ns_tracker->num_parameter_ns > 0U) { + /// Remove param namesapce + ret = rem_name_from_ns(ns_tracker, NS_TYPE_PARAM, allocator); + if (RCUTILS_RET_OK != ret) { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Internal error removing parameter namespace at line %d", line_num); + break; + } + } else { + map_level = 1U; + } } else { if ((MAP_NODE_NAME_LVL == map_level) && (map_depth == (ns_tracker->num_node_ns + 1U))) @@ -1002,6 +1280,38 @@ rcutils_ret_t find_parameter( return RCUTILS_RET_OK; } +/// +/// Find parameter descriptor entry index in node parameters' structure +/// +rcutils_ret_t find_descriptor( + const size_t node_idx, + const char * parameter_name, + rcl_params_t * param_st, + size_t * parameter_idx) +{ + assert(NULL != parameter_name); + assert(NULL != param_st); + assert(NULL != parameter_idx); + + assert(node_idx < param_st->num_nodes); + + rcl_node_params_descriptors_t * node_descriptors_st = &(param_st->descriptors[node_idx]); + for (*parameter_idx = 0U; *parameter_idx < node_descriptors_st->num_params; (*parameter_idx)++) { + if (0 == strcmp(node_descriptors_st->parameter_names[*parameter_idx], parameter_name)) { + // Parameter found. + return RCUTILS_RET_OK; + } + } + // Parameter not found, add it. + rcutils_allocator_t allocator = param_st->allocator; + node_descriptors_st->parameter_names[*parameter_idx] = rcutils_strdup(parameter_name, allocator); + if (NULL == node_descriptors_st->parameter_names[*parameter_idx]) { + return RCUTILS_RET_BAD_ALLOC; + } + // node_descriptors_st->num_params++; + return RCUTILS_RET_OK; +} + /// /// Find node entry index in parameters' structure /// @@ -1040,6 +1350,14 @@ rcutils_ret_t find_node( param_st->node_names[*node_idx] = NULL; return ret; } + + ret = node_params_descriptors_init(&(param_st->descriptors[*node_idx]), allocator); + if (RCUTILS_RET_OK != ret) { + allocator.deallocate(param_st->node_names[*node_idx], allocator.state); + param_st->node_names[*node_idx] = NULL; + return ret; + } + param_st->num_nodes++; return RCUTILS_RET_OK; } From 817bce1a497656da1e4559b754ed9cd608630a41 Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Tue, 16 Mar 2021 05:21:27 +0000 Subject: [PATCH 06/19] modify replace ns with parameter descriptor level Signed-off-by: Brian Wilcox --- rcl_yaml_param_parser/src/namespace.c | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/rcl_yaml_param_parser/src/namespace.c b/rcl_yaml_param_parser/src/namespace.c index 0ca3fed67..d11b883c1 100644 --- a/rcl_yaml_param_parser/src/namespace.c +++ b/rcl_yaml_param_parser/src/namespace.c @@ -184,6 +184,16 @@ rcutils_ret_t replace_ns( } ns_tracker->num_parameter_ns = new_ns_count; break; + case NS_TYPE_DESCRIPTOR: + if (NULL != ns_tracker->descriptor_key_ns) { + allocator.deallocate(ns_tracker->descriptor_key_ns, allocator.state); + } + ns_tracker->descriptor_key_ns = rcutils_strdup(new_ns, allocator); + if (NULL == ns_tracker->descriptor_key_ns) { + return RCUTILS_RET_BAD_ALLOC; + } + ns_tracker->num_descriptor_key_ns = new_ns_count; + break; default: res = RCUTILS_RET_ERROR; break; From 2640d09ab5185260b818bc7f7d7a89f8cfa579b2 Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Tue, 16 Mar 2021 05:23:08 +0000 Subject: [PATCH 07/19] modify parser implementation for parameter descriptors, add get param descriptor struct API Signed-off-by: Brian Wilcox --- .../include/rcl_yaml_param_parser/parser.h | 11 ++ rcl_yaml_param_parser/src/parser.c | 153 +++++++++++++++++- 2 files changed, 163 insertions(+), 1 deletion(-) 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 23cb04d06..03cd7c17c 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 @@ -119,6 +119,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/src/parser.c b/rcl_yaml_param_parser/src/parser.c index 028ad870e..66186772d 100644 --- a/rcl_yaml_param_parser/src/parser.c +++ b/rcl_yaml_param_parser/src/parser.c @@ -33,7 +33,9 @@ #include "./impl/types.h" #include "./impl/parse.h" #include "./impl/node_params.h" +#include "./impl/node_params_descriptors.h" #include "./impl/yaml_variant.h" +#include "./impl/yaml_descriptor.h" #define INIT_NUM_NODE_ENTRIES 128U @@ -79,6 +81,15 @@ rcl_params_t * rcl_yaml_node_struct_init_with_capacity( goto clean; } + params_st->descriptors = allocator.zero_allocate( + capacity, sizeof(rcl_node_params_descriptors_t), allocator.state); + if (NULL == params_st->descriptors) { + allocator.deallocate(params_st->node_names, allocator.state); + params_st->node_names = NULL; + RCUTILS_SET_ERROR_MSG("Failed to allocate memory for parameter descriptors"); + goto clean; + } + params_st->num_nodes = 0U; params_st->capacity_nodes = capacity; return params_st; @@ -126,6 +137,15 @@ rcutils_ret_t rcl_yaml_node_struct_reallocate( return RCUTILS_RET_BAD_ALLOC; } params_st->params = params; + + void * descriptors = allocator.reallocate( + params_st->descriptors, new_capacity * sizeof(rcl_node_params_descriptors_t), allocator.state); + if (NULL == descriptors) { + RCUTILS_SET_ERROR_MSG("Failed to reallocate memory for parameter descriptors"); + return RCUTILS_RET_BAD_ALLOC; + } + params_st->descriptors = descriptors; + // zero initialization for the added memory if (new_capacity > params_st->capacity_nodes) { memset( @@ -192,6 +212,34 @@ rcl_params_t * rcl_yaml_node_struct_copy( goto fail; } } + + rcl_node_params_descriptors_t * node_params_descriptors_st = &(params_st->descriptors[node_idx]); + rcl_node_params_descriptors_t * out_node_params_descriptors_st = &(out_params_st->descriptors[node_idx]); + ret = node_params_descriptors_init_with_capacity( + out_node_params_descriptors_st, + node_params_descriptors_st->capacity_descriptors, + allocator); + if (RCUTILS_RET_OK != ret) { + if (RCUTILS_RET_BAD_ALLOC == ret) { + RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n"); + } + goto fail; + } + for (size_t descriptor_idx = 0U; descriptor_idx < node_params_descriptors_st->num_params; ++descriptor_idx) { + out_node_params_descriptors_st->parameter_names[descriptor_idx] = + rcutils_strdup(node_params_descriptors_st->parameter_names[descriptor_idx], allocator); + if (NULL == out_node_params_descriptors_st->parameter_names[descriptor_idx]) { + RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n"); + goto fail; + } + out_node_params_descriptors_st->num_params++; + + const rcl_param_descriptor_t * param_descriptor = &(node_params_descriptors_st->parameter_descriptors[descriptor_idx]); + rcl_param_descriptor_t * out_param_descriptor = &(out_node_params_descriptors_st->parameter_descriptors[descriptor_idx]); + if (!rcl_yaml_descriptor_copy(out_param_descriptor, param_descriptor, allocator)) { + goto fail; + } + } } return out_params_st; @@ -234,6 +282,15 @@ void rcl_yaml_node_struct_fini( params_st->params = NULL; } // if (params) + if (NULL != params_st->descriptors) { + for (size_t node_idx = 0U; node_idx < params_st->num_nodes; node_idx++) { + rcl_yaml_node_params_descriptors_fini(&(params_st->descriptors[node_idx]), allocator); + } // for (node_idx) + + allocator.deallocate(params_st->descriptors, allocator.state); + params_st->descriptors = NULL; + } // if (descriptors) + params_st->num_nodes = 0U; params_st->capacity_nodes = 0U; allocator.deallocate(params_st, allocator.state); @@ -288,7 +345,9 @@ bool rcl_parse_yaml_file( if (NULL != ns_tracker.parameter_ns) { allocator.deallocate(ns_tracker.parameter_ns, allocator.state); } - + if (NULL != ns_tracker.descriptor_key_ns) { + allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); + } return RCUTILS_RET_OK == ret; } @@ -366,6 +425,29 @@ 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 /// @@ -446,4 +528,73 @@ void rcl_yaml_node_struct_print( } } } + printf("\n Node Name\t\t\t\tParameter Descriptors\n"); + for (size_t node_idx = 0U; node_idx < params_st->num_nodes; node_idx++) { + int32_t param_col = 50; + const char * const node_name = params_st->node_names[node_idx]; + if (NULL != node_name) { + printf("%s\n", node_name); + } + + if (NULL != params_st->descriptors) { + rcl_node_params_descriptors_t * node_descriptors_st = &(params_st->descriptors[node_idx]); + for (size_t parameter_idx = 0U; parameter_idx < node_descriptors_st->num_params; + parameter_idx++) + { + if (NULL != node_descriptors_st->parameter_names) { + char * param_name = node_descriptors_st->parameter_names[parameter_idx]; + if (NULL != param_name) { + printf("%*s:", param_col, param_name); + } + rcl_param_descriptor_t * descriptor = + &(node_descriptors_st->parameter_descriptors[parameter_idx]); + if (NULL != descriptor->name) { + printf("\n%*sname: ", param_col + 2, ""); + printf("%s", descriptor->name); + } + if (NULL != descriptor->description) { + printf("\n%*sdescription: ", param_col + 2, ""); + printf("%s", descriptor->description); + } + if (NULL != descriptor->additional_constraints) { + printf("\n%*sadditional_constraints: ", param_col + 2, ""); + printf("%s", descriptor->additional_constraints); + } + if (NULL != descriptor->type) { + printf("\n%*stype: ", param_col + 2, ""); + printf("%d", *(descriptor->type)); + } + if (NULL != descriptor->min_value_int) { + printf("\n%*smin_value: ", param_col + 2, ""); + printf("%ld", *(descriptor->min_value_int)); + } + if (NULL != descriptor->min_value_double) { + printf("\n%*smin_value: ", param_col + 2, ""); + printf("%lf", *(descriptor->min_value_double)); + } + if (NULL != descriptor->max_value_int) { + printf("\n%*smax_value: ", param_col + 2, ""); + printf("%ld", *(descriptor->max_value_int)); + } + 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_double) { + printf("\n%*sstep: ", param_col + 2, ""); + printf("%lf", *(descriptor->step_double)); + } + if (NULL != descriptor->read_only) { + printf("\n%*sread_only: ", param_col + 2, ""); + printf("%s", *(descriptor->read_only) ? "true" : "false"); + } + printf("\n"); + } + } + } + } } From b299ff25909c09c0ac8ee40f9e1a4bcc3cb4a989 Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Tue, 16 Mar 2021 05:23:55 +0000 Subject: [PATCH 08/19] add new files to CMakeLists Signed-off-by: Brian Wilcox --- rcl_yaml_param_parser/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/rcl_yaml_param_parser/CMakeLists.txt b/rcl_yaml_param_parser/CMakeLists.txt index 397f662ae..5825afb78 100644 --- a/rcl_yaml_param_parser/CMakeLists.txt +++ b/rcl_yaml_param_parser/CMakeLists.txt @@ -22,9 +22,11 @@ endif() set(rcl_yaml_parser_sources src/add_to_arrays.c src/namespace.c + src/node_params_descriptors.c src/node_params.c src/parse.c src/parser.c + src/yaml_descriptor.c src/yaml_variant.c ) From ce49272e8bdfb11380242011e95cc0289466e762 Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Wed, 17 Mar 2021 04:38:14 +0000 Subject: [PATCH 09/19] check for new map at MAP_NODE_NAME_LVL: fixes issue to allow both parameters and descriptors under node name in yaml Signed-off-by: Brian Wilcox --- rcl_yaml_param_parser/src/parse.c | 93 +++++++++++++++++++------------ 1 file changed, 56 insertions(+), 37 deletions(-) diff --git a/rcl_yaml_param_parser/src/parse.c b/rcl_yaml_param_parser/src/parse.c index 03d007aa3..4f1b8c69f 100644 --- a/rcl_yaml_param_parser/src/parse.c +++ b/rcl_yaml_param_parser/src/parse.c @@ -784,25 +784,35 @@ rcutils_ret_t parse_key( ret = RCUTILS_RET_ERROR; break; } - /// The previous key(last name in namespace) was the node name. Remove it - /// from the namespace - char * node_name_ns = rcutils_strdup(ns_tracker->node_ns, allocator); - if (NULL == node_name_ns) { - ret = RCUTILS_RET_BAD_ALLOC; - break; - } - ret = find_node(node_name_ns, params_st, node_idx); - if (RCUTILS_RET_OK != ret) { - break; - } + if (*is_new_map) { + /// The previous key(last name in namespace) was the node name. Remove it + /// from the namespace + char * node_name_ns = rcutils_strdup(ns_tracker->node_ns, allocator); + if (NULL == node_name_ns) { + ret = RCUTILS_RET_BAD_ALLOC; + break; + } - ret = rem_name_from_ns(ns_tracker, NS_TYPE_NODE, allocator); - if (RCUTILS_RET_OK != ret) { - RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( - "Internal error adding node namespace at line %d", line_num); - break; + ret = _validate_name(node_name_ns, allocator); + if (RCUTILS_RET_OK != ret) { + allocator.deallocate(node_name_ns, allocator.state); + break; + } + + ret = find_node(node_name_ns, params_st, node_idx); + if (RCUTILS_RET_OK != ret) { + break; + } + + ret = rem_name_from_ns(ns_tracker, NS_TYPE_NODE, allocator); + if (RCUTILS_RET_OK != ret) { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Internal error adding node namespace at line %d", line_num); + break; + } } + /// Bump the map level to PARAMS (*map_level)++; } else if (0 == strncmp(PARAMS_DESCRIPTORS_KEY, value, strlen(PARAMS_DESCRIPTORS_KEY))) { @@ -812,32 +822,36 @@ rcutils_ret_t parse_key( ret = RCUTILS_RET_ERROR; break; } - /// The previous key(last name in namespace) was the node name. Remove it - /// from the namespace - char * node_name_ns = rcutils_strdup(ns_tracker->node_ns, allocator); - if (NULL == node_name_ns) { - ret = RCUTILS_RET_BAD_ALLOC; - break; - } - ret = _validate_name(node_name_ns, allocator); - if (RCUTILS_RET_OK != ret) { + if (*is_new_map) { + /// The previous key(last name in namespace) was the node name. Remove it + /// from the namespace + char * node_name_ns = rcutils_strdup(ns_tracker->node_ns, allocator); + if (NULL == node_name_ns) { + ret = RCUTILS_RET_BAD_ALLOC; + break; + } + + ret = _validate_name(node_name_ns, allocator); + if (RCUTILS_RET_OK != ret) { + allocator.deallocate(node_name_ns, allocator.state); + break; + } + + ret = find_node(node_name_ns, params_st, node_idx); allocator.deallocate(node_name_ns, allocator.state); - break; - } + if (RCUTILS_RET_OK != ret) { + break; + } - ret = find_node(node_name_ns, params_st, node_idx); - allocator.deallocate(node_name_ns, allocator.state); - if (RCUTILS_RET_OK != ret) { - break; + ret = rem_name_from_ns(ns_tracker, NS_TYPE_NODE, allocator); + if (RCUTILS_RET_OK != ret) { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Internal error adding node namespace at line %d", line_num); + break; + } } - ret = rem_name_from_ns(ns_tracker, NS_TYPE_NODE, allocator); - if (RCUTILS_RET_OK != ret) { - RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( - "Internal error adding node namespace at line %d", line_num); - break; - } /// Bump the map level to PARAMS_DESCRIPTOR *map_level = 3U; } else { @@ -977,6 +991,11 @@ rcutils_ret_t parse_key( memcpy((param_name + params_ns_len + 1U), value, param_name_len); param_name[tot_len - 1U] = '\0'; + if (NULL != params_st->descriptors[*node_idx].parameter_names[*parameter_idx]) { + // This memory was allocated in find_parameter(), and its pointer is being overwritten + allocator.deallocate( + params_st->descriptors[*node_idx].parameter_names[*parameter_idx], allocator.state); + } params_st->descriptors[*node_idx].parameter_names[*parameter_idx] = param_name; } } From 7836801d6d29c84ddd9413506663710ae0b01cc2 Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Wed, 17 Mar 2021 04:40:10 +0000 Subject: [PATCH 10/19] fix test now that more calloc calls with param descriptors Signed-off-by: Brian Wilcox --- rcl_yaml_param_parser/test/test_parser.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rcl_yaml_param_parser/test/test_parser.cpp b/rcl_yaml_param_parser/test/test_parser.cpp index d627cc8fe..be8d13e29 100644 --- a/rcl_yaml_param_parser/test/test_parser.cpp +++ b/rcl_yaml_param_parser/test/test_parser.cpp @@ -117,7 +117,7 @@ TEST(RclYamlParamParser, node_copy) { 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; + constexpr int expected_num_calloc_calls = 8; 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); From 9da55901f96230a69eeaf9a723f81c3e9b420924 Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Wed, 17 Mar 2021 04:41:11 +0000 Subject: [PATCH 11/19] add parameter descriptor yaml tests Signed-off-by: Brian Wilcox --- .../test/assign_param_in_descriptors.yaml | 5 + .../test/correct_param_descriptors.yaml | 30 +++ .../test/invalid_param_descriptor_key.yaml | 5 + .../test/invalid_param_descriptor_type.yaml | 4 + .../test/no_value_descriptor.yaml | 4 + .../test/overlay_descriptors.yaml | 14 ++ .../test/test_parse_yaml.cpp | 175 ++++++++++++++++++ 7 files changed, 237 insertions(+) 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 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 000000000..7702e714e --- /dev/null +++ b/rcl_yaml_param_parser/test/assign_param_in_descriptors.yaml @@ -0,0 +1,5 @@ +node1: + parameter__descriptors: + bar: 42 + foo: + read_only: true 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 000000000..692cf1cd5 --- /dev/null +++ b/rcl_yaml_param_parser/test/correct_param_descriptors.yaml @@ -0,0 +1,30 @@ +# config/test_yaml +--- + +node_ns: + node1: + 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" 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 000000000..104d4e5b7 --- /dev/null +++ b/rcl_yaml_param_parser/test/invalid_param_descriptor_key.yaml @@ -0,0 +1,5 @@ +node1: + 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 000000000..a55510dde --- /dev/null +++ b/rcl_yaml_param_parser/test/invalid_param_descriptor_type.yaml @@ -0,0 +1,4 @@ +node1: + 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 000000000..5b6bc89c8 --- /dev/null +++ b/rcl_yaml_param_parser/test/no_value_descriptor.yaml @@ -0,0 +1,4 @@ +node1: + 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 000000000..34e7555f5 --- /dev/null +++ b/rcl_yaml_param_parser/test/overlay_descriptors.yaml @@ -0,0 +1,14 @@ +node_ns: + node1: + parameter__descriptors: + param1: + max_value: 200 + param2: + min_value: -2.0 + node2: + parameter__descriptors: + foo: + bar: + read_only: true + baz: + description: "other namespaced parameter" diff --git a/rcl_yaml_param_parser/test/test_parse_yaml.cpp b/rcl_yaml_param_parser/test/test_parse_yaml.cpp index 0c50eda91..7b0d3aa4b 100644 --- a/rcl_yaml_param_parser/test/test_parse_yaml.cpp +++ b/rcl_yaml_param_parser/test/test_parse_yaml.cpp @@ -661,6 +661,181 @@ TEST(test_file_parser, wildcards_partial) { } } +TEST(test_file_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); + 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); + 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); + 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); + EXPECT_FALSE(res); +} + int32_t main(int32_t argc, char ** argv) { ::testing::InitGoogleTest(&argc, argv); From 0b8a5d76fcb78342ffc6d5581c627e6efd4fa930 Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Wed, 17 Mar 2021 04:58:46 +0000 Subject: [PATCH 12/19] add parameter to test yaml for extra coverage and verify parsed param outputs Signed-off-by: Brian Wilcox --- .../test/correct_param_descriptors.yaml | 2 ++ rcl_yaml_param_parser/test/test_parse_yaml.cpp | 15 +++++++++++++++ 2 files changed, 17 insertions(+) diff --git a/rcl_yaml_param_parser/test/correct_param_descriptors.yaml b/rcl_yaml_param_parser/test/correct_param_descriptors.yaml index 692cf1cd5..40072f394 100644 --- a/rcl_yaml_param_parser/test/correct_param_descriptors.yaml +++ b/rcl_yaml_param_parser/test/correct_param_descriptors.yaml @@ -16,6 +16,8 @@ node_ns: min_value: 1.0 max_value: 10.0 description: "double parameter" + ros__parameters: + param1: 28 node2: ros__parameters: foo: diff --git a/rcl_yaml_param_parser/test/test_parse_yaml.cpp b/rcl_yaml_param_parser/test/test_parse_yaml.cpp index 7b0d3aa4b..66f4983ef 100644 --- a/rcl_yaml_param_parser/test/test_parse_yaml.cpp +++ b/rcl_yaml_param_parser/test/test_parse_yaml.cpp @@ -748,6 +748,21 @@ TEST(test_file_parser, correct_syntax_descriptors) { ASSERT_TRUE(NULL != param_descriptor->description); EXPECT_STREQ("other namespaced parameter", param_descriptor->description); + rcl_variant_t * param_value = rcl_yaml_node_struct_get("node_ns/node1", "param1", params); + ASSERT_TRUE(NULL != param_value) << rcutils_get_error_string().str; + ASSERT_TRUE(NULL != param_value->integer_value); + EXPECT_EQ(28, *param_value->integer_value); + + param_value = rcl_yaml_node_struct_get("node_ns/node2", "foo.bar", params); + ASSERT_TRUE(NULL != param_value) << rcutils_get_error_string().str; + ASSERT_TRUE(NULL != param_value->integer_value); + EXPECT_EQ(10, *param_value->integer_value); + + param_value = rcl_yaml_node_struct_get("node_ns/node2", "foo.baz", params); + ASSERT_TRUE(NULL != param_value) << rcutils_get_error_string().str; + ASSERT_TRUE(NULL != param_value->string_value); + EXPECT_STREQ("hello", param_value->string_value); + rcl_yaml_node_struct_print(params); } } From c06b47a0ee03a3959367985b1ec541d7caf4f7d1 Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Tue, 23 Mar 2021 02:44:01 +0000 Subject: [PATCH 13/19] add unit tests for param descriptors Signed-off-by: Brian Wilcox --- rcl_yaml_param_parser/CMakeLists.txt | 24 + rcl_yaml_param_parser/src/parse.c | 5 + .../test/test_node_params_descriptors.cpp | 80 +++ rcl_yaml_param_parser/test/test_parse.cpp | 465 +++++++++++++++++- .../test/test_yaml_descriptor.cpp | 118 +++++ 5 files changed, 691 insertions(+), 1 deletion(-) create mode 100644 rcl_yaml_param_parser/test/test_node_params_descriptors.cpp create mode 100644 rcl_yaml_param_parser/test/test_yaml_descriptor.cpp diff --git a/rcl_yaml_param_parser/CMakeLists.txt b/rcl_yaml_param_parser/CMakeLists.txt index 5825afb78..5b2a64cfb 100644 --- a/rcl_yaml_param_parser/CMakeLists.txt +++ b/rcl_yaml_param_parser/CMakeLists.txt @@ -94,6 +94,18 @@ if(BUILD_TESTING) target_link_libraries(test_node_params ${PROJECT_NAME}) endif() + ament_add_gtest(test_node_params_descriptors + test/test_node_params_descriptors.cpp + WORKING_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}" + ) + if(TARGET test_node_params_descriptors) + ament_target_dependencies(test_node_params_descriptors + "rcutils" + "osrf_testing_tools_cpp" + ) + target_link_libraries(test_node_params_descriptors ${PROJECT_NAME}) + endif() + ament_add_gtest(test_parse_yaml test/test_parse_yaml.cpp WORKING_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}" @@ -168,6 +180,18 @@ if(BUILD_TESTING) target_link_libraries(test_yaml_variant ${PROJECT_NAME}) endif() + ament_add_gtest(test_yaml_descriptor + test/test_yaml_descriptor.cpp + WORKING_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}" + ) + if(TARGET test_yaml_descriptor) + ament_target_dependencies(test_yaml_descriptor + "rcutils" + "osrf_testing_tools_cpp" + ) + target_link_libraries(test_yaml_descriptor ${PROJECT_NAME}) + endif() + add_performance_test(benchmark_parse_yaml test/benchmark/benchmark_parse_yaml.cpp WORKING_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}") if(TARGET benchmark_parse_yaml) diff --git a/rcl_yaml_param_parser/src/parse.c b/rcl_yaml_param_parser/src/parse.c index 4f1b8c69f..d6ac74cf6 100644 --- a/rcl_yaml_param_parser/src/parse.c +++ b/rcl_yaml_param_parser/src/parse.c @@ -521,6 +521,11 @@ rcutils_ret_t parse_descriptor( node_descriptors_st->num_params++; } + if (NULL == ns_tracker->descriptor_key_ns) { + RCUTILS_SET_ERROR_MSG("Internal error: Invalid mem"); + return RCUTILS_RET_ERROR; + } + if (0 == strncmp("additional_constraints", ns_tracker->descriptor_key_ns, strlen("additional_constraints"))) { diff --git a/rcl_yaml_param_parser/test/test_node_params_descriptors.cpp b/rcl_yaml_param_parser/test/test_node_params_descriptors.cpp new file mode 100644 index 000000000..33f876713 --- /dev/null +++ b/rcl_yaml_param_parser/test/test_node_params_descriptors.cpp @@ -0,0 +1,80 @@ +// 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 + +#include "../src/impl/node_params_descriptors.h" +#include "rcutils/allocator.h" + +TEST(TestNodeParamsDescriptors, init_fini) { + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + rcl_node_params_descriptors_t node_descriptors = {NULL, NULL, 0u, 128u}; + EXPECT_EQ(RCUTILS_RET_OK, node_params_descriptors_init(&node_descriptors, allocator)); + EXPECT_NE(nullptr, node_descriptors.parameter_names); + EXPECT_NE(nullptr, node_descriptors.parameter_descriptors); + EXPECT_EQ(0u, node_descriptors.num_params); + EXPECT_EQ(128u, node_descriptors.capacity_descriptors); + rcl_yaml_node_params_descriptors_fini(&node_descriptors, allocator); + EXPECT_EQ(nullptr, node_descriptors.parameter_names); + EXPECT_EQ(nullptr, node_descriptors.parameter_descriptors); + EXPECT_EQ(0u, node_descriptors.num_params); + EXPECT_EQ(0u, node_descriptors.capacity_descriptors); + + // This function doesn't return anything, so just check it doesn't segfault on the second try + rcl_yaml_node_params_descriptors_fini(&node_descriptors, allocator); + rcl_yaml_node_params_descriptors_fini(nullptr, allocator); +} + +TEST(TestNodeParamsDescriptors, init_with_capacity_fini) { + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + rcl_node_params_descriptors_t node_descriptors = {NULL, NULL, 0u, 1024u}; + EXPECT_EQ(RCUTILS_RET_OK, node_params_descriptors_init_with_capacity(&node_descriptors, 1024, allocator)); + EXPECT_NE(nullptr, node_descriptors.parameter_names); + EXPECT_NE(nullptr, node_descriptors.parameter_descriptors); + EXPECT_EQ(0u, node_descriptors.num_params); + EXPECT_EQ(1024u, node_descriptors.capacity_descriptors); + rcl_yaml_node_params_descriptors_fini(&node_descriptors, allocator); + EXPECT_EQ(nullptr, node_descriptors.parameter_names); + EXPECT_EQ(nullptr, node_descriptors.parameter_descriptors); + EXPECT_EQ(0u, node_descriptors.num_params); + EXPECT_EQ(0u, node_descriptors.capacity_descriptors); + + // This function doesn't return anything, so just check it doesn't segfault on the second try + rcl_yaml_node_params_descriptors_fini(&node_descriptors, allocator); + rcl_yaml_node_params_descriptors_fini(nullptr, allocator); +} + +TEST(TestNodeParamsDescriptors, reallocate_with_capacity_fini) { + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + rcl_node_params_descriptors_t node_descriptors = {NULL, NULL, 0u, 1024u}; + EXPECT_EQ(RCUTILS_RET_OK, node_params_descriptors_init_with_capacity(&node_descriptors, 1024, allocator)); + EXPECT_NE(nullptr, node_descriptors.parameter_names); + EXPECT_NE(nullptr, node_descriptors.parameter_descriptors); + EXPECT_EQ(0u, node_descriptors.num_params); + EXPECT_EQ(1024u, node_descriptors.capacity_descriptors); + EXPECT_EQ(RCUTILS_RET_OK, node_params_descriptors_reallocate(&node_descriptors, 2048, allocator)); + EXPECT_NE(nullptr, node_descriptors.parameter_names); + EXPECT_NE(nullptr, node_descriptors.parameter_descriptors); + EXPECT_EQ(0u, node_descriptors.num_params); + EXPECT_EQ(2048u, node_descriptors.capacity_descriptors); + rcl_yaml_node_params_descriptors_fini(&node_descriptors, allocator); + EXPECT_EQ(nullptr, node_descriptors.parameter_names); + EXPECT_EQ(nullptr, node_descriptors.parameter_descriptors); + EXPECT_EQ(0u, node_descriptors.num_params); + EXPECT_EQ(0u, node_descriptors.capacity_descriptors); + + // This function doesn't return anything, so just check it doesn't segfault on the second try + rcl_yaml_node_params_descriptors_fini(&node_descriptors, allocator); + rcl_yaml_node_params_descriptors_fini(nullptr, allocator); +} diff --git a/rcl_yaml_param_parser/test/test_parse.cpp b/rcl_yaml_param_parser/test/test_parse.cpp index e53849cc0..f32e3d7b6 100644 --- a/rcl_yaml_param_parser/test/test_parse.cpp +++ b/rcl_yaml_param_parser/test/test_parse.cpp @@ -23,7 +23,10 @@ #include "rcl_yaml_param_parser/parser.h" #include "../src/impl/parse.h" #include "../src/impl/node_params.h" +#include "../src/impl/node_params_descriptors.h" +#include "../src/impl/types.h" #include "rcutils/filesystem.h" +#include "rcutils/strdup.h" #include "./mocking_utils/patch.hpp" @@ -97,7 +100,7 @@ TEST(TestParse, parse_value) { params_st->params[node_idx].parameter_values[parameter_idx].double_value, allocator.state); params_st->params[node_idx].parameter_values[parameter_idx].double_value = nullptr; - // double value + // string value yaml_char_t string_value[] = "hello, I am a string"; const size_t string_value_length = sizeof(string_value) / sizeof(string_value[0]); event.data.scalar.value = string_value; @@ -116,6 +119,454 @@ TEST(TestParse, parse_value) { params_st->params[node_idx].parameter_values[parameter_idx].string_value = nullptr; } +TEST(TestParse, parse_descriptor) { + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + yaml_event_t event; + event.type = YAML_NO_EVENT; + event.start_mark = {0u, 0u, 0u}; + event.end_mark = {0u, 0u, 0u}; + event.data.scalar = {NULL, NULL, NULL, 1u, 0, 0, YAML_ANY_SCALAR_STYLE}; + + namespace_tracker_t ns_tracker; + ns_tracker.node_ns = nullptr; + ns_tracker.parameter_ns = nullptr; + ns_tracker.descriptor_key_ns = nullptr; + ns_tracker.num_node_ns = 0; + ns_tracker.num_parameter_ns = 0; + ns_tracker.num_descriptor_key_ns = 0; + + bool is_seq = false; + size_t node_idx = 0u; + size_t parameter_idx = 0u; + rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator); + ASSERT_NE(nullptr, params_st); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + rcl_yaml_node_struct_fini(params_st); + }); + + ASSERT_EQ(RCUTILS_RET_OK, node_params_descriptors_init(¶ms_st->descriptors[0], allocator)); + params_st->num_nodes = 1u; + + ns_tracker.parameter_ns = rcutils_strdup("param", allocator); + ASSERT_STREQ("param", ns_tracker.parameter_ns); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + allocator.deallocate(ns_tracker.parameter_ns, allocator.state); + }); + + // Set up descriptor test case data + yaml_char_t bool_value[] = "true"; + yaml_char_t int_value[] = "28"; + yaml_char_t double_value[] = "1.23456"; + yaml_char_t string_value[] = "I am a string"; + + const size_t bool_value_length = sizeof(bool_value) / sizeof(bool_value[0]); + const size_t int_value_length = sizeof(int_value) / sizeof(int_value[0]); + const size_t double_value_length = sizeof(double_value) / sizeof(double_value[0]); + const size_t string_value_length = sizeof(string_value) / sizeof(string_value[0]); + + // read_only + ns_tracker.descriptor_key_ns = rcutils_strdup("read_only", allocator); + ASSERT_STREQ("read_only", ns_tracker.descriptor_key_ns); + event.data.scalar.value = bool_value; + event.data.scalar.length = bool_value_length; + EXPECT_EQ( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only); + EXPECT_TRUE(*params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only); + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only, allocator.state); + allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only = nullptr; + + // min_value (int) + ns_tracker.descriptor_key_ns = rcutils_strdup("min_value", allocator); + ASSERT_STREQ("min_value", ns_tracker.descriptor_key_ns); + event.data.scalar.value = int_value; + event.data.scalar.length = int_value_length; + EXPECT_EQ( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int); + EXPECT_EQ(28, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int); + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int = nullptr; + + // min_value (double) + event.data.scalar.value = double_value; + event.data.scalar.length = double_value_length; + EXPECT_EQ( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_double); + EXPECT_EQ(1.23456, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_double); + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_double, allocator.state); + allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_double = nullptr; + + // max_value (int) + ns_tracker.descriptor_key_ns = rcutils_strdup("max_value", allocator); + ASSERT_STREQ("max_value", ns_tracker.descriptor_key_ns); + event.data.scalar.value = int_value; + event.data.scalar.length = int_value_length; + EXPECT_EQ( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int); + EXPECT_EQ(28, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int); + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int = nullptr; + + // max_value (double) + event.data.scalar.value = double_value; + event.data.scalar.length = double_value_length; + EXPECT_EQ( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_double); + EXPECT_EQ(1.23456, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_double); + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_double, allocator.state); + allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_double = nullptr; + + // step (int) + ns_tracker.descriptor_key_ns = rcutils_strdup("step", allocator); + ASSERT_STREQ("step", ns_tracker.descriptor_key_ns); + event.data.scalar.value = int_value; + event.data.scalar.length = int_value_length; + EXPECT_EQ( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int); + EXPECT_EQ(28, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int); + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int = nullptr; + + // step (double) + event.data.scalar.value = double_value; + event.data.scalar.length = double_value_length; + EXPECT_EQ( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_double); + EXPECT_EQ(1.23456, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_double); + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_double, allocator.state); + allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_double = nullptr; + + // description + ns_tracker.descriptor_key_ns = rcutils_strdup("description", allocator); + ASSERT_STREQ("description", ns_tracker.descriptor_key_ns); + event.data.scalar.value = string_value; + event.data.scalar.length = string_value_length; + EXPECT_EQ( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description); + EXPECT_STREQ( + "I am a string", + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description); + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description, allocator.state); + allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description = nullptr; + + // additional_constraints + ns_tracker.descriptor_key_ns = rcutils_strdup("additional_constraints", allocator); + ASSERT_STREQ("additional_constraints", ns_tracker.descriptor_key_ns); + event.data.scalar.value = string_value; + event.data.scalar.length = string_value_length; + EXPECT_EQ( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints); + EXPECT_STREQ( + "I am a string", + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints); + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints, allocator.state); + allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints = nullptr; +} + +TEST(TestParse, parse_descriptor_bad_args) { + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + yaml_event_t event; + event.type = YAML_NO_EVENT; + event.start_mark = {0u, 0u, 0u}; + event.end_mark = {0u, 0u, 0u}; + event.data.scalar = {NULL, NULL, NULL, 1u, 0, 0, YAML_ANY_SCALAR_STYLE}; + + namespace_tracker_t ns_tracker; + ns_tracker.node_ns = nullptr; + ns_tracker.parameter_ns = nullptr; + ns_tracker.descriptor_key_ns = nullptr; + ns_tracker.num_node_ns = 0; + ns_tracker.num_parameter_ns = 0; + ns_tracker.num_descriptor_key_ns = 0; + + bool is_seq = false; + size_t node_idx = 0u; + size_t parameter_idx = 0u; + rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator); + ASSERT_NE(nullptr, params_st); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + rcl_yaml_node_struct_fini(params_st); + }); + + EXPECT_EQ( + RCUTILS_RET_INVALID_ARGUMENT, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, nullptr)); + EXPECT_TRUE(rcutils_error_is_set()); + rcutils_reset_error(); + + // No node to update + const size_t num_nodes = params_st->num_nodes; + params_st->num_nodes = 0u; + EXPECT_EQ( + RCUTILS_RET_INVALID_ARGUMENT, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)); + EXPECT_TRUE(rcutils_error_is_set()); + rcutils_reset_error(); + params_st->num_nodes = num_nodes; + + ASSERT_EQ(RCUTILS_RET_OK, node_params_descriptors_init(¶ms_st->descriptors[0], allocator)); + params_st->num_nodes = 1u; + + // event.data.scalar.value is NULL, but event.data.scalar.length > 0 + event.data.scalar.value = NULL; + EXPECT_EQ( + RCUTILS_RET_INVALID_ARGUMENT, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)); + EXPECT_TRUE(rcutils_error_is_set()); + rcutils_reset_error(); + + // event.data.scalar.length is 0 and style is not a QUOTED_SCALAR_STYLE + event.data.scalar.length = 0u; + yaml_char_t event_value[] = "non_empty_string"; + const size_t event_value_length = sizeof(event_value) / sizeof(event_value[0]); + event.data.scalar.value = event_value; + EXPECT_EQ( + RCUTILS_RET_ERROR, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + EXPECT_TRUE(rcutils_error_is_set()); + rcutils_reset_error(); + + // parameter_descriptors is NULL + event.data.scalar.length = event_value_length; + rcl_param_descriptor_t * tmp_descriptor_array = params_st->descriptors[0].parameter_descriptors; + params_st->descriptors[0].parameter_descriptors = NULL; + EXPECT_EQ( + RCUTILS_RET_BAD_ALLOC, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + EXPECT_TRUE(rcutils_error_is_set()); + rcutils_reset_error(); + params_st->descriptors[0].parameter_descriptors = tmp_descriptor_array; + + // is_seq is true + EXPECT_EQ( + RCUTILS_RET_ERROR, + parse_descriptor(&ns_tracker, event, true, node_idx, parameter_idx, params_st)); + EXPECT_TRUE(rcutils_error_is_set()); + rcutils_reset_error(); + + // namespace_tracker->parameter_ns is NULL + EXPECT_EQ( + RCUTILS_RET_ERROR, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)); + EXPECT_TRUE(rcutils_error_is_set()); + rcutils_reset_error(); + + // namespace_tracker->descriptor_key_ns is NULL + ns_tracker.parameter_ns = rcutils_strdup("param", allocator); + ASSERT_STREQ("param", ns_tracker.parameter_ns); + EXPECT_EQ( + RCUTILS_RET_ERROR, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)); + EXPECT_TRUE(rcutils_error_is_set()); + rcutils_reset_error(); + + // Invalid namespace_tracker->descriptor_key_ns + ns_tracker.descriptor_key_ns = rcutils_strdup("invalid_key", allocator); + ASSERT_STREQ("invalid_key", ns_tracker.descriptor_key_ns); + EXPECT_EQ( + RCUTILS_RET_ERROR, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)); + EXPECT_TRUE(rcutils_error_is_set()); + allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); + rcutils_reset_error(); + + // Valid namespace_tracker->descriptor_key_ns + ns_tracker.descriptor_key_ns = rcutils_strdup("description", allocator); + ASSERT_STREQ("description", ns_tracker.descriptor_key_ns); + EXPECT_EQ( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)); + EXPECT_FALSE(rcutils_error_is_set()); + rcutils_reset_error(); +} + +TEST(TestParse, parse_descriptor_bad_types) { + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + yaml_event_t event; + event.type = YAML_NO_EVENT; + event.start_mark = {0u, 0u, 0u}; + event.end_mark = {0u, 0u, 0u}; + event.data.scalar = {NULL, NULL, NULL, 1u, 0, 0, YAML_ANY_SCALAR_STYLE}; + + namespace_tracker_t ns_tracker; + ns_tracker.node_ns = nullptr; + ns_tracker.parameter_ns = nullptr; + ns_tracker.descriptor_key_ns = nullptr; + ns_tracker.num_node_ns = 0; + ns_tracker.num_parameter_ns = 0; + ns_tracker.num_descriptor_key_ns = 0; + + bool is_seq = false; + size_t node_idx = 0u; + size_t parameter_idx = 0u; + rcl_params_t * params_st = rcl_yaml_node_struct_init(allocator); + ASSERT_NE(nullptr, params_st); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + rcl_yaml_node_struct_fini(params_st); + }); + + ASSERT_EQ(RCUTILS_RET_OK, node_params_descriptors_init(¶ms_st->descriptors[0], allocator)); + params_st->num_nodes = 1u; + + ns_tracker.parameter_ns = rcutils_strdup("param", allocator); + ASSERT_STREQ("param", ns_tracker.parameter_ns); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + allocator.deallocate(ns_tracker.parameter_ns, allocator.state); + }); + + // Set up descriptor test case data + yaml_char_t bool_value[] = "true"; + yaml_char_t int_value[] = "28"; + yaml_char_t double_value[] = "1.23456"; + yaml_char_t string_value[] = "I am a string"; + + const size_t bool_value_length = sizeof(bool_value) / sizeof(bool_value[0]); + const size_t int_value_length = sizeof(int_value) / sizeof(int_value[0]); + const size_t double_value_length = sizeof(double_value) / sizeof(double_value[0]); + const size_t string_value_length = sizeof(string_value) / sizeof(string_value[0]); + + // read_only + ns_tracker.descriptor_key_ns = rcutils_strdup("read_only", allocator); + ASSERT_STREQ("read_only", ns_tracker.descriptor_key_ns); + // read_only: catch invalid value type + event.data.scalar.value = double_value; + event.data.scalar.length = double_value_length; + EXPECT_NE( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only, allocator.state); + allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only = nullptr; + rcutils_reset_error(); + + // min_value + ns_tracker.descriptor_key_ns = rcutils_strdup("min_value", allocator); + ASSERT_STREQ("min_value", ns_tracker.descriptor_key_ns); + // min_value: catch invalid value type + event.data.scalar.value = string_value; + event.data.scalar.length = string_value_length; + EXPECT_NE( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int = nullptr; + rcutils_reset_error(); + + // max_value + ns_tracker.descriptor_key_ns = rcutils_strdup("max_value", allocator); + ASSERT_STREQ("max_value", ns_tracker.descriptor_key_ns); + // max_value: catch invalid value type + event.data.scalar.value = bool_value; + event.data.scalar.length = bool_value_length; + EXPECT_NE( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int = nullptr; + rcutils_reset_error(); + + // step (int) + ns_tracker.descriptor_key_ns = rcutils_strdup("step", allocator); + ASSERT_STREQ("step", ns_tracker.descriptor_key_ns); + // step: catch invalid value type + event.data.scalar.value = bool_value; + event.data.scalar.length = bool_value_length; + EXPECT_NE( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int = nullptr; + rcutils_reset_error(); + + // description + ns_tracker.descriptor_key_ns = rcutils_strdup("description", allocator); + ASSERT_STREQ("description", ns_tracker.descriptor_key_ns); + // description: catch invalid value type + event.data.scalar.value = bool_value; + event.data.scalar.length = bool_value_length; + EXPECT_NE( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description, allocator.state); + allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description = nullptr; + rcutils_reset_error(); + + // additional_constraints + ns_tracker.descriptor_key_ns = rcutils_strdup("additional_constraints", allocator); + ASSERT_STREQ("additional_constraints", ns_tracker.descriptor_key_ns); + // additional_constraints: catch invalid value type + event.data.scalar.value = int_value; + event.data.scalar.length = int_value_length; + EXPECT_NE( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints, allocator.state); + allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints = nullptr; + rcutils_reset_error(); +} + TEST(TestParse, parse_value_sequence) { rcutils_allocator_t allocator = rcutils_get_default_allocator(); yaml_event_t event; @@ -376,6 +827,7 @@ TEST(TestParse, parse_key_bad_args) }); ASSERT_EQ(RCUTILS_RET_OK, node_params_init(¶ms_st->params[0], allocator)); + ASSERT_EQ(RCUTILS_RET_OK, node_params_descriptors_init(¶ms_st->descriptors[0], allocator)); params_st->num_nodes = 1u; // map_level is nullptr @@ -451,8 +903,19 @@ TEST(TestParse, parse_key_bad_args) rcutils_get_error_string().str; EXPECT_TRUE(rcutils_error_is_set()); rcutils_reset_error(); + + // previous parameter names required for parameter namespace in descriptors level + map_level = MAP_PARAMS_DESCRIPTORS_LVL; + EXPECT_EQ( + RCUTILS_RET_ERROR, + parse_key( + event, &map_level, &is_new_map, &node_idx, ¶meter_idx, &ns_tracker, params_st)) << + rcutils_get_error_string().str; + EXPECT_TRUE(rcutils_error_is_set()); + rcutils_reset_error(); } + TEST(TestParse, parse_file_events_mock_yaml_parser_parse) { char cur_dir[1024]; rcutils_reset_error(); diff --git a/rcl_yaml_param_parser/test/test_yaml_descriptor.cpp b/rcl_yaml_param_parser/test/test_yaml_descriptor.cpp new file mode 100644 index 000000000..315eff7c7 --- /dev/null +++ b/rcl_yaml_param_parser/test/test_yaml_descriptor.cpp @@ -0,0 +1,118 @@ +// 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 + +#include "osrf_testing_tools_cpp/scope_exit.hpp" +#include "../src/impl/yaml_descriptor.h" +#include "rcutils/allocator.h" +#include "rcutils/strdup.h" + +#define TEST_DESCRIPTOR_COPY(field, tmp_field) \ + do { \ + SCOPED_TRACE("TEST_DESCRIPTOR_COPY " #field); \ + rcl_param_descriptor_t src_descriptor{}; \ + rcl_param_descriptor_t dest_descriptor{}; \ + rcutils_allocator_t allocator = rcutils_get_default_allocator(); \ + src_descriptor.field = &tmp_field; \ + EXPECT_TRUE(rcl_yaml_descriptor_copy(&dest_descriptor, &src_descriptor, allocator)); \ + ASSERT_NE(nullptr, dest_descriptor.field); \ + EXPECT_EQ(*src_descriptor.field, *dest_descriptor.field); \ + rcl_yaml_descriptor_fini(&dest_descriptor, allocator); \ + src_descriptor.field = nullptr; \ + } while (0) + +TEST(TestYamlDescriptor, copy_fini) { + rcl_param_descriptor_t descriptor{}; + rcl_param_descriptor_t copy{}; + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + + EXPECT_FALSE(rcl_yaml_descriptor_copy(nullptr, &descriptor, allocator)); + EXPECT_FALSE(rcl_yaml_descriptor_copy(©, nullptr, allocator)); + + ASSERT_TRUE(rcl_yaml_descriptor_copy(©, &descriptor, allocator)); + + rcl_yaml_descriptor_fini(©, allocator); + + // Check second fini works fine + rcl_yaml_descriptor_fini(©, allocator); + + // Check fini with a nullptr doesn't crash. + rcl_yaml_descriptor_fini(nullptr, allocator); +} + +TEST(TestYamlDescriptor, copy_fields) { + bool tmp_read_only = true; + TEST_DESCRIPTOR_COPY(read_only, tmp_read_only); + + uint8_t tmp_type = 2; + TEST_DESCRIPTOR_COPY(type, tmp_type); + + double tmp_min_value_double = -5.5; + TEST_DESCRIPTOR_COPY(min_value_double, tmp_min_value_double); + + double tmp_max_value_double = 16.4; + TEST_DESCRIPTOR_COPY(max_value_double, tmp_max_value_double); + + double tmp_step_double = 0.1; + TEST_DESCRIPTOR_COPY(step_double, tmp_step_double); + + int64_t tmp_min_value_int = 1; + TEST_DESCRIPTOR_COPY(min_value_int, tmp_min_value_int); + + int64_t tmp_max_value_int = 1001; + TEST_DESCRIPTOR_COPY(max_value_int, tmp_max_value_int); + + int64_t tmp_step_int = 5; + TEST_DESCRIPTOR_COPY(step_int, tmp_step_int); +} + +TEST(TestYamlDescriptor, copy_string_fields) { + // String version is slightly different and can't use the above macro + rcl_param_descriptor_t src_descriptor{}; + rcl_param_descriptor_t dest_descriptor{}; + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + + char * tmp_name = rcutils_strdup("param_name", allocator); + ASSERT_STREQ("param_name", tmp_name); + + char * tmp_description = rcutils_strdup("param description", allocator); + ASSERT_STREQ("param description", tmp_description); + + char * tmp_additional_constraints = rcutils_strdup("param additional constraints", allocator); + ASSERT_STREQ("param additional constraints", tmp_additional_constraints); + + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + allocator.deallocate(tmp_name, allocator.state); + allocator.deallocate(tmp_description, allocator.state); + allocator.deallocate(tmp_additional_constraints, allocator.state); + }); + + src_descriptor.name = tmp_name; + src_descriptor.description = tmp_description; + src_descriptor.additional_constraints = tmp_additional_constraints; + + EXPECT_TRUE(rcl_yaml_descriptor_copy(&dest_descriptor, &src_descriptor, allocator)); + ASSERT_NE(nullptr, dest_descriptor.name); + ASSERT_NE(nullptr, dest_descriptor.description); + ASSERT_NE(nullptr, dest_descriptor.additional_constraints); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + rcl_yaml_descriptor_fini(&dest_descriptor, allocator); + }); + EXPECT_STREQ(tmp_name, dest_descriptor.name); + EXPECT_STREQ(tmp_description, dest_descriptor.description); + EXPECT_STREQ(tmp_additional_constraints, dest_descriptor.additional_constraints); +} From dbfbe8791e00dcee47ca3d50e6a0298c3962fee2 Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Tue, 23 Mar 2021 03:40:12 +0000 Subject: [PATCH 14/19] fix cpplint Signed-off-by: Brian Wilcox --- .../src/impl/yaml_descriptor.h | 4 +- .../src/node_params_descriptors.c | 9 +- rcl_yaml_param_parser/src/parse.c | 3 +- rcl_yaml_param_parser/src/parser.c | 20 ++-- rcl_yaml_param_parser/src/yaml_descriptor.c | 4 +- .../test/test_node_params_descriptors.cpp | 6 +- rcl_yaml_param_parser/test/test_parse.cpp | 93 ++++++++++++------- .../test/test_yaml_descriptor.cpp | 2 +- 8 files changed, 93 insertions(+), 48 deletions(-) diff --git a/rcl_yaml_param_parser/src/impl/yaml_descriptor.h b/rcl_yaml_param_parser/src/impl/yaml_descriptor.h index 3b200e24f..e901dfacc 100644 --- a/rcl_yaml_param_parser/src/impl/yaml_descriptor.h +++ b/rcl_yaml_param_parser/src/impl/yaml_descriptor.h @@ -40,7 +40,9 @@ void rcl_yaml_descriptor_fini( RCL_YAML_PARAM_PARSER_PUBLIC RCUTILS_WARN_UNUSED bool rcl_yaml_descriptor_copy( - rcl_param_descriptor_t * out_param_desc, const rcl_param_descriptor_t * param_desc, rcutils_allocator_t allocator); + rcl_param_descriptor_t * out_param_desc, + const rcl_param_descriptor_t * param_desc, + rcutils_allocator_t allocator); #ifdef __cplusplus } diff --git a/rcl_yaml_param_parser/src/node_params_descriptors.c b/rcl_yaml_param_parser/src/node_params_descriptors.c index 272074746..6ad353941 100644 --- a/rcl_yaml_param_parser/src/node_params_descriptors.c +++ b/rcl_yaml_param_parser/src/node_params_descriptors.c @@ -22,7 +22,8 @@ rcutils_ret_t node_params_descriptors_init( rcl_node_params_descriptors_t * node_descriptors, const rcutils_allocator_t allocator) { - return node_params_descriptors_init_with_capacity(node_descriptors, INIT_NUM_PARAMS_DESCRIPTORS_PER_NODE, allocator); + return node_params_descriptors_init_with_capacity( + node_descriptors, INIT_NUM_PARAMS_DESCRIPTORS_PER_NODE, allocator); } rcutils_ret_t node_params_descriptors_init_with_capacity( @@ -91,7 +92,8 @@ rcutils_ret_t node_params_descriptors_reallocate( } void * parameter_descriptors = allocator.reallocate( - node_descriptors->parameter_descriptors, new_capacity * sizeof(rcl_param_descriptor_t), allocator.state); + node_descriptors->parameter_descriptors, + new_capacity * sizeof(rcl_param_descriptor_t), allocator.state); if (NULL == parameter_descriptors) { RCUTILS_SET_ERROR_MSG("Failed to reallocate node parameter values"); return RCUTILS_RET_BAD_ALLOC; @@ -133,7 +135,8 @@ void rcl_yaml_node_params_descriptors_fini( for (size_t parameter_idx = 0U; parameter_idx < node_descriptors->num_params; parameter_idx++) { - rcl_yaml_descriptor_fini(&(node_descriptors->parameter_descriptors[parameter_idx]), allocator); + rcl_yaml_descriptor_fini( + &(node_descriptors->parameter_descriptors[parameter_idx]), allocator); } allocator.deallocate(node_descriptors->parameter_descriptors, allocator.state); diff --git a/rcl_yaml_param_parser/src/parse.c b/rcl_yaml_param_parser/src/parse.c index d6ac74cf6..ba58d7da3 100644 --- a/rcl_yaml_param_parser/src/parse.c +++ b/rcl_yaml_param_parser/src/parse.c @@ -596,7 +596,8 @@ rcutils_ret_t parse_descriptor( param_descriptor->step_double = (double *)ret_val; } else { RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( - "Value type 'integer' or 'double' expected at line %d for " PARAMS_DESCRIPTORS_KEY " key: step", + "Value type 'integer' or 'double' expected at line %d for " + PARAMS_DESCRIPTORS_KEY " key: step", line_num); return RCUTILS_RET_ERROR; } diff --git a/rcl_yaml_param_parser/src/parser.c b/rcl_yaml_param_parser/src/parser.c index 66186772d..9bef720b9 100644 --- a/rcl_yaml_param_parser/src/parser.c +++ b/rcl_yaml_param_parser/src/parser.c @@ -213,8 +213,10 @@ rcl_params_t * rcl_yaml_node_struct_copy( } } - rcl_node_params_descriptors_t * node_params_descriptors_st = &(params_st->descriptors[node_idx]); - rcl_node_params_descriptors_t * out_node_params_descriptors_st = &(out_params_st->descriptors[node_idx]); + rcl_node_params_descriptors_t * node_params_descriptors_st = + &(params_st->descriptors[node_idx]); + rcl_node_params_descriptors_t * out_node_params_descriptors_st = + &(out_params_st->descriptors[node_idx]); ret = node_params_descriptors_init_with_capacity( out_node_params_descriptors_st, node_params_descriptors_st->capacity_descriptors, @@ -225,17 +227,19 @@ rcl_params_t * rcl_yaml_node_struct_copy( } goto fail; } - for (size_t descriptor_idx = 0U; descriptor_idx < node_params_descriptors_st->num_params; ++descriptor_idx) { - out_node_params_descriptors_st->parameter_names[descriptor_idx] = - rcutils_strdup(node_params_descriptors_st->parameter_names[descriptor_idx], allocator); - if (NULL == out_node_params_descriptors_st->parameter_names[descriptor_idx]) { + for (size_t desc_idx = 0U; desc_idx < node_params_descriptors_st->num_params; ++desc_idx) { + out_node_params_descriptors_st->parameter_names[desc_idx] = + rcutils_strdup(node_params_descriptors_st->parameter_names[desc_idx], allocator); + if (NULL == out_node_params_descriptors_st->parameter_names[desc_idx]) { RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n"); goto fail; } out_node_params_descriptors_st->num_params++; - const rcl_param_descriptor_t * param_descriptor = &(node_params_descriptors_st->parameter_descriptors[descriptor_idx]); - rcl_param_descriptor_t * out_param_descriptor = &(out_node_params_descriptors_st->parameter_descriptors[descriptor_idx]); + const rcl_param_descriptor_t * param_descriptor = + &(node_params_descriptors_st->parameter_descriptors[desc_idx]); + rcl_param_descriptor_t * out_param_descriptor = + &(out_node_params_descriptors_st->parameter_descriptors[desc_idx]); if (!rcl_yaml_descriptor_copy(out_param_descriptor, param_descriptor, allocator)) { goto fail; } diff --git a/rcl_yaml_param_parser/src/yaml_descriptor.c b/rcl_yaml_param_parser/src/yaml_descriptor.c index 4be921d48..4424fd627 100644 --- a/rcl_yaml_param_parser/src/yaml_descriptor.c +++ b/rcl_yaml_param_parser/src/yaml_descriptor.c @@ -75,7 +75,9 @@ void rcl_yaml_descriptor_fini( } bool rcl_yaml_descriptor_copy( - rcl_param_descriptor_t * out_param_descriptor, const rcl_param_descriptor_t * param_descriptor, rcutils_allocator_t allocator) + rcl_param_descriptor_t * out_param_descriptor, + const rcl_param_descriptor_t * param_descriptor, + rcutils_allocator_t allocator) { if (NULL == param_descriptor || NULL == out_param_descriptor) { return false; diff --git a/rcl_yaml_param_parser/test/test_node_params_descriptors.cpp b/rcl_yaml_param_parser/test/test_node_params_descriptors.cpp index 33f876713..87a79913f 100644 --- a/rcl_yaml_param_parser/test/test_node_params_descriptors.cpp +++ b/rcl_yaml_param_parser/test/test_node_params_descriptors.cpp @@ -39,7 +39,8 @@ TEST(TestNodeParamsDescriptors, init_fini) { TEST(TestNodeParamsDescriptors, init_with_capacity_fini) { rcutils_allocator_t allocator = rcutils_get_default_allocator(); rcl_node_params_descriptors_t node_descriptors = {NULL, NULL, 0u, 1024u}; - EXPECT_EQ(RCUTILS_RET_OK, node_params_descriptors_init_with_capacity(&node_descriptors, 1024, allocator)); + EXPECT_EQ(RCUTILS_RET_OK, node_params_descriptors_init_with_capacity( + &node_descriptors, 1024, allocator)); EXPECT_NE(nullptr, node_descriptors.parameter_names); EXPECT_NE(nullptr, node_descriptors.parameter_descriptors); EXPECT_EQ(0u, node_descriptors.num_params); @@ -58,7 +59,8 @@ TEST(TestNodeParamsDescriptors, init_with_capacity_fini) { TEST(TestNodeParamsDescriptors, reallocate_with_capacity_fini) { rcutils_allocator_t allocator = rcutils_get_default_allocator(); rcl_node_params_descriptors_t node_descriptors = {NULL, NULL, 0u, 1024u}; - EXPECT_EQ(RCUTILS_RET_OK, node_params_descriptors_init_with_capacity(&node_descriptors, 1024, allocator)); + EXPECT_EQ(RCUTILS_RET_OK, node_params_descriptors_init_with_capacity( + &node_descriptors, 1024, allocator)); EXPECT_NE(nullptr, node_descriptors.parameter_names); EXPECT_NE(nullptr, node_descriptors.parameter_descriptors); EXPECT_EQ(0u, node_descriptors.num_params); diff --git a/rcl_yaml_param_parser/test/test_parse.cpp b/rcl_yaml_param_parser/test/test_parse.cpp index f32e3d7b6..ee1a42669 100644 --- a/rcl_yaml_param_parser/test/test_parse.cpp +++ b/rcl_yaml_param_parser/test/test_parse.cpp @@ -175,10 +175,12 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only); + ASSERT_NE(nullptr, + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only); EXPECT_TRUE(*params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only); allocator.deallocate( - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only, + allocator.state); allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only = nullptr; @@ -191,10 +193,13 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int); - EXPECT_EQ(28, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int); + ASSERT_NE(nullptr, + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int); + EXPECT_EQ(28, + *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int); allocator.deallocate( - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int, + allocator.state); params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int = nullptr; // min_value (double) @@ -204,10 +209,13 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_double); - EXPECT_EQ(1.23456, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_double); + ASSERT_NE(nullptr, + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_double); + EXPECT_EQ(1.23456, + *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_double); allocator.deallocate( - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_double, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_double, + allocator.state); allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_double = nullptr; @@ -220,10 +228,13 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int); - EXPECT_EQ(28, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int); + ASSERT_NE(nullptr, + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int); + EXPECT_EQ(28, + *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int); allocator.deallocate( - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int, + allocator.state); params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int = nullptr; // max_value (double) @@ -233,10 +244,13 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_double); - EXPECT_EQ(1.23456, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_double); + ASSERT_NE(nullptr, + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_double); + EXPECT_EQ(1.23456, + *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_double); allocator.deallocate( - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_double, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_double, + allocator.state); allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_double = nullptr; @@ -249,10 +263,12 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int); + ASSERT_NE(nullptr, + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int); EXPECT_EQ(28, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int); allocator.deallocate( - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int, + allocator.state); params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int = nullptr; // step (double) @@ -262,10 +278,13 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_double); - EXPECT_EQ(1.23456, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_double); + ASSERT_NE(nullptr, + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_double); + EXPECT_EQ(1.23456, + *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_double); allocator.deallocate( - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_double, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_double, + allocator.state); allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_double = nullptr; @@ -278,12 +297,14 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description); + ASSERT_NE(nullptr, + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description); EXPECT_STREQ( "I am a string", params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description); allocator.deallocate( - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description, + allocator.state); allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description = nullptr; @@ -296,14 +317,17 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints); + ASSERT_NE(nullptr, + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints); EXPECT_STREQ( "I am a string", params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints); allocator.deallocate( - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints, + allocator.state); allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints = nullptr; + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints = + nullptr; } TEST(TestParse, parse_descriptor_bad_args) { @@ -484,7 +508,8 @@ TEST(TestParse, parse_descriptor_bad_types) { parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; allocator.deallocate( - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only, + allocator.state); allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only = nullptr; rcutils_reset_error(); @@ -500,7 +525,8 @@ TEST(TestParse, parse_descriptor_bad_types) { parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; allocator.deallocate( - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int, + allocator.state); params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int = nullptr; rcutils_reset_error(); @@ -515,7 +541,8 @@ TEST(TestParse, parse_descriptor_bad_types) { parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; allocator.deallocate( - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int, + allocator.state); params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int = nullptr; rcutils_reset_error(); @@ -530,7 +557,8 @@ TEST(TestParse, parse_descriptor_bad_types) { parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; allocator.deallocate( - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int, + allocator.state); params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int = nullptr; rcutils_reset_error(); @@ -545,7 +573,8 @@ TEST(TestParse, parse_descriptor_bad_types) { parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; allocator.deallocate( - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description, + allocator.state); allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description = nullptr; rcutils_reset_error(); @@ -561,9 +590,11 @@ TEST(TestParse, parse_descriptor_bad_types) { parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; allocator.deallocate( - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints, + allocator.state); allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints = nullptr; + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints = + nullptr; rcutils_reset_error(); } diff --git a/rcl_yaml_param_parser/test/test_yaml_descriptor.cpp b/rcl_yaml_param_parser/test/test_yaml_descriptor.cpp index 315eff7c7..f7350c8a8 100644 --- a/rcl_yaml_param_parser/test/test_yaml_descriptor.cpp +++ b/rcl_yaml_param_parser/test/test_yaml_descriptor.cpp @@ -103,7 +103,7 @@ TEST(TestYamlDescriptor, copy_string_fields) { src_descriptor.name = tmp_name; src_descriptor.description = tmp_description; src_descriptor.additional_constraints = tmp_additional_constraints; - + EXPECT_TRUE(rcl_yaml_descriptor_copy(&dest_descriptor, &src_descriptor, allocator)); ASSERT_NE(nullptr, dest_descriptor.name); ASSERT_NE(nullptr, dest_descriptor.description); From f5338cc4551430da21d29c99db826b4d775707d0 Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Tue, 23 Mar 2021 03:47:14 +0000 Subject: [PATCH 15/19] fix uncrustify issues Signed-off-by: Brian Wilcox --- rcl_yaml_param_parser/src/parse.c | 25 ++++++---- .../test/test_node_params_descriptors.cpp | 10 ++-- rcl_yaml_param_parser/test/test_parse.cpp | 48 ++++++++++++------- .../test/test_parse_yaml.cpp | 39 ++++++++++----- 4 files changed, 78 insertions(+), 44 deletions(-) diff --git a/rcl_yaml_param_parser/src/parse.c b/rcl_yaml_param_parser/src/parse.c index ba58d7da3..1d7c05089 100644 --- a/rcl_yaml_param_parser/src/parse.c +++ b/rcl_yaml_param_parser/src/parse.c @@ -509,7 +509,8 @@ rcutils_ret_t parse_descriptor( return RCUTILS_RET_ERROR; } // 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.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); @@ -526,8 +527,9 @@ rcutils_ret_t parse_descriptor( return RCUTILS_RET_ERROR; } - if (0 == strncmp("additional_constraints", ns_tracker->descriptor_key_ns, - strlen("additional_constraints"))) + 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; @@ -947,8 +949,9 @@ rcutils_ret_t parse_key( ret = RCUTILS_RET_ERROR; break; } - ret = replace_ns(ns_tracker, parameter_ns, (ns_tracker->num_parameter_ns + 1U), - NS_TYPE_PARAM, allocator); + ret = replace_ns( + ns_tracker, parameter_ns, (ns_tracker->num_parameter_ns + 1U), + NS_TYPE_PARAM, allocator); if (RCUTILS_RET_OK != ret) { RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( "Internal error replacing namespace at line %d", line_num); @@ -972,9 +975,10 @@ rcutils_ret_t parse_key( } ret = - replace_ns(ns_tracker, rcutils_strdup(value, allocator), - (ns_tracker->num_descriptor_key_ns + 1U), - NS_TYPE_DESCRIPTOR, allocator); + replace_ns( + ns_tracker, rcutils_strdup(value, allocator), + (ns_tracker->num_descriptor_key_ns + 1U), + NS_TYPE_DESCRIPTOR, allocator); if (RCUTILS_RET_OK != ret) { RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( "Internal error replacing namespace at line %d", line_num); @@ -1091,8 +1095,9 @@ rcutils_ret_t parse_file_events( if (map_level != 3U) { ret = parse_value(event, is_seq, node_idx, parameter_idx, &seq_data_type, params_st); } else { - ret = parse_descriptor(ns_tracker, event, is_seq, node_idx, parameter_idx, - params_st); + ret = parse_descriptor( + ns_tracker, event, is_seq, node_idx, parameter_idx, + params_st); } if (RCUTILS_RET_OK != ret) { break; diff --git a/rcl_yaml_param_parser/test/test_node_params_descriptors.cpp b/rcl_yaml_param_parser/test/test_node_params_descriptors.cpp index 87a79913f..a9d435b68 100644 --- a/rcl_yaml_param_parser/test/test_node_params_descriptors.cpp +++ b/rcl_yaml_param_parser/test/test_node_params_descriptors.cpp @@ -39,8 +39,9 @@ TEST(TestNodeParamsDescriptors, init_fini) { TEST(TestNodeParamsDescriptors, init_with_capacity_fini) { rcutils_allocator_t allocator = rcutils_get_default_allocator(); rcl_node_params_descriptors_t node_descriptors = {NULL, NULL, 0u, 1024u}; - EXPECT_EQ(RCUTILS_RET_OK, node_params_descriptors_init_with_capacity( - &node_descriptors, 1024, allocator)); + EXPECT_EQ( + RCUTILS_RET_OK, node_params_descriptors_init_with_capacity( + &node_descriptors, 1024, allocator)); EXPECT_NE(nullptr, node_descriptors.parameter_names); EXPECT_NE(nullptr, node_descriptors.parameter_descriptors); EXPECT_EQ(0u, node_descriptors.num_params); @@ -59,8 +60,9 @@ TEST(TestNodeParamsDescriptors, init_with_capacity_fini) { TEST(TestNodeParamsDescriptors, reallocate_with_capacity_fini) { rcutils_allocator_t allocator = rcutils_get_default_allocator(); rcl_node_params_descriptors_t node_descriptors = {NULL, NULL, 0u, 1024u}; - EXPECT_EQ(RCUTILS_RET_OK, node_params_descriptors_init_with_capacity( - &node_descriptors, 1024, allocator)); + EXPECT_EQ( + RCUTILS_RET_OK, node_params_descriptors_init_with_capacity( + &node_descriptors, 1024, allocator)); EXPECT_NE(nullptr, node_descriptors.parameter_names); EXPECT_NE(nullptr, node_descriptors.parameter_descriptors); EXPECT_EQ(0u, node_descriptors.num_params); diff --git a/rcl_yaml_param_parser/test/test_parse.cpp b/rcl_yaml_param_parser/test/test_parse.cpp index ee1a42669..2ce4f86af 100644 --- a/rcl_yaml_param_parser/test/test_parse.cpp +++ b/rcl_yaml_param_parser/test/test_parse.cpp @@ -175,7 +175,8 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, + ASSERT_NE( + nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only); EXPECT_TRUE(*params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only); allocator.deallocate( @@ -193,9 +194,11 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, + ASSERT_NE( + nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int); - EXPECT_EQ(28, + EXPECT_EQ( + 28, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int); allocator.deallocate( params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_int, @@ -209,9 +212,11 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, + ASSERT_NE( + nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_double); - EXPECT_EQ(1.23456, + EXPECT_EQ( + 1.23456, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_double); allocator.deallocate( params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].min_value_double, @@ -228,9 +233,11 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, + ASSERT_NE( + nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int); - EXPECT_EQ(28, + EXPECT_EQ( + 28, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int); allocator.deallocate( params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int, @@ -244,9 +251,11 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, + ASSERT_NE( + nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_double); - EXPECT_EQ(1.23456, + EXPECT_EQ( + 1.23456, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_double); allocator.deallocate( params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_double, @@ -254,7 +263,7 @@ TEST(TestParse, parse_descriptor) { allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_double = nullptr; - // step (int) + // step (int) ns_tracker.descriptor_key_ns = rcutils_strdup("step", allocator); ASSERT_STREQ("step", ns_tracker.descriptor_key_ns); event.data.scalar.value = int_value; @@ -263,7 +272,8 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, + ASSERT_NE( + nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int); EXPECT_EQ(28, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_int); allocator.deallocate( @@ -278,9 +288,11 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, + ASSERT_NE( + nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_double); - EXPECT_EQ(1.23456, + EXPECT_EQ( + 1.23456, *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_double); allocator.deallocate( params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].step_double, @@ -297,7 +309,8 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, + ASSERT_NE( + nullptr, params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].description); EXPECT_STREQ( "I am a string", @@ -317,8 +330,9 @@ TEST(TestParse, parse_descriptor) { RCUTILS_RET_OK, parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << rcutils_get_error_string().str; - ASSERT_NE(nullptr, - params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints); + ASSERT_NE( + nullptr, + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints); EXPECT_STREQ( "I am a string", params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].additional_constraints); @@ -546,7 +560,7 @@ TEST(TestParse, parse_descriptor_bad_types) { params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].max_value_int = nullptr; rcutils_reset_error(); - // step (int) + // step (int) ns_tracker.descriptor_key_ns = rcutils_strdup("step", allocator); ASSERT_STREQ("step", ns_tracker.descriptor_key_ns); // step: catch invalid value type diff --git a/rcl_yaml_param_parser/test/test_parse_yaml.cpp b/rcl_yaml_param_parser/test/test_parse_yaml.cpp index 66f4983ef..f60c31486 100644 --- a/rcl_yaml_param_parser/test/test_parse_yaml.cpp +++ b/rcl_yaml_param_parser/test/test_parse_yaml.cpp @@ -667,18 +667,21 @@ TEST(test_file_parser, correct_syntax_descriptors) { 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({ + 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({ + 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({ + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { rcl_yaml_node_struct_fini(params_hdl); }); bool res = rcl_parse_yaml_file(path, params_hdl); @@ -686,7 +689,8 @@ TEST(test_file_parser, correct_syntax_descriptors) { 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({ + 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; @@ -695,7 +699,8 @@ TEST(test_file_parser, correct_syntax_descriptors) { 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({ + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { rcl_yaml_node_struct_fini(copy_of_params_hdl); }); @@ -773,12 +778,14 @@ TEST(test_parser, param_assign_in_descriptors) { 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({ + 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({ + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { allocator.deallocate(path, allocator.state); }); ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; @@ -794,12 +801,14 @@ TEST(test_parser, invalid_param_descriptor_key) { 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({ + 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({ + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { allocator.deallocate(path, allocator.state); }); ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; @@ -815,12 +824,14 @@ TEST(test_parser, invalid_param_descriptor_type) { 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({ + 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({ + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { allocator.deallocate(path, allocator.state); }); ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; @@ -836,12 +847,14 @@ TEST(test_parser, no_value_descriptor) { 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({ + 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({ + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { allocator.deallocate(path, allocator.state); }); ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; From a5939aaeadcb609c765da022c26a8b1a468fd04e Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Tue, 23 Mar 2021 04:02:27 +0000 Subject: [PATCH 16/19] change param descriptor key name to ros__parameter_descriptors Signed-off-by: Brian Wilcox --- rcl_yaml_param_parser/src/impl/types.h | 2 +- rcl_yaml_param_parser/test/assign_param_in_descriptors.yaml | 2 +- rcl_yaml_param_parser/test/correct_param_descriptors.yaml | 4 ++-- rcl_yaml_param_parser/test/invalid_param_descriptor_key.yaml | 2 +- rcl_yaml_param_parser/test/invalid_param_descriptor_type.yaml | 2 +- rcl_yaml_param_parser/test/no_value_descriptor.yaml | 2 +- rcl_yaml_param_parser/test/overlay_descriptors.yaml | 4 ++-- 7 files changed, 9 insertions(+), 9 deletions(-) diff --git a/rcl_yaml_param_parser/src/impl/types.h b/rcl_yaml_param_parser/src/impl/types.h index c9ca94a81..79d073c3b 100644 --- a/rcl_yaml_param_parser/src/impl/types.h +++ b/rcl_yaml_param_parser/src/impl/types.h @@ -28,7 +28,7 @@ extern "C" #endif #define PARAMS_KEY "ros__parameters" -#define PARAMS_DESCRIPTORS_KEY "parameter__descriptors" +#define PARAMS_DESCRIPTORS_KEY "ros__parameter_descriptors" #define NODE_NS_SEPERATOR "/" #define PARAMETER_NS_SEPERATOR "." diff --git a/rcl_yaml_param_parser/test/assign_param_in_descriptors.yaml b/rcl_yaml_param_parser/test/assign_param_in_descriptors.yaml index 7702e714e..73b7a461b 100644 --- a/rcl_yaml_param_parser/test/assign_param_in_descriptors.yaml +++ b/rcl_yaml_param_parser/test/assign_param_in_descriptors.yaml @@ -1,5 +1,5 @@ node1: - parameter__descriptors: + ros__parameter_descriptors: bar: 42 foo: read_only: true diff --git a/rcl_yaml_param_parser/test/correct_param_descriptors.yaml b/rcl_yaml_param_parser/test/correct_param_descriptors.yaml index 40072f394..245f3ae0b 100644 --- a/rcl_yaml_param_parser/test/correct_param_descriptors.yaml +++ b/rcl_yaml_param_parser/test/correct_param_descriptors.yaml @@ -3,7 +3,7 @@ node_ns: node1: - parameter__descriptors: + ros__parameter_descriptors: param1: type: 2 min_value: 5 @@ -23,7 +23,7 @@ node_ns: foo: bar: 10 baz: "hello" - parameter__descriptors: + ros__parameter_descriptors: foo: bar: description: "namespaced parameter" diff --git a/rcl_yaml_param_parser/test/invalid_param_descriptor_key.yaml b/rcl_yaml_param_parser/test/invalid_param_descriptor_key.yaml index 104d4e5b7..a5f7d6b38 100644 --- a/rcl_yaml_param_parser/test/invalid_param_descriptor_key.yaml +++ b/rcl_yaml_param_parser/test/invalid_param_descriptor_key.yaml @@ -1,5 +1,5 @@ node1: - parameter__descriptors: + ros__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 index a55510dde..01c92c263 100644 --- a/rcl_yaml_param_parser/test/invalid_param_descriptor_type.yaml +++ b/rcl_yaml_param_parser/test/invalid_param_descriptor_type.yaml @@ -1,4 +1,4 @@ node1: - parameter__descriptors: + ros__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 index 5b6bc89c8..d78c3fb52 100644 --- a/rcl_yaml_param_parser/test/no_value_descriptor.yaml +++ b/rcl_yaml_param_parser/test/no_value_descriptor.yaml @@ -1,4 +1,4 @@ node1: - parameter__descriptors: + ros__parameter_descriptors: foo: description: diff --git a/rcl_yaml_param_parser/test/overlay_descriptors.yaml b/rcl_yaml_param_parser/test/overlay_descriptors.yaml index 34e7555f5..953819d19 100644 --- a/rcl_yaml_param_parser/test/overlay_descriptors.yaml +++ b/rcl_yaml_param_parser/test/overlay_descriptors.yaml @@ -1,12 +1,12 @@ node_ns: node1: - parameter__descriptors: + ros__parameter_descriptors: param1: max_value: 200 param2: min_value: -2.0 node2: - parameter__descriptors: + ros__parameter_descriptors: foo: bar: read_only: true From e6cf65db73fc0839291337effbf7cbcffd9be3d0 Mon Sep 17 00:00:00 2001 From: Brian Wilcox Date: Tue, 29 Jun 2021 15:59:58 +0000 Subject: [PATCH 17/19] remove error msg for node name before key to allow for both keys param/descriptor keys under node name Signed-off-by: Brian Wilcox Signed-off-by: Brian --- rcl_yaml_param_parser/src/parse.c | 14 -------------- 1 file changed, 14 deletions(-) diff --git a/rcl_yaml_param_parser/src/parse.c b/rcl_yaml_param_parser/src/parse.c index 1d7c05089..f1814cda3 100644 --- a/rcl_yaml_param_parser/src/parse.c +++ b/rcl_yaml_param_parser/src/parse.c @@ -786,13 +786,6 @@ rcutils_ret_t parse_key( { /// Till we get PARAMS_KEY or PARAMS_DESCRIPTORS_KEY, keep adding to node namespace if (0 == strncmp(PARAMS_KEY, value, strlen(PARAMS_KEY))) { - if (0U == ns_tracker->num_node_ns) { - RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( - "There are no node names before %s at line %d", PARAMS_KEY, line_num); - ret = RCUTILS_RET_ERROR; - break; - } - if (*is_new_map) { /// The previous key(last name in namespace) was the node name. Remove it /// from the namespace @@ -824,13 +817,6 @@ rcutils_ret_t parse_key( /// Bump the map level to PARAMS (*map_level)++; } else if (0 == strncmp(PARAMS_DESCRIPTORS_KEY, value, strlen(PARAMS_DESCRIPTORS_KEY))) { - if (0U == ns_tracker->num_node_ns) { - RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( - "There are no node names before %s at line %d", PARAMS_DESCRIPTORS_KEY, line_num); - ret = RCUTILS_RET_ERROR; - break; - } - if (*is_new_map) { /// The previous key(last name in namespace) was the node name. Remove it /// from the namespace From 1d1eb27bf861a57c647f583d3d956a4aa8fb6a69 Mon Sep 17 00:00:00 2001 From: Brian Date: Tue, 7 Dec 2021 14:02:05 +0000 Subject: [PATCH 18/19] address feedback, remove descriptor name, change field naming Signed-off-by: Brian --- .../include/rcl_yaml_param_parser/parser.h | 2 +- .../include/rcl_yaml_param_parser/types.h | 3 +- .../src/node_params_descriptors.c | 16 ++++----- rcl_yaml_param_parser/src/parse.c | 36 +++++++++++++------ rcl_yaml_param_parser/src/parser.c | 10 ++---- rcl_yaml_param_parser/src/yaml_descriptor.c | 13 +------ .../test/test_node_params_descriptors.cpp | 14 ++++---- .../test/test_parse_yaml.cpp | 8 ----- .../test/test_yaml_descriptor.cpp | 7 ---- 9 files changed, 46 insertions(+), 63 deletions(-) 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 03cd7c17c..131a92365 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 @@ -121,7 +121,7 @@ rcl_variant_t * rcl_yaml_node_struct_get( /// \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[in] param_name is the name of the parameter whose descriptor 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 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 dd8c1142a..dc53184dd 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 @@ -99,7 +99,6 @@ typedef struct rcl_node_params_s /// \brief param_descriptor_t stores the descriptor of a parameter typedef struct rcl_param_descriptor_s { - char * name; bool * read_only; uint8_t * type; char * description; @@ -118,7 +117,7 @@ typedef struct rcl_node_params_descriptors_s { char ** parameter_names; ///< Array of parameter names (keys) rcl_param_descriptor_t * parameter_descriptors; ///< Array of corresponding parameter descriptors - size_t num_params; ///< Number of parameters in the node + size_t num_descriptors; ///< Number of parameters in the node size_t capacity_descriptors; ///< Capacity of parameters in the node } rcl_node_params_descriptors_t; diff --git a/rcl_yaml_param_parser/src/node_params_descriptors.c b/rcl_yaml_param_parser/src/node_params_descriptors.c index 6ad353941..5eb003252 100644 --- a/rcl_yaml_param_parser/src/node_params_descriptors.c +++ b/rcl_yaml_param_parser/src/node_params_descriptors.c @@ -51,11 +51,11 @@ rcutils_ret_t node_params_descriptors_init_with_capacity( if (NULL == node_descriptors->parameter_descriptors) { allocator.deallocate(node_descriptors->parameter_names, allocator.state); node_descriptors->parameter_names = NULL; - RCUTILS_SET_ERROR_MSG("Failed to allocate memory for node parameter values"); + RCUTILS_SET_ERROR_MSG("Failed to allocate memory for node parameter descriptors"); return RCUTILS_RET_BAD_ALLOC; } - node_descriptors->num_params = 0U; + node_descriptors->num_descriptors = 0U; node_descriptors->capacity_descriptors = capacity; return RCUTILS_RET_OK; } @@ -68,12 +68,12 @@ rcutils_ret_t node_params_descriptors_reallocate( RCUTILS_CHECK_ARGUMENT_FOR_NULL(node_descriptors, RCUTILS_RET_INVALID_ARGUMENT); RCUTILS_CHECK_ALLOCATOR_WITH_MSG( &allocator, "invalid allocator", return RCUTILS_RET_INVALID_ARGUMENT); - // invalid if new_capacity is less than num_params - if (new_capacity < node_descriptors->num_params) { + // invalid if new_capacity is less than num_descriptors + if (new_capacity < node_descriptors->num_descriptors) { RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( "new capacity '%zu' must be greater than or equal to '%zu'", new_capacity, - node_descriptors->num_params); + node_descriptors->num_descriptors); return RCUTILS_RET_INVALID_ARGUMENT; } @@ -119,7 +119,7 @@ void rcl_yaml_node_params_descriptors_fini( } if (NULL != node_descriptors->parameter_names) { - for (size_t parameter_idx = 0U; parameter_idx < node_descriptors->num_params; + for (size_t parameter_idx = 0U; parameter_idx < node_descriptors->num_descriptors; parameter_idx++) { char * param_name = node_descriptors->parameter_names[parameter_idx]; @@ -132,7 +132,7 @@ void rcl_yaml_node_params_descriptors_fini( } if (NULL != node_descriptors->parameter_descriptors) { - for (size_t parameter_idx = 0U; parameter_idx < node_descriptors->num_params; + for (size_t parameter_idx = 0U; parameter_idx < node_descriptors->num_descriptors; parameter_idx++) { rcl_yaml_descriptor_fini( @@ -143,6 +143,6 @@ void rcl_yaml_node_params_descriptors_fini( node_descriptors->parameter_descriptors = NULL; } - node_descriptors->num_params = 0; + node_descriptors->num_descriptors = 0; node_descriptors->capacity_descriptors = 0; } diff --git a/rcl_yaml_param_parser/src/parse.c b/rcl_yaml_param_parser/src/parse.c index f1814cda3..ffa46640e 100644 --- a/rcl_yaml_param_parser/src/parse.c +++ b/rcl_yaml_param_parser/src/parse.c @@ -495,6 +495,13 @@ rcutils_ret_t parse_descriptor( rcl_param_descriptor_t * param_descriptor = &(params_st->descriptors[node_idx].parameter_descriptors[parameter_idx]); + rcl_node_params_descriptors_t * node_descriptors_st = &(params_st->descriptors[node_idx]); + + // Increase descriptor count only once when a new parameter descriptor value is parsed + if (parameter_idx == node_descriptors_st->num_descriptors) { + node_descriptors_st->num_descriptors++; + } + data_types_t val_type; void * ret_val = get_value(value, style, &val_type, allocator); if (NULL == ret_val) { @@ -508,6 +515,7 @@ rcutils_ret_t parse_descriptor( "Parameter assignment at line %d unallowed in " PARAMS_DESCRIPTORS_KEY, line_num); return RCUTILS_RET_ERROR; } + // If parsing a yaml value, then current parameter namespace must be parameter name allocator.deallocate( params_st->descriptors[node_idx].parameter_names[parameter_idx], @@ -515,13 +523,6 @@ rcutils_ret_t parse_descriptor( 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++; - } - if (NULL == ns_tracker->descriptor_key_ns) { RCUTILS_SET_ERROR_MSG("Internal error: Invalid mem"); return RCUTILS_RET_ERROR; @@ -1312,19 +1313,32 @@ rcutils_ret_t find_descriptor( assert(node_idx < param_st->num_nodes); rcl_node_params_descriptors_t * node_descriptors_st = &(param_st->descriptors[node_idx]); - for (*parameter_idx = 0U; *parameter_idx < node_descriptors_st->num_params; (*parameter_idx)++) { + for (*parameter_idx = 0U; *parameter_idx < node_descriptors_st->num_descriptors; + (*parameter_idx)++) + { if (0 == strcmp(node_descriptors_st->parameter_names[*parameter_idx], parameter_name)) { - // Parameter found. + // Descriptor found. return RCUTILS_RET_OK; } } - // Parameter not found, add it. + // Descriptor not found, add it. rcutils_allocator_t allocator = param_st->allocator; + // Reallocate if necessary + if (node_descriptors_st->num_descriptors >= node_descriptors_st->capacity_descriptors) { + if (RCUTILS_RET_OK != node_params_descriptors_reallocate( + node_descriptors_st, node_descriptors_st->capacity_descriptors * 2, allocator)) + { + return RCUTILS_RET_BAD_ALLOC; + } + } + if (NULL != node_descriptors_st->parameter_names[*parameter_idx]) { + param_st->allocator.deallocate( + node_descriptors_st->parameter_names[*parameter_idx], param_st->allocator.state); + } node_descriptors_st->parameter_names[*parameter_idx] = rcutils_strdup(parameter_name, allocator); if (NULL == node_descriptors_st->parameter_names[*parameter_idx]) { return RCUTILS_RET_BAD_ALLOC; } - // node_descriptors_st->num_params++; return RCUTILS_RET_OK; } diff --git a/rcl_yaml_param_parser/src/parser.c b/rcl_yaml_param_parser/src/parser.c index 9bef720b9..6efd6a2ae 100644 --- a/rcl_yaml_param_parser/src/parser.c +++ b/rcl_yaml_param_parser/src/parser.c @@ -227,14 +227,14 @@ rcl_params_t * rcl_yaml_node_struct_copy( } goto fail; } - for (size_t desc_idx = 0U; desc_idx < node_params_descriptors_st->num_params; ++desc_idx) { + for (size_t desc_idx = 0U; desc_idx < node_params_descriptors_st->num_descriptors; ++desc_idx) { out_node_params_descriptors_st->parameter_names[desc_idx] = rcutils_strdup(node_params_descriptors_st->parameter_names[desc_idx], allocator); if (NULL == out_node_params_descriptors_st->parameter_names[desc_idx]) { RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem\n"); goto fail; } - out_node_params_descriptors_st->num_params++; + out_node_params_descriptors_st->num_descriptors++; const rcl_param_descriptor_t * param_descriptor = &(node_params_descriptors_st->parameter_descriptors[desc_idx]); @@ -542,7 +542,7 @@ void rcl_yaml_node_struct_print( if (NULL != params_st->descriptors) { rcl_node_params_descriptors_t * node_descriptors_st = &(params_st->descriptors[node_idx]); - for (size_t parameter_idx = 0U; parameter_idx < node_descriptors_st->num_params; + for (size_t parameter_idx = 0U; parameter_idx < node_descriptors_st->num_descriptors; parameter_idx++) { if (NULL != node_descriptors_st->parameter_names) { @@ -552,10 +552,6 @@ void rcl_yaml_node_struct_print( } rcl_param_descriptor_t * descriptor = &(node_descriptors_st->parameter_descriptors[parameter_idx]); - if (NULL != descriptor->name) { - printf("\n%*sname: ", param_col + 2, ""); - printf("%s", descriptor->name); - } if (NULL != descriptor->description) { printf("\n%*sdescription: ", param_col + 2, ""); printf("%s", descriptor->description); diff --git a/rcl_yaml_param_parser/src/yaml_descriptor.c b/rcl_yaml_param_parser/src/yaml_descriptor.c index 4424fd627..507730932 100644 --- a/rcl_yaml_param_parser/src/yaml_descriptor.c +++ b/rcl_yaml_param_parser/src/yaml_descriptor.c @@ -28,10 +28,6 @@ void rcl_yaml_descriptor_fini( return; } - if (NULL != param_descriptor->name) { - allocator.deallocate(param_descriptor->name, allocator.state); - param_descriptor->name = NULL; - } if (NULL != param_descriptor->read_only) { allocator.deallocate(param_descriptor->read_only, allocator.state); param_descriptor->read_only = NULL; @@ -82,14 +78,7 @@ bool rcl_yaml_descriptor_copy( if (NULL == param_descriptor || NULL == out_param_descriptor) { return false; } - if (NULL != param_descriptor->name) { - out_param_descriptor->name = - rcutils_strdup(param_descriptor->name, allocator); - if (NULL == out_param_descriptor->name) { - RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); - return false; - } - } + if (NULL != param_descriptor->description) { out_param_descriptor->description = rcutils_strdup(param_descriptor->description, allocator); diff --git a/rcl_yaml_param_parser/test/test_node_params_descriptors.cpp b/rcl_yaml_param_parser/test/test_node_params_descriptors.cpp index a9d435b68..1d9a20d02 100644 --- a/rcl_yaml_param_parser/test/test_node_params_descriptors.cpp +++ b/rcl_yaml_param_parser/test/test_node_params_descriptors.cpp @@ -23,12 +23,12 @@ TEST(TestNodeParamsDescriptors, init_fini) { EXPECT_EQ(RCUTILS_RET_OK, node_params_descriptors_init(&node_descriptors, allocator)); EXPECT_NE(nullptr, node_descriptors.parameter_names); EXPECT_NE(nullptr, node_descriptors.parameter_descriptors); - EXPECT_EQ(0u, node_descriptors.num_params); + EXPECT_EQ(0u, node_descriptors.num_descriptors); EXPECT_EQ(128u, node_descriptors.capacity_descriptors); rcl_yaml_node_params_descriptors_fini(&node_descriptors, allocator); EXPECT_EQ(nullptr, node_descriptors.parameter_names); EXPECT_EQ(nullptr, node_descriptors.parameter_descriptors); - EXPECT_EQ(0u, node_descriptors.num_params); + EXPECT_EQ(0u, node_descriptors.num_descriptors); EXPECT_EQ(0u, node_descriptors.capacity_descriptors); // This function doesn't return anything, so just check it doesn't segfault on the second try @@ -44,12 +44,12 @@ TEST(TestNodeParamsDescriptors, init_with_capacity_fini) { &node_descriptors, 1024, allocator)); EXPECT_NE(nullptr, node_descriptors.parameter_names); EXPECT_NE(nullptr, node_descriptors.parameter_descriptors); - EXPECT_EQ(0u, node_descriptors.num_params); + EXPECT_EQ(0u, node_descriptors.num_descriptors); EXPECT_EQ(1024u, node_descriptors.capacity_descriptors); rcl_yaml_node_params_descriptors_fini(&node_descriptors, allocator); EXPECT_EQ(nullptr, node_descriptors.parameter_names); EXPECT_EQ(nullptr, node_descriptors.parameter_descriptors); - EXPECT_EQ(0u, node_descriptors.num_params); + EXPECT_EQ(0u, node_descriptors.num_descriptors); EXPECT_EQ(0u, node_descriptors.capacity_descriptors); // This function doesn't return anything, so just check it doesn't segfault on the second try @@ -65,17 +65,17 @@ TEST(TestNodeParamsDescriptors, reallocate_with_capacity_fini) { &node_descriptors, 1024, allocator)); EXPECT_NE(nullptr, node_descriptors.parameter_names); EXPECT_NE(nullptr, node_descriptors.parameter_descriptors); - EXPECT_EQ(0u, node_descriptors.num_params); + EXPECT_EQ(0u, node_descriptors.num_descriptors); EXPECT_EQ(1024u, node_descriptors.capacity_descriptors); EXPECT_EQ(RCUTILS_RET_OK, node_params_descriptors_reallocate(&node_descriptors, 2048, allocator)); EXPECT_NE(nullptr, node_descriptors.parameter_names); EXPECT_NE(nullptr, node_descriptors.parameter_descriptors); - EXPECT_EQ(0u, node_descriptors.num_params); + EXPECT_EQ(0u, node_descriptors.num_descriptors); EXPECT_EQ(2048u, node_descriptors.capacity_descriptors); rcl_yaml_node_params_descriptors_fini(&node_descriptors, allocator); EXPECT_EQ(nullptr, node_descriptors.parameter_names); EXPECT_EQ(nullptr, node_descriptors.parameter_descriptors); - EXPECT_EQ(0u, node_descriptors.num_params); + EXPECT_EQ(0u, node_descriptors.num_descriptors); EXPECT_EQ(0u, node_descriptors.capacity_descriptors); // This function doesn't return anything, so just check it doesn't segfault on the second try diff --git a/rcl_yaml_param_parser/test/test_parse_yaml.cpp b/rcl_yaml_param_parser/test/test_parse_yaml.cpp index f60c31486..0cef8ecb0 100644 --- a/rcl_yaml_param_parser/test/test_parse_yaml.cpp +++ b/rcl_yaml_param_parser/test/test_parse_yaml.cpp @@ -709,8 +709,6 @@ TEST(test_file_parser, correct_syntax_descriptors) { 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); @@ -728,8 +726,6 @@ TEST(test_file_parser, correct_syntax_descriptors) { 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); @@ -739,8 +735,6 @@ TEST(test_file_parser, correct_syntax_descriptors) { 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); @@ -748,8 +742,6 @@ TEST(test_file_parser, correct_syntax_descriptors) { 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); diff --git a/rcl_yaml_param_parser/test/test_yaml_descriptor.cpp b/rcl_yaml_param_parser/test/test_yaml_descriptor.cpp index f7350c8a8..2b35f006d 100644 --- a/rcl_yaml_param_parser/test/test_yaml_descriptor.cpp +++ b/rcl_yaml_param_parser/test/test_yaml_descriptor.cpp @@ -84,9 +84,6 @@ TEST(TestYamlDescriptor, copy_string_fields) { rcl_param_descriptor_t dest_descriptor{}; rcutils_allocator_t allocator = rcutils_get_default_allocator(); - char * tmp_name = rcutils_strdup("param_name", allocator); - ASSERT_STREQ("param_name", tmp_name); - char * tmp_description = rcutils_strdup("param description", allocator); ASSERT_STREQ("param description", tmp_description); @@ -95,24 +92,20 @@ TEST(TestYamlDescriptor, copy_string_fields) { OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( { - allocator.deallocate(tmp_name, allocator.state); allocator.deallocate(tmp_description, allocator.state); allocator.deallocate(tmp_additional_constraints, allocator.state); }); - src_descriptor.name = tmp_name; src_descriptor.description = tmp_description; src_descriptor.additional_constraints = tmp_additional_constraints; EXPECT_TRUE(rcl_yaml_descriptor_copy(&dest_descriptor, &src_descriptor, allocator)); - ASSERT_NE(nullptr, dest_descriptor.name); ASSERT_NE(nullptr, dest_descriptor.description); ASSERT_NE(nullptr, dest_descriptor.additional_constraints); OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( { rcl_yaml_descriptor_fini(&dest_descriptor, allocator); }); - EXPECT_STREQ(tmp_name, dest_descriptor.name); EXPECT_STREQ(tmp_description, dest_descriptor.description); EXPECT_STREQ(tmp_additional_constraints, dest_descriptor.additional_constraints); } From a66f54d9d1b82d988e9e7e25ee4bb85f21f30033 Mon Sep 17 00:00:00 2001 From: Brian Date: Tue, 7 Dec 2021 15:47:03 +0000 Subject: [PATCH 19/19] add dynamic_typing field Signed-off-by: Brian --- .../include/rcl_yaml_param_parser/types.h | 1 + rcl_yaml_param_parser/src/parse.c | 10 +++++ rcl_yaml_param_parser/src/parser.c | 4 ++ rcl_yaml_param_parser/src/yaml_descriptor.c | 12 ++++++ .../test/correct_param_descriptors.yaml | 1 + rcl_yaml_param_parser/test/test_parse.cpp | 37 +++++++++++++++++++ .../test/test_parse_yaml.cpp | 2 + 7 files changed, 67 insertions(+) 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 dc53184dd..60f1f243a 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 @@ -100,6 +100,7 @@ typedef struct rcl_node_params_s typedef struct rcl_param_descriptor_s { bool * read_only; + bool * dynamic_typing; uint8_t * type; char * description; char * additional_constraints; diff --git a/rcl_yaml_param_parser/src/parse.c b/rcl_yaml_param_parser/src/parse.c index ffa46640e..ceadf8718 100644 --- a/rcl_yaml_param_parser/src/parse.c +++ b/rcl_yaml_param_parser/src/parse.c @@ -528,6 +528,7 @@ rcutils_ret_t parse_descriptor( return RCUTILS_RET_ERROR; } + char * dt = "dynamic_typing"; if (0 == strncmp( "additional_constraints", ns_tracker->descriptor_key_ns, strlen("additional_constraints"))) @@ -604,6 +605,15 @@ rcutils_ret_t parse_descriptor( line_num); return RCUTILS_RET_ERROR; } + } else if (0 == strncmp(dt, ns_tracker->descriptor_key_ns, strlen(dt))) { + if (val_type == DATA_TYPE_BOOL) { + param_descriptor->dynamic_typing = (bool *)ret_val; + } else { + RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( + "Value type 'bool' expected at line %d for " PARAMS_DESCRIPTORS_KEY " key: dynamic_typing", + line_num); + return RCUTILS_RET_ERROR; + } } else { RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING( "Descriptor key at line %d does not match any valid " PARAMS_DESCRIPTORS_KEY " key", diff --git a/rcl_yaml_param_parser/src/parser.c b/rcl_yaml_param_parser/src/parser.c index 6efd6a2ae..dafc49240 100644 --- a/rcl_yaml_param_parser/src/parser.c +++ b/rcl_yaml_param_parser/src/parser.c @@ -592,6 +592,10 @@ void rcl_yaml_node_struct_print( printf("\n%*sread_only: ", param_col + 2, ""); printf("%s", *(descriptor->read_only) ? "true" : "false"); } + if (NULL != descriptor->dynamic_typing) { + printf("\n%*sdynamic_typing: ", param_col + 2, ""); + printf("%s", *(descriptor->dynamic_typing) ? "true" : "false"); + } printf("\n"); } } diff --git a/rcl_yaml_param_parser/src/yaml_descriptor.c b/rcl_yaml_param_parser/src/yaml_descriptor.c index 507730932..c0b95bc8e 100644 --- a/rcl_yaml_param_parser/src/yaml_descriptor.c +++ b/rcl_yaml_param_parser/src/yaml_descriptor.c @@ -32,6 +32,10 @@ void rcl_yaml_descriptor_fini( allocator.deallocate(param_descriptor->read_only, allocator.state); param_descriptor->read_only = NULL; } + if (NULL != param_descriptor->dynamic_typing) { + allocator.deallocate(param_descriptor->dynamic_typing, allocator.state); + param_descriptor->dynamic_typing = NULL; + } if (NULL != param_descriptor->type) { allocator.deallocate(param_descriptor->type, allocator.state); param_descriptor->type = NULL; @@ -161,5 +165,13 @@ bool rcl_yaml_descriptor_copy( } *(out_param_descriptor->read_only) = *(param_descriptor->read_only); } + if (NULL != param_descriptor->dynamic_typing) { + out_param_descriptor->dynamic_typing = allocator.allocate(sizeof(bool), allocator.state); + if (NULL == out_param_descriptor->dynamic_typing) { + RCUTILS_SAFE_FWRITE_TO_STDERR("Error allocating mem"); + return false; + } + *(out_param_descriptor->dynamic_typing) = *(param_descriptor->dynamic_typing); + } return true; } diff --git a/rcl_yaml_param_parser/test/correct_param_descriptors.yaml b/rcl_yaml_param_parser/test/correct_param_descriptors.yaml index 245f3ae0b..819eab6da 100644 --- a/rcl_yaml_param_parser/test/correct_param_descriptors.yaml +++ b/rcl_yaml_param_parser/test/correct_param_descriptors.yaml @@ -30,3 +30,4 @@ node_ns: read_only: false baz: description: "another namespaced parameter" + dynamic_typing: true diff --git a/rcl_yaml_param_parser/test/test_parse.cpp b/rcl_yaml_param_parser/test/test_parse.cpp index 2ce4f86af..6be3d99e1 100644 --- a/rcl_yaml_param_parser/test/test_parse.cpp +++ b/rcl_yaml_param_parser/test/test_parse.cpp @@ -185,6 +185,26 @@ TEST(TestParse, parse_descriptor) { allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only = nullptr; + // dynamic_typing + ns_tracker.descriptor_key_ns = rcutils_strdup("dynamic_typing", allocator); + ASSERT_STREQ("dynamic_typing", ns_tracker.descriptor_key_ns); + event.data.scalar.value = bool_value; + event.data.scalar.length = bool_value_length; + EXPECT_EQ( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + ASSERT_NE( + nullptr, + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].dynamic_typing); + EXPECT_TRUE( + *params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].dynamic_typing); + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].dynamic_typing, + allocator.state); + allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].dynamic_typing = nullptr; + // min_value (int) ns_tracker.descriptor_key_ns = rcutils_strdup("min_value", allocator); ASSERT_STREQ("min_value", ns_tracker.descriptor_key_ns); @@ -528,6 +548,23 @@ TEST(TestParse, parse_descriptor_bad_types) { params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].read_only = nullptr; rcutils_reset_error(); + // dynamic_typing + ns_tracker.descriptor_key_ns = rcutils_strdup("dynamic_typing", allocator); + ASSERT_STREQ("dynamic_typing", ns_tracker.descriptor_key_ns); + // dynamic_typing: catch invalid value type + event.data.scalar.value = double_value; + event.data.scalar.length = double_value_length; + EXPECT_NE( + RCUTILS_RET_OK, + parse_descriptor(&ns_tracker, event, is_seq, node_idx, parameter_idx, params_st)) << + rcutils_get_error_string().str; + allocator.deallocate( + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].dynamic_typing, + allocator.state); + allocator.deallocate(ns_tracker.descriptor_key_ns, allocator.state); + params_st->descriptors[node_idx].parameter_descriptors[parameter_idx].dynamic_typing = nullptr; + rcutils_reset_error(); + // min_value ns_tracker.descriptor_key_ns = rcutils_strdup("min_value", allocator); ASSERT_STREQ("min_value", ns_tracker.descriptor_key_ns); diff --git a/rcl_yaml_param_parser/test/test_parse_yaml.cpp b/rcl_yaml_param_parser/test/test_parse_yaml.cpp index 0cef8ecb0..cc4160b29 100644 --- a/rcl_yaml_param_parser/test/test_parse_yaml.cpp +++ b/rcl_yaml_param_parser/test/test_parse_yaml.cpp @@ -759,6 +759,8 @@ TEST(test_file_parser, correct_syntax_descriptors) { ASSERT_TRUE(NULL != param_value) << rcutils_get_error_string().str; ASSERT_TRUE(NULL != param_value->string_value); EXPECT_STREQ("hello", param_value->string_value); + ASSERT_TRUE(NULL != param_descriptor->dynamic_typing); + EXPECT_TRUE(*param_descriptor->dynamic_typing); rcl_yaml_node_struct_print(params); }