Skip to content

Commit

Permalink
address feedback, remove descriptor name, change field naming
Browse files Browse the repository at this point in the history
Signed-off-by: Brian <[email protected]>
  • Loading branch information
bpwilcox committed Dec 7, 2021
1 parent e6cf65d commit 1d1eb27
Show file tree
Hide file tree
Showing 9 changed files with 46 additions and 63 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
3 changes: 1 addition & 2 deletions rcl_yaml_param_parser/include/rcl_yaml_param_parser/types.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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;

Expand Down
16 changes: 8 additions & 8 deletions rcl_yaml_param_parser/src/node_params_descriptors.c
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
Expand All @@ -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;
}

Expand Down Expand Up @@ -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];
Expand All @@ -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(
Expand All @@ -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;
}
36 changes: 25 additions & 11 deletions rcl_yaml_param_parser/src/parse.c
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand All @@ -508,20 +515,14 @@ 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],
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 (NULL == ns_tracker->descriptor_key_ns) {
RCUTILS_SET_ERROR_MSG("Internal error: Invalid mem");
return RCUTILS_RET_ERROR;
Expand Down Expand Up @@ -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;
}

Expand Down
10 changes: 3 additions & 7 deletions rcl_yaml_param_parser/src/parser.c
Original file line number Diff line number Diff line change
Expand Up @@ -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]);
Expand Down Expand Up @@ -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) {
Expand All @@ -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);
Expand Down
13 changes: 1 addition & 12 deletions rcl_yaml_param_parser/src/yaml_descriptor.c
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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);
Expand Down
14 changes: 7 additions & 7 deletions rcl_yaml_param_parser/test/test_node_params_descriptors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand All @@ -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
Expand Down
8 changes: 0 additions & 8 deletions rcl_yaml_param_parser/test/test_parse_yaml.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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);
Expand All @@ -739,17 +735,13 @@ 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);
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);

Expand Down
7 changes: 0 additions & 7 deletions rcl_yaml_param_parser/test/test_yaml_descriptor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand All @@ -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);
}

0 comments on commit 1d1eb27

Please sign in to comment.