[YAML Parser] Support parameter value parsing (#471)

* Support parameter YAML string value parsing.

Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>

* Address peer review comments.

- Improve test coverage using new getter API.
- Unify function return style and improve readability.

Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>

* Clean up allocations in rcl_yaml_param_parser package tests.

Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
This commit is contained in:
Michel Hidalgo 2019-07-12 15:07:42 -03:00 committed by GitHub
parent f9ceef5c86
commit 5fde9c0c0e
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
5 changed files with 494 additions and 135 deletions

View file

@ -15,6 +15,8 @@
#include <stdio.h>
#include <gtest/gtest.h>
#include "osrf_testing_tools_cpp/scope_exit.hpp"
#include "rcl_yaml_param_parser/parser.h"
#include "rcutils/allocator.h"
@ -23,244 +25,361 @@
static char cur_dir[1024];
TEST(test_file_parser, correct_syntax) {
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);
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_config.yaml", allocator);
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(path));
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);
EXPECT_FALSE(NULL == params_hdl);
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);
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_TRUE(res);
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;
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);
allocator.deallocate(path, allocator.state);
}
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);
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, "string_array_with_quoted_number.yaml", allocator);
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(path));
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);
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);
ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({
rcl_yaml_node_struct_fini(params_hdl);
}
allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state);
});
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);
}
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);
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, "multi_ns_correct.yaml", allocator);
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(path));
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);
EXPECT_FALSE(NULL == params_hdl);
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);
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);
allocator.deallocate(path, allocator.state);
}
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);
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, "root_ns.yaml", allocator);
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(path));
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);
EXPECT_FALSE(NULL == params_hdl);
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);
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]);
rcl_yaml_node_struct_fini(params_hdl);
allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state);
EXPECT_EQ(1u, params_hdl->num_nodes);
EXPECT_STREQ("/my_node", params_hdl->node_names[0]);
}
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);
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, "seq_map1.yaml", allocator);
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(path));
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);
EXPECT_FALSE(NULL == params_hdl);
ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str;
bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_FALSE(res);
allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state);
}
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);
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, "seq_map2.yaml", allocator);
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(path));
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);
EXPECT_FALSE(NULL == params_hdl);
ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str;
bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_FALSE(res);
allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state);
}
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);
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, "params_with_no_node.yaml", allocator);
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(path));
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);
EXPECT_FALSE(NULL == params_hdl);
ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str;
bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_FALSE(res);
allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state);
}
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);
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_alias_support.yaml", allocator);
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(path));
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);
EXPECT_FALSE(NULL == params_hdl);
ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str;
bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_FALSE(res);
allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state);
}
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);
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, "max_string_sz.yaml", allocator);
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(path));
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);
EXPECT_FALSE(NULL == params_hdl);
ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str;
bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_FALSE(res);
allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state);
}
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);
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, "empty_string.yaml", allocator);
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(path));
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);
EXPECT_FALSE(NULL == params_hdl);
ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str;
bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_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);
allocator.deallocate(path, allocator.state);
}
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);
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_value1.yaml", allocator);
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(path));
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);
EXPECT_FALSE(NULL == params_hdl);
ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str;
bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_FALSE(res);
allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state);
}
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);
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, "indented_name_space.yaml", allocator);
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(path));
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);
EXPECT_FALSE(NULL == params_hdl);
ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str;
bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_FALSE(res);
allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state);
}
// 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);
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, "max_num_params.yaml", allocator);
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(path));
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);
EXPECT_FALSE(NULL == params_hdl);
ASSERT_TRUE(NULL != params_hdl) << rcutils_get_error_string().str;
bool res = rcl_parse_yaml_file(path, params_hdl);
fprintf(stderr, "%s\n", rcutils_get_error_string().str);
EXPECT_FALSE(res);
allocator.deallocate(test_path, allocator.state);
allocator.deallocate(path, allocator.state);
}
int32_t main(int32_t argc, char ** argv)