Skip to content

Commit

Permalink
Address peer review comments.
Browse files Browse the repository at this point in the history
- Improve test coverage using new getter API.
- Unify function return style and improve readability.

Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
  • Loading branch information
hidmic committed Jul 10, 2019
1 parent d39e14e commit a1a833f
Show file tree
Hide file tree
Showing 3 changed files with 201 additions and 154 deletions.
12 changes: 12 additions & 0 deletions rcl_yaml_param_parser/include/rcl_yaml_param_parser/parser.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,18 @@ bool rcl_parse_yaml_value(
const char * yaml_value,
rcl_params_t * params_st);

/// \brief Get the variant value for a given parameter, zero initializing it in the
/// process if not present already
/// \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 variant value on success and NULL on failure
RCL_YAML_PARAM_PARSER_PUBLIC
rcl_variant_t * rcl_yaml_node_struct_get(
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
Expand Down
177 changes: 95 additions & 82 deletions rcl_yaml_param_parser/src/parser.c
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <assert.h>
#include <errno.h>
#include <inttypes.h>
#include <stdbool.h>
Expand Down Expand Up @@ -487,6 +488,96 @@ void rcl_yaml_node_struct_fini(
allocator.deallocate(params_st, allocator.state);
}


///
/// Find node entry index in parameters' structure
///
static rcutils_ret_t find_node(
const char * node_name,
rcl_params_t * param_st,
size_t * node_idx)
{
assert(NULL != node_name);
assert(NULL != param_st);
assert(NULL != node_idx);

for (*node_idx = 0U; *node_idx < param_st->num_nodes; (*node_idx)++) {
if (0 == strcmp(param_st->node_names[*node_idx], node_name)) {
// Node found.
return RCUTILS_RET_OK;
}
}
// Node not found, add it.
rcutils_allocator_t allocator = param_st->allocator;
param_st->node_names[*node_idx] = rcutils_strdup(node_name, allocator);
if (NULL == param_st->node_names[*node_idx]) {
return RCUTILS_RET_BAD_ALLOC;
}
rcutils_ret_t ret = node_params_init(&param_st->params[*node_idx], allocator);
if (RCUTILS_RET_OK != ret) {
allocator.deallocate(param_st->node_names[*node_idx], allocator.state);
return ret;
}
param_st->num_nodes++;
return RCUTILS_RET_OK;
}

///
/// Find paremeter entry index in node parameters' structure
///
static rcutils_ret_t find_parameter(
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_t * node_param_st = &param_st->params[node_idx];
for (*parameter_idx = 0U; *parameter_idx < node_param_st->num_params; (*parameter_idx)++) {
if (0 == strcmp(node_param_st->parameter_names[*parameter_idx], parameter_name)) {
// Parameter found.
return RCUTILS_RET_OK;
}
}
// Parameter not found, add it.
rcutils_allocator_t allocator = param_st->allocator;
node_param_st->parameter_names[*parameter_idx] = rcutils_strdup(parameter_name, allocator);
if (NULL == node_param_st->parameter_names[*parameter_idx]) {
return RCUTILS_RET_BAD_ALLOC;
}
node_param_st->num_params++;
return RCUTILS_RET_OK;
}

rcl_variant_t * rcl_yaml_node_struct_get(
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_variant_t * param_value = 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_parameter(node_idx, param_name, params_st, &parameter_idx);
if (RCUTILS_RET_OK == ret) {
param_value = &params_st->params[node_idx].parameter_values[parameter_idx];
}
}
return param_value;
}


