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
5 changes: 4 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 @@ -126,6 +127,7 @@ if(BUILD_TESTING)
ament_add_gtest(test_parser_multiple_nodes
test/test_parser_multiple_nodes.cpp
WORKING_DIRECTORY "${CMAKE_CURRENT_SOURCE_DIR}"
TIMEOUT 240 # Large timeout to wait for fault injection tests
)
if(TARGET test_parser_multiple_nodes)
ament_target_dependencies(test_parser_multiple_nodes
Expand Down Expand Up @@ -181,6 +183,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
179 changes: 179 additions & 0 deletions rcl_yaml_param_parser/src/parse.c
Expand Up @@ -18,13 +18,54 @@
#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"
#include "./impl/node_params.h"
#include "rcl_yaml_param_parser/parser.h"
#include "rcl_yaml_param_parser/visibility_control.h"

///
/// Check a name space whether it is valid
///
/// \param[in] namespace the namespace to check
/// \return RCUTILS_RET_OK if namespace is valid, or
/// \return RCUTILS_RET_INVALID_ARGUMENT if namespace is not valid, or
/// \return RCUTILS_RET_ERROR if an unspecified error occurred.
RCL_YAML_PARAM_PARSER_LOCAL
jacobperron marked this conversation as resolved.
Show resolved Hide resolved
rcutils_ret_t
_validate_namespace(const char * namespace_);

///
/// Check a node name whether it is valid
///
/// \param[in] name the node name to check
/// \return RCUTILS_RET_OK if the node name is valid, or
/// \return RCUTILS_RET_INVALID_ARGUMENT if node name is not valid, or
/// \return RCUTILS_RET_ERROR if an unspecified error occurred.
RCL_YAML_PARAM_PARSER_LOCAL
rcutils_ret_t
_validate_nodename(const char * node_name);

///
/// Check a name (namespace/node_name) whether it is valid
///
/// \param name the name to check
/// \param allocator an allocator to use
/// \return RCUTILS_RET_OK if name is valid, or
/// \return RCUTILS_RET_INVALID_ARGUMENT if name is not valid, or
/// \return RCL_RET_BAD_ALLOC if an allocation failed, or
/// \return RCUTILS_RET_ERROR if an unspecified error occurred.
RCL_YAML_PARAM_PARSER_LOCAL
rcutils_ret_t
_validate_name(const char * name, rcutils_allocator_t allocator);

///
/// Determine the type of the value and return the converted value
Expand Down Expand Up @@ -404,6 +445,138 @@ rcutils_ret_t parse_value(
return ret;
}

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 (RMW_RET_OK != ret) {
RCUTILS_SET_ERROR_MSG(rmw_get_error_string().str);
return RCUTILS_RET_ERROR;
}
if (RMW_NAMESPACE_VALID != validation_result) {
RCUTILS_SET_ERROR_MSG(rmw_namespace_validation_result_string(validation_result));
return RCUTILS_RET_INVALID_ARGUMENT;
}

return RCUTILS_RET_OK;
}

rcutils_ret_t
_validate_nodename(const char * node_name)
{
int validation_result = 0;
rmw_ret_t ret;
ret = rmw_validate_node_name(node_name, &validation_result, NULL);
if (RMW_RET_OK != ret) {
RCUTILS_SET_ERROR_MSG(rmw_get_error_string().str);
return RCUTILS_RET_ERROR;
}
if (RMW_NODE_NAME_VALID != validation_result) {
RCUTILS_SET_ERROR_MSG(rmw_node_name_validation_result_string(validation_result));
return RCUTILS_RET_INVALID_ARGUMENT;
}

return RCUTILS_RET_OK;
}

rcutils_ret_t
_validate_name(const char * name, rcutils_allocator_t allocator)
{
// special rules
if (0 == strcmp(name, "/**") || 0 == strcmp(name, "/*")) {
return RCUTILS_RET_OK;
}

rcutils_ret_t ret = RCUTILS_RET_OK;
char * separator_pos = strrchr(name, '/');
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 {
// substring namespace including the last '/'
char * namespace_ = rcutils_strndup(name, separator_pos - name + 1, allocator);
if (NULL == namespace_) {
ret = RCUTILS_RET_BAD_ALLOC;
goto clean;
}
if (namespace_[0] != '/') {
absolute_namespace = rcutils_format_string(allocator, "/%s", namespace_);
allocator.deallocate(namespace_, allocator.state);
if (NULL == absolute_namespace) {
ret = RCUTILS_RET_BAD_ALLOC;
goto clean;
}
} else {
absolute_namespace = namespace_;
}

node_name = rcutils_strdup(separator_pos + 1, allocator);
if (NULL == node_name) {
ret = RCUTILS_RET_BAD_ALLOC;
goto clean;
}
}

if (absolute_namespace) {
size_t i = 0;
separator_pos = strchr(absolute_namespace + i + 1, '/');
if (NULL == separator_pos) {
ret = _validate_namespace(absolute_namespace);
if (RCUTILS_RET_OK != ret) {
goto clean;
}
} else {
do {
jacobperron marked this conversation as resolved.
Show resolved Hide resolved
size_t len = separator_pos - absolute_namespace - i;
char * namespace_ = rcutils_strndup(absolute_namespace + i, len, allocator);
if (NULL == namespace_) {
ret = RCUTILS_RET_BAD_ALLOC;
goto clean;
}
if (0 == strcmp(namespace_, "/")) {
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(
"%s contains repeated forward slash", absolute_namespace);
allocator.deallocate(namespace_, allocator.state);
ret = RCUTILS_RET_INVALID_ARGUMENT;
goto clean;
}
if (0 != strcmp(namespace_, "/**") && 0 != strcmp(namespace_, "/*")) {
ret = _validate_namespace(namespace_);
if (RCUTILS_RET_OK != ret) {
allocator.deallocate(namespace_, allocator.state);
goto clean;
}
}
allocator.deallocate(namespace_, allocator.state);
i += len;
} while (NULL != (separator_pos = strchr(absolute_namespace + i + 1, '/')));
}
}

if (0 != strcmp(node_name, "*") && 0 != strcmp(node_name, "**")) {
jacobperron marked this conversation as resolved.
Show resolved Hide resolved
ret = _validate_nodename(node_name);
if (RCUTILS_RET_OK != ret) {
goto clean;
}
}

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

///
/// Parse the key part of the <key:value> pair
///
Expand Down Expand Up @@ -466,6 +639,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