diff --git a/rcl_yaml_param_parser/CMakeLists.txt b/rcl_yaml_param_parser/CMakeLists.txt
index d11cd33a5..e23104743 100644
--- a/rcl_yaml_param_parser/CMakeLists.txt
+++ b/rcl_yaml_param_parser/CMakeLists.txt
@@ -49,6 +49,7 @@ install(TARGETS ${PROJECT_NAME}
if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_lint_auto REQUIRED)
+ find_package(osrf_testing_tools_cpp REQUIRED)
ament_lint_auto_find_test_dependencies()
# Gtests
@@ -57,6 +58,8 @@ if(BUILD_TESTING)
)
if(TARGET test_parse_yaml)
target_link_libraries(test_parse_yaml ${PROJECT_NAME})
+ target_include_directories(test_parse_yaml
+ PRIVATE ${osrf_testing_tools_cpp_INCLUDE_DIRS})
endif()
endif()
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 9e7d1f2a4..628d16123 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
@@ -25,28 +25,53 @@ extern "C"
{
#endif
-/// \brief Init param structure
+/// \brief Initialize parameter structure
/// \param[in] allocator memory allocator to be used
/// \return a pointer to param structure on success or NULL on failure
RCL_YAML_PARAM_PARSER_PUBLIC
rcl_params_t * rcl_yaml_node_struct_init(
const rcutils_allocator_t allocator);
-/// \brief Free param structure
-/// \param[in] params_st points to the populated paramter struct
+/// \brief Free parameter structure
+/// \param[in] params_st points to the populated parameter struct
RCL_YAML_PARAM_PARSER_PUBLIC
void rcl_yaml_node_struct_fini(
rcl_params_t * params_st);
/// \brief Parse the YAML file, initialize and populate params_st
/// \param[in] file_path is the path to the YAML file
-/// \param[inout] params_st points to the populated paramter struct
+/// \param[inout] params_st points to the populated parameter struct
/// \return true on success and false on failure
RCL_YAML_PARAM_PARSER_PUBLIC
bool rcl_parse_yaml_file(
const char * file_path,
rcl_params_t * params_st);
+/// \brief Parse a parameter value as a YAML string, updating params_st accordingly
+/// \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 will be parsed
+/// \param[in] yaml_value is the parameter value as a YAML string to be parsed
+/// \param[inout] params_st points to the parameter struct
+/// \return true on success and false on failure
+RCL_YAML_PARAM_PARSER_PUBLIC
+bool rcl_parse_yaml_value(
+ const char * node_name,
+ const char * param_name,
+ 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/package.xml b/rcl_yaml_param_parser/package.xml
index 8ed4ef127..c0dacb9b2 100644
--- a/rcl_yaml_param_parser/package.xml
+++ b/rcl_yaml_param_parser/package.xml
@@ -16,6 +16,7 @@
ament_cmake_gtest
ament_lint_common
ament_lint_auto
+ osrf_testing_tools_cpp
ament_cmake
diff --git a/rcl_yaml_param_parser/src/parser.c b/rcl_yaml_param_parser/src/parser.c
index 01bd48bf4..5fdd01a4a 100644
--- a/rcl_yaml_param_parser/src/parser.c
+++ b/rcl_yaml_param_parser/src/parser.c
@@ -12,12 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.
+#include
#include
#include
#include
#include
#include
#include
+#include
#include
#include "rcl_yaml_param_parser/parser.h"
@@ -25,8 +27,8 @@
#include "rcutils/allocator.h"
#include "rcutils/error_handling.h"
-#include "rcutils/types.h"
#include "rcutils/strdup.h"
+#include "rcutils/types.h"
/// NOTE: Will allow a max YAML mapping depth of 5
/// map level 1 : Node name mapping
@@ -126,6 +128,8 @@ static void * get_value(
static rcutils_ret_t parse_value(
const yaml_event_t event,
const bool is_seq,
+ const size_t node_idx,
+ const size_t parameter_idx,
data_types_t * seq_data_type,
rcl_params_t * params_st);
@@ -136,11 +140,17 @@ static rcutils_ret_t parse_key(
namespace_tracker_t * ns_tracker,
rcl_params_t * params_st);
-static rcutils_ret_t parse_events(
+static rcutils_ret_t parse_file_events(
yaml_parser_t * parser,
namespace_tracker_t * ns_tracker,
rcl_params_t * params_st);
+static rcutils_ret_t parse_value_events(
+ yaml_parser_t * parser,
+ const size_t node_idx,
+ const size_t parameter_idx,
+ rcl_params_t * params_st);
+
///
/// Add name to namespace tracker
///
@@ -410,14 +420,14 @@ void rcl_yaml_node_struct_fini(
}
if (NULL != params_st->params) {
- rcl_node_params_t * node_params_st = ¶ms_st->params[node_idx];
+ rcl_node_params_t * node_params_st = &(params_st->params[node_idx]);
for (size_t parameter_idx = 0U; parameter_idx < node_params_st->num_params; parameter_idx++) {
if (
(NULL != node_params_st->parameter_names) &&
(NULL != node_params_st->parameter_values))
{
char * param_name = node_params_st->parameter_names[parameter_idx];
- rcl_variant_t * param_var = &node_params_st->parameter_values[parameter_idx];
+ rcl_variant_t * param_var = &(node_params_st->parameter_values[parameter_idx]);
if (NULL != param_name) {
allocator.deallocate(param_name, allocator.state);
}
@@ -478,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, ¶meter_idx);
+ if (RCUTILS_RET_OK == ret) {
+ param_value = &(params_st->params[node_idx].parameter_values[parameter_idx]);
+ }
+ }
+ return param_value;
+}
+
+
///
/// Dump the param structure
///
@@ -497,14 +597,14 @@ void rcl_yaml_node_struct_print(
}
if (NULL != params_st->params) {
- rcl_node_params_t * node_params_st = ¶ms_st->params[node_idx];
+ rcl_node_params_t * node_params_st = &(params_st->params[node_idx]);
for (size_t parameter_idx = 0U; parameter_idx < node_params_st->num_params; parameter_idx++) {
if (
(NULL != node_params_st->parameter_names) &&
(NULL != node_params_st->parameter_values))
{
char * param_name = node_params_st->parameter_names[parameter_idx];
- rcl_variant_t * param_var = &node_params_st->parameter_values[parameter_idx];
+ rcl_variant_t * param_var = &(node_params_st->parameter_values[parameter_idx]);
if (NULL != param_name) {
printf("%*s", param_col, param_name);
}
@@ -817,6 +917,8 @@ static void * get_value(
static rcutils_ret_t parse_value(
const yaml_event_t event,
const bool is_seq,
+ const size_t node_idx,
+ const size_t parameter_idx,
data_types_t * seq_data_type,
rcl_params_t * params_st)
{
@@ -832,13 +934,6 @@ static rcutils_ret_t parse_value(
return RCUTILS_RET_INVALID_ARGUMENT;
}
- const size_t node_idx = (params_st->num_nodes - 1U);
- if (0U == params_st->params[node_idx].num_params) {
- RCUTILS_SET_ERROR_MSG("No parameter to update");
- return RCUTILS_RET_INVALID_ARGUMENT;
- }
-
- const size_t parameter_idx = ((params_st->params[node_idx].num_params) - 1U);
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;
@@ -1056,11 +1151,10 @@ static rcutils_ret_t parse_key(
}
size_t node_idx = 0U;
- size_t num_nodes = params_st->num_nodes; // New node index
+ size_t num_nodes = params_st->num_nodes;
if (num_nodes > 0U) {
- node_idx = (num_nodes - 1U); // Current node index
+ node_idx = num_nodes - 1U;
}
-
rcutils_ret_t ret = RCUTILS_RET_OK;
switch (*map_level) {
case MAP_UNINIT_LVL:
@@ -1114,8 +1208,8 @@ static rcutils_ret_t parse_key(
break;
case MAP_PARAMS_LVL:
{
- char * parameter_ns;
size_t parameter_idx;
+ char * parameter_ns;
char * param_name;
/// If it is a new map, the previous key is param namespace
@@ -1194,15 +1288,14 @@ static rcutils_ret_t parse_key(
}
///
-/// Get events from the parser and process the events
+/// Get events from parsing a parameter YAML file and process them
///
-static rcutils_ret_t parse_events(
+static rcutils_ret_t parse_file_events(
yaml_parser_t * parser,
namespace_tracker_t * ns_tracker,
rcl_params_t * params_st)
{
int32_t done_parsing = 0;
- yaml_event_t event;
bool is_key = true;
bool is_seq = false;
uint32_t line_num = 0;
@@ -1217,6 +1310,7 @@ static rcutils_ret_t parse_events(
RCUTILS_CHECK_ALLOCATOR_WITH_MSG(
&allocator, "invalid allocator", return RCUTILS_RET_INVALID_ARGUMENT);
+ yaml_event_t event;
rcutils_ret_t ret = RCUTILS_RET_OK;
while (0 == done_parsing) {
if (RCUTILS_RET_OK != ret) {
@@ -1252,7 +1346,21 @@ static rcutils_ret_t parse_events(
ret = RCUTILS_RET_ERROR;
break;
}
- ret = parse_value(event, is_seq, &seq_data_type, params_st);
+ if (0U == params_st->num_nodes) {
+ 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;
+ }
+ const size_t node_idx = (params_st->num_nodes - 1U);
+ if (0U == params_st->params[node_idx].num_params) {
+ 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;
+ }
+ const size_t parameter_idx = (params_st->params[node_idx].num_params - 1U);
+ ret = parse_value(event, is_seq, node_idx, parameter_idx, &seq_data_type, params_st);
if (RCUTILS_RET_OK != ret) {
break;
}
@@ -1348,7 +1456,62 @@ static rcutils_ret_t parse_events(
}
///
-/// TODO (anup.pemmaiah): Support string yaml similar to yaml file
+/// Get events from parsing a parameter YAML value string and process them
+///
+static rcutils_ret_t parse_value_events(
+ yaml_parser_t * parser,
+ const size_t node_idx,
+ const size_t parameter_idx,
+ rcl_params_t * params_st)
+{
+ bool is_seq = false;
+ data_types_t seq_data_type = DATA_TYPE_UNKNOWN;
+ rcutils_ret_t ret = RCUTILS_RET_OK;
+ bool done_parsing = false;
+ 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");
+ ret = RCUTILS_RET_ERROR;
+ break;
+ }
+ switch (event.type) {
+ case YAML_STREAM_END_EVENT:
+ done_parsing = true;
+ break;
+ case YAML_SCALAR_EVENT:
+ ret = parse_value(
+ event, is_seq, node_idx, parameter_idx, &seq_data_type, params_st);
+ break;
+ case YAML_SEQUENCE_START_EVENT:
+ is_seq = true;
+ seq_data_type = DATA_TYPE_UNKNOWN;
+ break;
+ case YAML_SEQUENCE_END_EVENT:
+ is_seq = false;
+ break;
+ case YAML_STREAM_START_EVENT:
+ break;
+ case YAML_DOCUMENT_START_EVENT:
+ break;
+ case YAML_DOCUMENT_END_EVENT:
+ break;
+ case YAML_NO_EVENT:
+ RCUTILS_SET_ERROR_MSG("Received an empty event");
+ ret = RCUTILS_RET_ERROR;
+ break;
+ default:
+ RCUTILS_SET_ERROR_MSG("Unknown YAML event");
+ ret = RCUTILS_RET_ERROR;
+ break;
+ }
+ yaml_event_delete(&event);
+ }
+ return ret;
+}
+
+///
/// TODO (anup.pemmaiah): Support Mutiple yaml files
///
///
@@ -1358,14 +1521,13 @@ bool rcl_parse_yaml_file(
const char * file_path,
rcl_params_t * params_st)
{
+ RCUTILS_CHECK_FOR_NULL_WITH_MSG(
+ file_path, "YAML file path is NULL", return false);
+
if (NULL == params_st) {
- RCUTILS_SAFE_FWRITE_TO_STDERR("Pass a initialized paramter structure");
+ RCUTILS_SAFE_FWRITE_TO_STDERR("Pass an initialized parameter structure");
return false;
}
- rcutils_allocator_t allocator = params_st->allocator;
-
- RCUTILS_CHECK_FOR_NULL_WITH_MSG(
- file_path, "YAML file path is NULL", return false);
yaml_parser_t parser;
int success = yaml_parser_initialize(&parser);
@@ -1385,12 +1547,14 @@ bool rcl_parse_yaml_file(
namespace_tracker_t ns_tracker;
memset(&ns_tracker, 0, sizeof(namespace_tracker_t));
- rcutils_ret_t ret = parse_events(&parser, &ns_tracker, params_st);
+ rcutils_ret_t ret = parse_file_events(&parser, &ns_tracker, params_st);
- yaml_parser_delete(&parser);
fclose(yaml_file);
+ yaml_parser_delete(&parser);
+
if (RCUTILS_RET_OK != ret) {
+ rcutils_allocator_t allocator = params_st->allocator;
if (NULL != ns_tracker.node_ns) {
allocator.deallocate(ns_tracker.node_ns, allocator.state);
}
@@ -1403,3 +1567,50 @@ bool rcl_parse_yaml_file(
return true;
}
+
+///
+/// Parse a YAML string and populate params_st
+///
+bool rcl_parse_yaml_value(
+ const char * node_name,
+ const char * param_name,
+ const char * yaml_value,
+ rcl_params_t * params_st)
+{
+ RCUTILS_CHECK_ARGUMENT_FOR_NULL(node_name, false);
+ RCUTILS_CHECK_ARGUMENT_FOR_NULL(param_name, false);
+ RCUTILS_CHECK_ARGUMENT_FOR_NULL(yaml_value, false);
+
+ if (NULL == params_st) {
+ RCUTILS_SAFE_FWRITE_TO_STDERR("Pass an initialized parameter structure");
+ return false;
+ }
+
+ size_t node_idx = 0U;
+ rcutils_ret_t ret = find_node(node_name, params_st, &node_idx);
+ if (RCUTILS_RET_OK != ret) {
+ return false;
+ }
+
+ size_t parameter_idx = 0U;
+ ret = find_parameter(node_idx, param_name, params_st, ¶meter_idx);
+ if (RCUTILS_RET_OK != ret) {
+ return false;
+ }
+
+ yaml_parser_t parser;
+ int success = yaml_parser_initialize(&parser);
+ if (0 == success) {
+ RCUTILS_SET_ERROR_MSG("Could not initialize the parser");
+ return false;
+ }
+
+ yaml_parser_set_input_string(
+ &parser, (const unsigned char *)yaml_value, strlen(yaml_value));
+
+ ret = parse_value_events(&parser, node_idx, parameter_idx, params_st);
+
+ yaml_parser_delete(&parser);
+
+ return RCUTILS_RET_OK == ret;
+}
diff --git a/rcl_yaml_param_parser/test/test_parse_yaml.cpp b/rcl_yaml_param_parser/test/test_parse_yaml.cpp
index 274e62f79..cee2f388b 100644
--- a/rcl_yaml_param_parser/test/test_parse_yaml.cpp
+++ b/rcl_yaml_param_parser/test/test_parse_yaml.cpp
@@ -15,6 +15,8 @@
#include
#include
+#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)