///
/// Dump the param structure
///
Expand Down Expand Up @@ -1377,127 +1468,49 @@ static rcutils_ret_t parse_value_events(
data_types_t seq_data_type = DATA_TYPE_UNKNOWN;
rcutils_ret_t ret = RCUTILS_RET_OK;
bool done_parsing = false;
while (!done_parsing) {
while (RCUTILS_RET_OK == ret && !done_parsing) {
yaml_event_t event;
int success = yaml_parser_parse(parser, &event);
if (0 == success) {
RCUTILS_SET_ERROR_MSG("Error parsing an event");
return RCUTILS_RET_ERROR;
ret = RCUTILS_RET_ERROR;
break;
}
switch (event.type) {
case YAML_STREAM_END_EVENT:
done_parsing = true;
yaml_event_delete(&event);
break;
case YAML_SCALAR_EVENT:
ret = parse_value(
event, is_seq, node_idx, parameter_idx, &seq_data_type, params_st);
if (RCUTILS_RET_OK != ret) {
yaml_event_delete(&event);
return ret;
}
yaml_event_delete(&event);
break;
case YAML_SEQUENCE_START_EVENT:
is_seq = true;
seq_data_type = DATA_TYPE_UNKNOWN;
yaml_event_delete(&event);
break;
case YAML_SEQUENCE_END_EVENT:
is_seq = false;
yaml_event_delete(&event);
break;
case YAML_STREAM_START_EVENT:
yaml_event_delete(&event);
break;
case YAML_DOCUMENT_START_EVENT:
yaml_event_delete(&event);
break;
case YAML_DOCUMENT_END_EVENT:
yaml_event_delete(&event);
break;
case YAML_NO_EVENT:
RCUTILS_SET_ERROR_MSG("Received an empty event");
ret = RCUTILS_RET_ERROR;
yaml_event_delete(&event);
break;
default:
RCUTILS_SET_ERROR_MSG("Unknown YAML event");
ret = RCUTILS_RET_ERROR;
yaml_event_delete(&event);
break;
}
yaml_event_delete(&event);
}
return ret;
}

///
/// Find node entry index in parameters' structure
///
static rcutils_ret_t find_node(
const char * node_name,
rcl_params_t * param_st,
size_t * node_idx)
{
RCUTILS_CHECK_ARGUMENT_FOR_NULL(node_name, RCUTILS_RET_INVALID_ARGUMENT);
RCUTILS_CHECK_ARGUMENT_FOR_NULL(param_st, RCUTILS_RET_INVALID_ARGUMENT);
RCUTILS_CHECK_ARGUMENT_FOR_NULL(node_idx, RCUTILS_RET_INVALID_ARGUMENT);

bool found = false;
for (*node_idx = 0U; *node_idx < param_st->num_nodes; (*node_idx)++) {
if (0 == strcmp(param_st->node_names[*node_idx], node_name)) {
found = true;
break;
}
}
if (!found) {
rcutils_allocator_t allocator = param_st->allocator;
param_st->node_names[*node_idx] = rcutils_strdup(node_name, allocator);
if (NULL == param_st->node_names[*node_idx]) {
return RCUTILS_RET_BAD_ALLOC;
}
rcutils_ret_t ret = node_params_init(&param_st->params[*node_idx], allocator);
if (RCUTILS_RET_OK != ret) {
allocator.deallocate(param_st->node_names[*node_idx], allocator.state);
return ret;
}
param_st->num_nodes++;
}
return RCUTILS_RET_OK;
}

///
/// Find paremeter entry index in node parameters' structure
///
static rcutils_ret_t find_parameter(
const size_t node_idx,
const char * parameter_name,
rcl_params_t * param_st,
size_t * parameter_idx)
{
RCUTILS_CHECK_ARGUMENT_FOR_NULL(parameter_name, RCUTILS_RET_INVALID_ARGUMENT);
RCUTILS_CHECK_ARGUMENT_FOR_NULL(param_st, RCUTILS_RET_INVALID_ARGUMENT);
RCUTILS_CHECK_ARGUMENT_FOR_NULL(parameter_idx, RCUTILS_RET_INVALID_ARGUMENT);

bool found = false;
rcl_node_params_t * node_param_st = &param_st->params[node_idx];
for (*parameter_idx = 0U; *parameter_idx < node_param_st->num_params; (*parameter_idx)++) {
if (0 == strcmp(node_param_st->parameter_names[*parameter_idx], parameter_name)) {
found = true;
break;
}
}
if (!found) {
rcutils_allocator_t allocator = param_st->allocator;
node_param_st->parameter_names[*parameter_idx] = rcutils_strdup(parameter_name, allocator);
if (NULL == node_param_st->parameter_names[*parameter_idx]) {
return RCUTILS_RET_BAD_ALLOC;
}
node_param_st->num_params++;
}
return RCUTILS_RET_OK;
}

///
/// TODO (anup.pemmaiah): Support Mutiple yaml files
///
Expand Down
Loading

0 comments on commit a1a833f

Please sign in to comment.