From a1a833f6cf156e171657637a91eebb98c37631f7 Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Wed, 10 Jul 2019 15:52:24 -0300 Subject: [PATCH] Address peer review comments. - Improve test coverage using new getter API. - Unify function return style and improve readability. Signed-off-by: Michel Hidalgo --- .../include/rcl_yaml_param_parser/parser.h | 12 ++ rcl_yaml_param_parser/src/parser.c | 177 ++++++++++-------- .../test/test_parse_yaml.cpp | 166 +++++++++------- 3 files changed, 201 insertions(+), 154 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 5d11a8721d..628d161237 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 @@ -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 diff --git a/rcl_yaml_param_parser/src/parser.c b/rcl_yaml_param_parser/src/parser.c index 0f48e36d98..2eaba07536 100644 --- a/rcl_yaml_param_parser/src/parser.c +++ b/rcl_yaml_param_parser/src/parser.c @@ -12,6 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include #include @@ -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(¶m_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 = ¶m_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, ¶meter_idx); + if (RCUTILS_RET_OK == ret) { + param_value = ¶ms_st->params[node_idx].parameter_values[parameter_idx]; + } + } + return param_value; +} + + /// /// Dump the param structure /// @@ -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(¶m_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 = ¶m_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 /// diff --git a/rcl_yaml_param_parser/test/test_parse_yaml.cpp b/rcl_yaml_param_parser/test/test_parse_yaml.cpp index 76cef6449c..9c9e9d5f67 100644 --- a/rcl_yaml_param_parser/test/test_parse_yaml.cpp +++ b/rcl_yaml_param_parser/test/test_parse_yaml.cpp @@ -25,24 +25,55 @@ static char cur_dir[1024]; TEST(test_parser, correct_syntax) { rcutils_reset_error(); - EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)); + 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); char * path = rcutils_join_path(test_path, "correct_config.yaml", allocator); - fprintf(stderr, "cur_path: %s\n", path); - EXPECT_TRUE(rcutils_exists(path)); + ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); - EXPECT_FALSE(NULL == params_hdl); + ASSERT_TRUE(NULL != params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl); - EXPECT_TRUE(res) << rcutils_get_error_string().str; + ASSERT_TRUE(res) << rcutils_get_error_string().str; + + rcl_variant_t * param_value = rcl_yaml_node_struct_get("lidar_ns/lidar_1", "ports", params_hdl); + ASSERT_TRUE(NULL != param_value) << rcutils_get_error_string().str; + ASSERT_TRUE(NULL != param_value->integer_array_value); + ASSERT_EQ(3U, param_value->integer_array_value->size); + EXPECT_EQ(2438, param_value->integer_array_value->values[0]); + EXPECT_EQ(2439, param_value->integer_array_value->values[1]); + EXPECT_EQ(2440, param_value->integer_array_value->values[2]); res = rcl_parse_yaml_value("lidar_ns/lidar_1", "ports", "[8080]", params_hdl); EXPECT_TRUE(res) << rcutils_get_error_string().str; + ASSERT_TRUE(NULL != param_value->integer_array_value); + ASSERT_EQ(1U, param_value->integer_array_value->size); + EXPECT_EQ(8080, param_value->integer_array_value->values[0]); + + param_value = rcl_yaml_node_struct_get("lidar_ns/lidar_2", "is_back", params_hdl); + ASSERT_TRUE(NULL != param_value) << rcutils_get_error_string().str; + ASSERT_TRUE(NULL != param_value->bool_value); + EXPECT_FALSE(*param_value->bool_value); res = rcl_parse_yaml_value("lidar_ns/lidar_2", "is_back", "true", params_hdl); EXPECT_TRUE(res) << rcutils_get_error_string().str; + ASSERT_TRUE(NULL != param_value->bool_value); + EXPECT_TRUE(*param_value->bool_value); + + param_value = rcl_yaml_node_struct_get("camera", "cam_spec.angle", params_hdl); + ASSERT_TRUE(NULL != param_value) << rcutils_get_error_string().str; + ASSERT_TRUE(NULL != param_value->double_value); + EXPECT_DOUBLE_EQ(2.34, *param_value->double_value); res = rcl_parse_yaml_value("camera", "cam_spec.angle", "2.2", params_hdl); EXPECT_TRUE(res) << rcutils_get_error_string().str; - res = rcl_parse_yaml_value("intel", "num_cores", "12", params_hdl); + ASSERT_TRUE(NULL != param_value->double_value); + EXPECT_DOUBLE_EQ(2.2, *param_value->double_value); + + param_value = rcl_yaml_node_struct_get("intel", "arch", params_hdl); + ASSERT_TRUE(NULL != param_value) << rcutils_get_error_string().str; + ASSERT_TRUE(NULL != param_value->string_value); + EXPECT_STREQ("x86_64", param_value->string_value); + res = rcl_parse_yaml_value("intel", "arch", "x86", params_hdl); EXPECT_TRUE(res) << rcutils_get_error_string().str; + ASSERT_TRUE(NULL != param_value->string_value); + EXPECT_STREQ("x86", param_value->string_value); rcl_yaml_node_struct_print(params_hdl); rcl_yaml_node_struct_fini(params_hdl); allocator.deallocate(test_path, allocator.state); @@ -51,38 +82,43 @@ TEST(test_parser, correct_syntax) { TEST(test_file_parser, string_array_with_quoted_number) { rcutils_reset_error(); - EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)); + 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); char * path = rcutils_join_path(test_path, "string_array_with_quoted_number.yaml", allocator); - fprintf(stderr, "cur_path: %s\n", path); - EXPECT_TRUE(rcutils_exists(path)); + ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); - EXPECT_TRUE(params_hdl); - if (params_hdl) { - bool res = rcl_parse_yaml_file(path, params_hdl); - fprintf(stderr, "%s\n", rcutils_get_error_string().str); - EXPECT_TRUE(res); - rcl_yaml_node_struct_print(params_hdl); - rcl_yaml_node_struct_fini(params_hdl); - } + ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str; + bool res = rcl_parse_yaml_file(path, params_hdl); + ASSERT_TRUE(res) << rcutils_get_error_string().str; + rcl_variant_t * param_value = rcl_yaml_node_struct_get( + "initial_params_node", "sa2", params_hdl); + ASSERT_TRUE(NULL != param_value) << rcutils_get_error_string().str; + ASSERT_TRUE(NULL != param_value->string_array_value); + ASSERT_EQ(2U, param_value->string_array_value->size); + EXPECT_STREQ("and", param_value->string_array_value->data[0]); + EXPECT_STREQ("7", param_value->string_array_value->data[1]); + res = rcl_parse_yaml_value("initial_params_node", "category", "'0'", params_hdl); + EXPECT_TRUE(res) << rcutils_get_error_string().str; + param_value = rcl_yaml_node_struct_get("initial_params_node", "category", params_hdl); + ASSERT_TRUE(NULL != param_value) << rcutils_get_error_string().str; + ASSERT_TRUE(NULL != param_value->string_value); + EXPECT_STREQ("0", param_value->string_value); + rcl_yaml_node_struct_print(params_hdl); + rcl_yaml_node_struct_fini(params_hdl); allocator.deallocate(test_path, allocator.state); allocator.deallocate(path, allocator.state); } TEST(test_file_parser, multi_ns_correct_syntax) { rcutils_reset_error(); - EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)); + 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); char * path = rcutils_join_path(test_path, "multi_ns_correct.yaml", allocator); - fprintf(stderr, "cur_path: %s\n", path); - EXPECT_TRUE(rcutils_exists(path)); + ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); - EXPECT_FALSE(NULL == params_hdl); - bool res = rcl_parse_yaml_file(path, params_hdl); - fprintf(stderr, "%s\n", rcutils_get_error_string().str); - EXPECT_TRUE(res); + ASSERT_TRUE(NULL != params_hdl); rcl_yaml_node_struct_print(params_hdl); rcl_yaml_node_struct_fini(params_hdl); allocator.deallocate(test_path, allocator.state); @@ -91,24 +127,20 @@ TEST(test_file_parser, multi_ns_correct_syntax) { TEST(test_file_parser, root_ns) { rcutils_reset_error(); - EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)); + 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); char * path = rcutils_join_path(test_path, "root_ns.yaml", allocator); - fprintf(stderr, "cur_path: %s\n", path); - EXPECT_TRUE(rcutils_exists(path)); + ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); - EXPECT_FALSE(NULL == params_hdl); + ASSERT_TRUE(NULL != params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl); - fprintf(stderr, "%s\n", rcutils_get_error_string().str); - EXPECT_TRUE(res); + EXPECT_TRUE(res) << rcutils_get_error_string().str; rcl_yaml_node_struct_print(params_hdl); - // Check that there is only one forward slash in the node's FQN. // (Regression test for https://github.com/ros2/rcl/pull/299). - ASSERT_EQ(1u, params_hdl->num_nodes); - ASSERT_STREQ("/my_node", params_hdl->node_names[0]); - + EXPECT_EQ(1u, params_hdl->num_nodes); + EXPECT_STREQ("/my_node", params_hdl->node_names[0]); rcl_yaml_node_struct_fini(params_hdl); allocator.deallocate(test_path, allocator.state); allocator.deallocate(path, allocator.state); @@ -116,14 +148,13 @@ TEST(test_file_parser, root_ns) { TEST(test_file_parser, seq_map1) { rcutils_reset_error(); - EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)); + 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); char * path = rcutils_join_path(test_path, "seq_map1.yaml", allocator); - fprintf(stderr, "cur_path: %s\n", path); - EXPECT_TRUE(rcutils_exists(path)); + ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); - EXPECT_FALSE(NULL == params_hdl); + ASSERT_TRUE(NULL != params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl); fprintf(stderr, "%s\n", rcutils_get_error_string().str); EXPECT_FALSE(res); @@ -133,14 +164,13 @@ TEST(test_file_parser, seq_map1) { TEST(test_file_parser, seq_map2) { rcutils_reset_error(); - EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)); + 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); char * path = rcutils_join_path(test_path, "seq_map2.yaml", allocator); - fprintf(stderr, "cur_path: %s\n", path); - EXPECT_TRUE(rcutils_exists(path)); + ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); - EXPECT_FALSE(NULL == params_hdl); + ASSERT_TRUE(NULL != params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl); fprintf(stderr, "%s\n", rcutils_get_error_string().str); EXPECT_FALSE(res); @@ -150,14 +180,13 @@ TEST(test_file_parser, seq_map2) { TEST(test_file_parser, params_with_no_node) { rcutils_reset_error(); - EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)); + 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); char * path = rcutils_join_path(test_path, "params_with_no_node.yaml", allocator); - fprintf(stderr, "cur_path: %s\n", path); - EXPECT_TRUE(rcutils_exists(path)); + ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); - EXPECT_FALSE(NULL == params_hdl); + ASSERT_TRUE(NULL != params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl); fprintf(stderr, "%s\n", rcutils_get_error_string().str); EXPECT_FALSE(res); @@ -167,14 +196,13 @@ TEST(test_file_parser, params_with_no_node) { TEST(test_file_parser, no_alias_support) { rcutils_reset_error(); - EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)); + 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); char * path = rcutils_join_path(test_path, "no_alias_support.yaml", allocator); - fprintf(stderr, "cur_path: %s\n", path); - EXPECT_TRUE(rcutils_exists(path)); + ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); - EXPECT_FALSE(NULL == params_hdl); + ASSERT_TRUE(NULL != params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl); fprintf(stderr, "%s\n", rcutils_get_error_string().str); EXPECT_FALSE(res); @@ -184,14 +212,13 @@ TEST(test_file_parser, no_alias_support) { TEST(test_file_parser, max_string_sz) { rcutils_reset_error(); - EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)); + 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); char * path = rcutils_join_path(test_path, "max_string_sz.yaml", allocator); - fprintf(stderr, "cur_path: %s\n", path); - EXPECT_TRUE(rcutils_exists(path)); + ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); - EXPECT_FALSE(NULL == params_hdl); + ASSERT_TRUE(NULL != params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl); fprintf(stderr, "%s\n", rcutils_get_error_string().str); EXPECT_FALSE(res); @@ -201,17 +228,15 @@ TEST(test_file_parser, max_string_sz) { TEST(test_file_parser, empty_string) { rcutils_reset_error(); - EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)); + 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); char * path = rcutils_join_path(test_path, "empty_string.yaml", allocator); - fprintf(stderr, "cur_path: %s\n", path); - EXPECT_TRUE(rcutils_exists(path)); + ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); - EXPECT_FALSE(NULL == params_hdl); + ASSERT_TRUE(NULL != params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl); - fprintf(stderr, "%s\n", rcutils_get_error_string().str); - EXPECT_TRUE(res); + EXPECT_TRUE(res) << rcutils_get_error_string().str; rcl_yaml_node_struct_print(params_hdl); rcl_yaml_node_struct_fini(params_hdl); allocator.deallocate(test_path, allocator.state); @@ -220,14 +245,13 @@ TEST(test_file_parser, empty_string) { TEST(test_file_parser, no_value1) { rcutils_reset_error(); - EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)); + 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); char * path = rcutils_join_path(test_path, "no_value1.yaml", allocator); - fprintf(stderr, "cur_path: %s\n", path); - EXPECT_TRUE(rcutils_exists(path)); + ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); - EXPECT_FALSE(NULL == params_hdl); + ASSERT_TRUE(NULL != params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl); fprintf(stderr, "%s\n", rcutils_get_error_string().str); EXPECT_FALSE(res); @@ -237,14 +261,13 @@ TEST(test_file_parser, no_value1) { TEST(test_file_parser, indented_ns) { rcutils_reset_error(); - EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)); + 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); char * path = rcutils_join_path(test_path, "indented_name_space.yaml", allocator); - fprintf(stderr, "cur_path: %s\n", path); - EXPECT_TRUE(rcutils_exists(path)); + ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); - EXPECT_FALSE(NULL == params_hdl); + ASSERT_TRUE(NULL != params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl); fprintf(stderr, "%s\n", rcutils_get_error_string().str); EXPECT_FALSE(res); @@ -255,14 +278,13 @@ TEST(test_file_parser, indented_ns) { // Regression test for https://github.com/ros2/rcl/issues/419 TEST(test_file_parser, maximum_number_parameters) { rcutils_reset_error(); - EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024)); + 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); char * path = rcutils_join_path(test_path, "max_num_params.yaml", allocator); - fprintf(stderr, "cur_path: %s\n", path); - EXPECT_TRUE(rcutils_exists(path)); + ASSERT_TRUE(rcutils_exists(path)) << "No test YAML file found at " << path; rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator); - EXPECT_FALSE(NULL == params_hdl); + ASSERT_TRUE(NULL != params_hdl); bool res = rcl_parse_yaml_file(path, params_hdl); fprintf(stderr, "%s\n", rcutils_get_error_string().str); EXPECT_FALSE(res);