YAML parameter parser (#235)

* Implement a basic YAML based parameter parser for ros2 nodes

* Add README file

* Fix the issues after moving from rcutils_yaml_param_parser to rcl_yaml_param_parser

  - rename folders from rcutils_yaml_param_parser to rcl_yaml_param_parser
  - rename project, header guards and include statements from rcutils_yaml_param_parser to rcl_yaml_param_parser
  - move type declaration in separat file and namespace new structures
  - Fix the code review comments from Mikael

* Few minor changes

   - Changed "params" string to "ros__parameters"
   - Add -Wall, -Wextra and -Wpedantic falgs
   - Fix the compile warning with the new flags

* Fix the changes made in the design of C structure

  - Remove the node_namespaces entry in rcl_params_t
  - Change the type of num_nodes and num_params to size_t

* depend on libyaml_vendor (#236)

* Fix cmake setting standard(C and C++) and add byte_array in C struct

*   Remove C11 so that it defaults to C99

* [rcl_yaml_param_parser] fix export symbols (#237)

* add visibility macros

* remove unused macro

* Support for multi level node and parameter name spaces

* Additional fixes and cleanups

  - Support for string namespace seperator
  - Provide parameter structure init function API
  - name cleanups

* off by 1

* Call yaml_parser_delete()

* fclose(yaml_file)

* free() allocated paths

* Call yaml_event_delete()

* completely deallcoate string array

* Few cleanup changes

  - Add install command into CMakelists.txt
  - Replace one of the zero_allocate with reallocate
  - Pass allocator state
  - Fix int32_t -> rcl_ret_t return value

* Don't include unistd.h

* Use size_t for array indices

* Just pass the allocator in the init function
This commit is contained in:
anup-pem 2018-05-29 09:07:02 -07:00 committed by Mikael Arguedas
parent e8491ab8ab
commit 5edf27b032
17 changed files with 2087 additions and 0 deletions

View file

@ -0,0 +1,62 @@
cmake_minimum_required(VERSION 3.5)
project(rcl_yaml_param_parser)
find_package(ament_cmake_ros REQUIRED)
find_package(rcutils REQUIRED)
find_package(rcl REQUIRED)
find_package(libyaml_vendor REQUIRED)
find_package(yaml REQUIRED)
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCC OR CMAKE_C_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
include_directories(include ${yaml_INCLUDE_DIRS} ${rcutils_INCLUDE_DIRS} ${rcl_INCLUDE_DIRS})
set(rcl_yaml_parser_sources
src/parser.c
)
add_library(
${PROJECT_NAME}
${rcl_yaml_parser_sources})
ament_target_dependencies(${PROJECT_NAME} "yaml" "rcutils" "rcl")
# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(${PROJECT_NAME} PRIVATE "RCL_YAML_PARAM_PARSER_BUILDING_DLL")
install(TARGETS ${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)
if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
# Gtests
ament_add_gtest(test_parse_yaml
test/test_parse_yaml.cpp
)
if(TARGET test_parse_yaml)
target_link_libraries(test_parse_yaml ${PROJECT_NAME})
endif()
endif()
ament_export_dependencies(ament_cmake)
ament_export_include_directories(include)
install(
DIRECTORY include/
DESTINATION include
)
ament_export_libraries(${PROJECT_NAME})
ament_package()

View file

@ -0,0 +1,27 @@
**ROS2 rcl YAML paramter parser**
Parse a YAML parameter file and populate the C data structure
The data structure params_st will then be used during node initialization
YAML parameter file should follow the yaml syntax shown below
NOTE: It only supports canonical int and float types
```
<node_namespace_string>: # optional
<node1_name>:
params:
<field_name>: <field_value>
<parameter_namespace_string>: # optional
<field1_name>: <field1_value>
<field2_name>: <field2_value>
<node2_name>:
params:
<field_name>: <field_value>
<parameter_namespace_string>: # optional
<field1_name>: <field1_value>
<field2_name>: <field2_value>
```
This package depends on C libyaml

View file

@ -0,0 +1,60 @@
// Copyright 2018 Apex.AI, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCL_YAML_PARAM_PARSER__PARSER_H_
#define RCL_YAML_PARAM_PARSER__PARSER_H_
#include <stdlib.h>
#include "rcl_yaml_param_parser/types.h"
#include "rcl_yaml_param_parser/visibility_control.h"
#ifdef __cplusplus
extern "C"
{
#endif
/// \brief Init param 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
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[in/out] params_st points to the populated paramter 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 Print the parameter structure to stdout
/// \param[in] params_st points to the populated parameter struct
RCL_YAML_PARAM_PARSER_PUBLIC
void rcl_yaml_node_struct_print(
const rcl_params_t * const params_st);
#ifdef __cplusplus
}
#endif
#endif // RCL_YAML_PARAM_PARSER__PARSER_H_

View file

@ -0,0 +1,87 @@
// Copyright 2018 Apex.AI, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCL_YAML_PARAM_PARSER__TYPES_H_
#define RCL_YAML_PARAM_PARSER__TYPES_H_
#include "rcl/allocator.h"
#include "rcutils/types/string_array.h"
/// \typedef rcl_bool_array_t
/// \brief Array of bool values
typedef struct rcl_bool_array_s
{
bool * values;
size_t size;
} rcl_bool_array_t;
/// \typedef rcl_int64_array_t
/// \brief Array of int64_t values
typedef struct rcl_int64_array_s
{
int64_t * values;
size_t size;
} rcl_int64_array_t;
/// \typedef rcl_double_array_t
/// \brief Array of double values
typedef struct rcl_double_array_s
{
double * values;
size_t size;
} rcl_double_array_t;
/// \typedef rcl_byte_array_t
/// \brief Array of byte values
typedef struct rcl_byte_array_s
{
uint8_t * values;
size_t size;
} rcl_byte_array_t;
/// \typedef rcl_variant_t
/// \brief variant_t stores the value of a parameter
/// Only one pointer in this struct will store the value
typedef struct rcl_variant_s
{
bool * bool_value; ///< If bool, gets stored here
int64_t * integer_value; ///< If integer, gets stored here
double * double_value; ///< If double, gets stored here
char * string_value; ///< If string, gets stored here
rcl_byte_array_t * byte_array_value; ///< If array of bytes
rcl_bool_array_t * bool_array_value; ///< If array of bool's
rcl_int64_array_t * integer_array_value; ///< If array of integers
rcl_double_array_t * double_array_value; ///< If array of doubles
rcutils_string_array_t * string_array_value; ///< If array of strings
} rcl_variant_t;
/// \typedef rcl_node_params_t
/// \brief node_params_t stores all the parameters(key:value) of a single node
typedef struct rcl_node_params_s
{
char ** parameter_names; ///< Array of parameter names (keys)
rcl_variant_t * parameter_values; ///< Array of coressponding parameter values
size_t num_params; ///< Number of parameters in the node
} rcl_node_params_t;
/// \typedef rcl_params_t
/// \brief params_t stores all the parameters of all nodes of a process
typedef struct rcl_params_s
{
char ** node_names; ///< List of names of the node
rcl_node_params_t * params; ///< Array of parameters
size_t num_nodes; ///< Number of nodes
rcl_allocator_t allocator; ///< Allocator used
} rcl_params_t;
#endif // RCL_YAML_PARAM_PARSER__TYPES_H_

View file

@ -0,0 +1,58 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCL_YAML_PARAM_PARSER__VISIBILITY_CONTROL_H_
#define RCL_YAML_PARAM_PARSER__VISIBILITY_CONTROL_H_
#ifdef __cplusplus
extern "C"
{
#endif
// This logic was borrowed (then namespaced) from the examples on the gcc wiki:
// https://gcc.gnu.org/wiki/Visibility
#if defined _WIN32 || defined __CYGWIN__
#ifdef __GNUC__
#define RCL_YAML_PARAM_PARSER_EXPORT __attribute__ ((dllexport))
#define RCL_YAML_PARAM_PARSER_IMPORT __attribute__ ((dllimport))
#else
#define RCL_YAML_PARAM_PARSER_EXPORT __declspec(dllexport)
#define RCL_YAML_PARAM_PARSER_IMPORT __declspec(dllimport)
#endif
#ifdef RCL_YAML_PARAM_PARSER_BUILDING_DLL
#define RCL_YAML_PARAM_PARSER_PUBLIC RCL_YAML_PARAM_PARSER_EXPORT
#else
#define RCL_YAML_PARAM_PARSER_PUBLIC RCL_YAML_PARAM_PARSER_IMPORT
#endif
#define RCL_YAML_PARAM_PARSER_PUBLIC_TYPE RCL_YAML_PARAM_PARSER_PUBLIC
#define RCL_YAML_PARAM_PARSER_LOCAL
#else
#define RCL_YAML_PARAM_PARSER_EXPORT __attribute__ ((visibility("default")))
#define RCL_YAML_PARAM_PARSER_IMPORT
#if __GNUC__ >= 4
#define RCL_YAML_PARAM_PARSER_PUBLIC __attribute__ ((visibility("default")))
#define RCL_YAML_PARAM_PARSER_LOCAL __attribute__ ((visibility("hidden")))
#else
#define RCL_YAML_PARAM_PARSER_PUBLIC
#define RCL_YAML_PARAM_PARSER_LOCAL
#endif
#define RCL_YAML_PARAM_PARSER_PUBLIC_TYPE
#endif
#ifdef __cplusplus
}
#endif
#endif // RCL_YAML_PARAM_PARSER__VISIBILITY_CONTROL_H_

View file

@ -0,0 +1,25 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>rcl_yaml_param_parser</name>
<version>0.1.0</version>
<description>Package containing various utility types and functions for C</description>
<maintainer email="anup.pemmaiah@apex.ai">Anup Pemmaiah</maintainer>
<license>Apache License 2.0</license>
<buildtool_depend>ament_cmake_ros</buildtool_depend>
<depend>libyaml_vendor</depend>
<depend>yaml</depend>
<build_depend>rcutils</build_depend>
<build_depend>rcl</build_depend>
<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>launch_testing</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,51 @@
# config/test_yaml
---
lidar_ns:
lidar_1:
ros__parameters:
id: 10
name: front_lidar
ports: [2438, 2439, 2440]
driver1:
dx: 4.56
dy: 2.30
fr_sensor_specs: [12, 3, 0, 7]
bk_sensor_specs: [12.1, -2.3, 5.2, 9.0]
is_front: true
driver2:
dx: 1.23
dy: 0.45
lidar_2:
ros__parameters:
id: 11
name: back_lidar
dy1: 0.003
is_back: false
driver:
dz: 7.89
camera:
ros__parameters:
name: camera1
loc: front
cam_spec:
angle: 2.34
supported_brands: ["Bosch", "Novatek", "Mobius"]
new_camera_ns:
new_camera1:
ros__parameters:
is_cam_on: [true, true, false, true, false, false]
brand: Bosch
new_camera2:
ros__parameters:
camera_dr:
dr_name: default
brand: Mobius
drive_px:
ros__parameters:
num_cores: 6
arch: ARM
intel:
ros__parameters:
num_cores: 8
arch: x86_64

View file

@ -0,0 +1,17 @@
# config/test_yaml
---
lidar_ns:
lidar_1:
ros__parameters:
id: 10
name: front_lidar
ports: [2438, 2439, 2440]
driver1:
dx: 4.56
dy: 2.30
fr_sensor_specs: [12, 3, 0, 7]
bk_sensor_specs: [12.1, -2.3, 5.2, 9.0]
is_front: true
driver2:
dx: 1.23
dy: 0.45

View file

@ -0,0 +1,9 @@
# config/test_yaml
---
lidar_ns:
lidar_1:
ros__parameters:
id: 10
name: "A very long name that will not be supported by the yaml parser. The max supported string size is 128
characters. Anything over the max size will be rejected"

View file

@ -0,0 +1,64 @@
# config/test_yaml
---
lidar_ns:
lidar_1:
lidar11:
lidar111:
ros__parameters:
id: 10
name: front_lidar
ports: [2438, 2439, 2440]
driver1:
driver11:
driver111:
dx: 4.56
dy: 2.30
fr_sensor_specs: [12, 3, 0, 7]
bk_sensor_specs: [12.1, -2.3, 5.2, 9.0]
is_front: true
driver2:
driver21:
dx: 1.23
dy: 0.45
lidar_2:
lidar21:
ros__parameters:
driver1:
driver11:
id: 11
name: back_lidar
back_lidar1:
back_lidar12:
pos: center
ratio: 2:1
dy1: 0.003
is_back: false
tmp_driver:
dz: 7.89
camera:
camera1:
ros__parameters:
name: camera1
loc: front
cam_spec:
angle: 2.34
supported_brands: ["Bosch", "Novatek", "Mobius"]
new_camera_ns:
new_camera1:
ros__parameters:
is_cam_on: [true, true, false, true, false, false]
brand: Bosch
new_camera2:
ros__parameters:
camera_dr:
dr_name: default
brand: Mobius
drive_px:
ros__parameters:
num_cores: 6
arch: ARM
intel:
ros__parameters:
num_cores: 8
arch: x86_64

View file

@ -0,0 +1,9 @@
# config/test_yaml
---
lidar_ns:
lidar_1:
ros__parameters:
id: 10
name: &FL "front_lidar"
spec: *FL

View file

@ -0,0 +1,8 @@
# config/test_yaml
---
lidar_ns:
lidar_1:
ros__parameters:
id:
name: "front lidar"

View file

@ -0,0 +1,18 @@
# config/test_yaml
---
node1:
ros__parameters:
name: test
ros__parameters:
id: 10
name: front_lidar
ports: [2438, 2439, 2440]
driver1:
dx: 4.56
dy: 2.30
fr_sensor_specs: [12, 3, 0, 7]
bk_sensor_specs: [12.1, -2.3, 5.2, 9.0]
is_front: true
driver2:
dx: 1.23
dy: 0.45

View file

@ -0,0 +1,14 @@
# config/test_yaml
---
lidar_ns:
lidar_1:
ros__parameters:
- driver: front_driver
dx: 4.56
dy: 2.30
sensor_specs: [12, 3, 0, 7]
- driver: back_driver
dx: 1.23
dy: 0.45
sensor_specs: [12.1, -2.3, 5.2, 9.0]

View file

@ -0,0 +1,16 @@
# config/test_yaml
---
lidar_ns:
lidar_1:
ros__parameters:
id: 10
name: front_lidar
- driver: front_driver
dx: 4.56
dy: 2.30
sensor_specs: [12, 3, 0, 7]
- driver: back_driver
dx: 1.23
dy: 0.45
sensor_specs: [12.1, -2.3, 5.2, 9.0]

View file

@ -0,0 +1,178 @@
// Copyright 2018 Apex.AI, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <stdio.h>
#include <gtest/gtest.h>
#include "rcl_yaml_param_parser/parser.h"
#include "rcutils/error_handling.h"
#include "rcutils/filesystem.h"
static char cur_dir[1024];
rcutils_allocator_t allocator = rcutils_get_default_allocator();
TEST(test_file_parser, correct_syntax) {
rcutils_reset_error();
EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024));
char * test_path = rcutils_join_path(cur_dir, "test");
char * path = rcutils_join_path(test_path, "correct_config.yaml");
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(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_safe());
EXPECT_TRUE(res);
rcl_yaml_node_struct_print(params_hdl);
rcl_yaml_node_struct_fini(params_hdl);
free(test_path);
free(path);
}
TEST(test_file_parser, multi_ns_correct_syntax) {
rcutils_reset_error();
EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024));
char * test_path = rcutils_join_path(cur_dir, "test");
char * path = rcutils_join_path(test_path, "multi_ns_correct.yaml");
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(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_safe());
EXPECT_TRUE(res);
rcl_yaml_node_struct_print(params_hdl);
rcl_yaml_node_struct_fini(params_hdl);
free(test_path);
free(path);
}
TEST(test_file_parser, seq_map1) {
rcutils_reset_error();
EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024));
char * test_path = rcutils_join_path(cur_dir, "test");
char * path = rcutils_join_path(test_path, "seq_map1.yaml");
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(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_safe());
EXPECT_FALSE(res);
free(test_path);
free(path);
}
TEST(test_file_parser, seq_map2) {
rcutils_reset_error();
EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024));
char * test_path = rcutils_join_path(cur_dir, "test");
char * path = rcutils_join_path(test_path, "seq_map2.yaml");
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(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_safe());
EXPECT_FALSE(res);
free(test_path);
free(path);
}
TEST(test_file_parser, params_with_no_node) {
rcutils_reset_error();
EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024));
char * test_path = rcutils_join_path(cur_dir, "test");
char * path = rcutils_join_path(test_path, "params_with_no_node.yaml");
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(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_safe());
EXPECT_FALSE(res);
free(test_path);
free(path);
}
TEST(test_file_parser, no_alias_support) {
rcutils_reset_error();
EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024));
char * test_path = rcutils_join_path(cur_dir, "test");
char * path = rcutils_join_path(test_path, "no_alias_support.yaml");
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(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_safe());
EXPECT_FALSE(res);
free(test_path);
free(path);
}
TEST(test_file_parser, max_string_sz) {
rcutils_reset_error();
EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024));
char * test_path = rcutils_join_path(cur_dir, "test");
char * path = rcutils_join_path(test_path, "max_string_sz.yaml");
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(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_safe());
EXPECT_FALSE(res);
free(test_path);
free(path);
}
TEST(test_file_parser, no_value1) {
rcutils_reset_error();
EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024));
char * test_path = rcutils_join_path(cur_dir, "test");
char * path = rcutils_join_path(test_path, "no_value1.yaml");
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(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_safe());
EXPECT_FALSE(res);
free(test_path);
free(path);
}
TEST(test_file_parser, indented_ns) {
rcutils_reset_error();
EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024));
char * test_path = rcutils_join_path(cur_dir, "test");
char * path = rcutils_join_path(test_path, "indented_name_space.yaml");
fprintf(stderr, "cur_path: %s\n", path);
EXPECT_TRUE(rcutils_exists(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_safe());
EXPECT_FALSE(res);
free(test_path);
free(path);
}
int32_t main(int32_t argc, char ** argv)
{
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}