Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add general check for yaml on rcl_yaml_param_parser #809

Merged
merged 14 commits into from Oct 19, 2020
4 changes: 3 additions & 1 deletion rcl_yaml_param_parser/CMakeLists.txt
Expand Up @@ -4,6 +4,7 @@ project(rcl_yaml_param_parser)

find_package(ament_cmake_ros REQUIRED)
find_package(rcutils REQUIRED)
find_package(rmw REQUIRED)
find_package(libyaml_vendor REQUIRED)

# Default to C++14
Expand All @@ -30,7 +31,7 @@ add_library(
target_include_directories(${PROJECT_NAME} PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include>")
ament_target_dependencies(${PROJECT_NAME} "libyaml_vendor" "rcutils")
ament_target_dependencies(${PROJECT_NAME} "libyaml_vendor" "rcutils" "rmw")

# Set the visibility to hidden by default if possible
if(CMAKE_C_COMPILER_ID STREQUAL "GNU" OR CMAKE_C_COMPILER_ID MATCHES "Clang")
Expand Down Expand Up @@ -181,6 +182,7 @@ if(BUILD_TESTING)
endif()

ament_export_dependencies(ament_cmake libyaml_vendor)
ament_export_dependencies(rmw)
ament_export_include_directories(include)
install(
DIRECTORY include/
Expand Down
1 change: 1 addition & 0 deletions rcl_yaml_param_parser/package.xml
Expand Up @@ -14,6 +14,7 @@

<depend>libyaml_vendor</depend>
<depend>yaml</depend>
<depend>rmw</depend>
<build_depend>rcutils</build_depend>

<test_depend>ament_cmake_gtest</test_depend>
Expand Down
123 changes: 123 additions & 0 deletions rcl_yaml_param_parser/src/parse.c
Expand Up @@ -18,8 +18,13 @@
#include <string.h>

#include "rcutils/allocator.h"
#include "rcutils/format_string.h"
#include "rcutils/strdup.h"

#include "rmw/error_handling.h"
#include "rmw/validate_namespace.h"
#include "rmw/validate_node_name.h"

#include "./impl/add_to_arrays.h"
#include "./impl/parse.h"
#include "./impl/namespace.h"
Expand Down Expand Up @@ -404,6 +409,118 @@ rcutils_ret_t parse_value(
return ret;
}

///
/// Check a name space whether it is valid
///
static rcutils_ret_t
__validate_namespace(const char * namespace)
{
int validation_result = 0;
rmw_ret_t ret;
ret = rmw_validate_namespace(namespace, &validation_result, NULL);
if (ret != RMW_RET_OK) {
RCUTILS_SET_ERROR_MSG(rmw_get_error_string().str);
return RCUTILS_RET_ERROR;
}
if (validation_result != RMW_NAMESPACE_VALID) {
RCUTILS_SET_ERROR_MSG(rmw_namespace_validation_result_string(validation_result));
return RCUTILS_RET_INVALID_ARGUMENT;
}

return RCUTILS_RET_OK;
}

///
/// Check a node name whether it is valid
///
static rcutils_ret_t
__validate_nodename(const char * name)
{
int validation_result = 0;
rmw_ret_t ret;
ret = rmw_validate_node_name(name, &validation_result, NULL);
if (ret != RMW_RET_OK) {
RCUTILS_SET_ERROR_MSG(rmw_get_error_string().str);
return RCUTILS_RET_ERROR;
}
if (validation_result != RMW_NODE_NAME_VALID) {
RCUTILS_SET_ERROR_MSG(rmw_node_name_validation_result_string(validation_result));
return RCUTILS_RET_ERROR;
}

return RCUTILS_RET_OK;
}

///
/// Check a name (namespace/node_name) whether it is valid
///
static rcutils_ret_t
__validate_name(const char * name, rcutils_allocator_t allocator)
{
// special rules
if (strcmp(name, "/**") == 0) {
iuhilnehc-ynos marked this conversation as resolved.
Show resolved Hide resolved
return RCUTILS_RET_OK;
}

rcutils_ret_t ret = RCUTILS_RET_OK;
char * separator_pos = rindex(name, '/');
char * namespace = NULL;
char * node_name = NULL;
char * absolute_namespace = NULL;
if (NULL == separator_pos) {
node_name = rcutils_strdup(name, allocator);
if (NULL == node_name) {
ret = RCUTILS_RET_BAD_ALLOC;
goto clean;
}
} else {
namespace = rcutils_strndup(name, separator_pos - name, allocator);
if (NULL == namespace) {
ret = RCUTILS_RET_BAD_ALLOC;
goto clean;
}
if (namespace[0] != '/') {
absolute_namespace = rcutils_format_string(allocator, "/%s", namespace);
if (NULL == absolute_namespace) {
ret = RCUTILS_RET_BAD_ALLOC;
goto clean;
}
}
node_name = rcutils_strdup(separator_pos + 1, allocator);
if (NULL == node_name) {
ret = RCUTILS_RET_BAD_ALLOC;
goto clean;
}
}

if (absolute_namespace) {
ret = __validate_namespace(absolute_namespace);
} else if (namespace) {
ret = __validate_namespace(namespace);
}

if (ret != RCUTILS_RET_OK) {
goto clean;
}

ret = __validate_nodename(node_name);
if (ret != RCUTILS_RET_OK) {
goto clean;
}

clean:
if (absolute_namespace) {
allocator.deallocate(absolute_namespace, allocator.state);
}
if (node_name) {
allocator.deallocate(node_name, allocator.state);
}
if (namespace) {
allocator.deallocate(namespace, allocator.state);
}
return ret;
}

///
/// Parse the key part of the <key:value> pair
///
Expand Down Expand Up @@ -466,6 +583,12 @@ rcutils_ret_t parse_key(
break;
}

ret = __validate_name(node_name_ns, allocator);
if (RCUTILS_RET_OK != ret) {
allocator.deallocate(node_name_ns, allocator.state);
break;
}

ret = find_node(node_name_ns, params_st, node_idx);
allocator.deallocate(node_name_ns, allocator.state);
if (RCUTILS_RET_OK != ret) {
Expand Down
14 changes: 14 additions & 0 deletions rcl_yaml_param_parser/test/empty_name_in_ns.yaml
@@ -0,0 +1,14 @@
lidar_ns//lidar_w:
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
27 changes: 27 additions & 0 deletions rcl_yaml_param_parser/test/test_parse_yaml.cpp
Expand Up @@ -531,6 +531,33 @@ TEST(test_file_parser, special_float_point) {
EXPECT_TRUE(std::isinf(param_value->double_array_value->values[6]));
}

TEST(test_file_parser, empty_name_in_ns) {
rcutils_reset_error();
EXPECT_TRUE(rcutils_get_cwd(cur_dir, 1024));
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_name_in_ns.yaml", allocator);
ASSERT_TRUE(NULL != path) << rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
allocator.deallocate(path, allocator.state);
});
EXPECT_TRUE(rcutils_exists(path));
rcl_params_t * params_hdl = rcl_yaml_node_struct_init(allocator);
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);
EXPECT_FALSE(res);
}

int32_t main(int32_t argc, char ** argv)
{
::testing::InitGoogleTest(&argc, argv);
Expand Down