Bump test coverage. (#764)
* init/shutdown API * context fini API * node init/fini API * guard condition init/fini API * security APIs Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
This commit is contained in:
parent
14ef8e02f8
commit
907a93dacc
14 changed files with 440 additions and 42 deletions
|
@ -783,6 +783,9 @@ rcl_arguments_copy(
|
|||
const rcl_arguments_t * args,
|
||||
rcl_arguments_t * args_out)
|
||||
{
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);
|
||||
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(args_out, RCL_RET_INVALID_ARGUMENT);
|
||||
|
|
|
@ -27,12 +27,13 @@ const char * const RCL_DOMAIN_ID_ENV_VAR = "ROS_DOMAIN_ID";
|
|||
rcl_ret_t
|
||||
rcl_get_default_domain_id(size_t * domain_id)
|
||||
{
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_ERROR);
|
||||
|
||||
const char * ros_domain_id = NULL;
|
||||
const char * get_env_error_str = NULL;
|
||||
|
||||
if (!domain_id) {
|
||||
return RCL_RET_INVALID_ARGUMENT;
|
||||
}
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(domain_id, RCL_RET_INVALID_ARGUMENT);
|
||||
|
||||
get_env_error_str = rcutils_get_env(RCL_DOMAIN_ID_ENV_VAR, &ros_domain_id);
|
||||
if (NULL != get_env_error_str) {
|
||||
|
|
|
@ -49,6 +49,13 @@ rcl_expand_topic_name(
|
|||
rcl_allocator_t allocator,
|
||||
char ** output_topic_name)
|
||||
{
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_TOPIC_NAME_INVALID);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_NODE_INVALID_NAME);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_NODE_INVALID_NAMESPACE);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_UNKNOWN_SUBSTITUTION);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);
|
||||
|
||||
// check arguments that could be null
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(input_topic_name, RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(node_name, RCL_RET_INVALID_ARGUMENT);
|
||||
|
|
|
@ -21,6 +21,7 @@ extern "C"
|
|||
|
||||
#include "./common.h"
|
||||
#include "./init_options_impl.h"
|
||||
#include "rcutils/macros.h"
|
||||
#include "rcl/error_handling.h"
|
||||
#include "rmw/error_handling.h"
|
||||
#include "rcutils/logging_macros.h"
|
||||
|
@ -36,6 +37,11 @@ rcl_get_zero_initialized_init_options(void)
|
|||
rcl_ret_t
|
||||
rcl_init_options_init(rcl_init_options_t * init_options, rcl_allocator_t allocator)
|
||||
{
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_ALREADY_INIT);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_ERROR);
|
||||
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(init_options, RCL_RET_INVALID_ARGUMENT);
|
||||
if (NULL != init_options->impl) {
|
||||
RCL_SET_ERROR_MSG("given init_options (rcl_init_options_t) is already initialized");
|
||||
|
@ -61,6 +67,11 @@ rcl_init_options_init(rcl_init_options_t * init_options, rcl_allocator_t allocat
|
|||
rcl_ret_t
|
||||
rcl_init_options_copy(const rcl_init_options_t * src, rcl_init_options_t * dst)
|
||||
{
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_ALREADY_INIT);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_ERROR);
|
||||
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(src, RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(src->impl, RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(dst, RCL_RET_INVALID_ARGUMENT);
|
||||
|
|
|
@ -30,9 +30,9 @@ rcl_get_localhost_only(rmw_localhost_only_t * localhost_only)
|
|||
const char * ros_local_host_env_val = NULL;
|
||||
const char * get_env_error_str = NULL;
|
||||
|
||||
if (!localhost_only) {
|
||||
return RCL_RET_INVALID_ARGUMENT;
|
||||
}
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_ERROR);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(localhost_only, RCL_RET_INVALID_ARGUMENT);
|
||||
|
||||
get_env_error_str = rcutils_get_env(RCL_LOCALHOST_ENV_VAR, &ros_local_host_env_val);
|
||||
if (NULL != get_env_error_str) {
|
||||
|
|
|
@ -17,6 +17,8 @@ extern "C"
|
|||
{
|
||||
#endif
|
||||
|
||||
#include "rcutils/macros.h"
|
||||
|
||||
#include "rcl/node_options.h"
|
||||
|
||||
#include "rcl/arguments.h"
|
||||
|
@ -44,6 +46,8 @@ rcl_node_options_copy(
|
|||
const rcl_node_options_t * options,
|
||||
rcl_node_options_t * options_out)
|
||||
{
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
|
||||
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(options, RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(options_out, RCL_RET_INVALID_ARGUMENT);
|
||||
if (options_out == options) {
|
||||
|
@ -59,8 +63,7 @@ rcl_node_options_copy(
|
|||
options_out->use_global_arguments = options->use_global_arguments;
|
||||
options_out->enable_rosout = options->enable_rosout;
|
||||
if (NULL != options->arguments.impl) {
|
||||
rcl_ret_t ret = rcl_arguments_copy(&(options->arguments), &(options_out->arguments));
|
||||
return ret;
|
||||
return rcl_arguments_copy(&(options->arguments), &(options_out->arguments));
|
||||
}
|
||||
return RCL_RET_OK;
|
||||
}
|
||||
|
|
|
@ -19,6 +19,7 @@
|
|||
#include "rcl/error_handling.h"
|
||||
#include "rcl/expand_topic_name.h"
|
||||
#include "rcutils/allocator.h"
|
||||
#include "rcutils/macros.h"
|
||||
#include "rcutils/strdup.h"
|
||||
#include "rcutils/types/string_map.h"
|
||||
|
||||
|
@ -41,6 +42,9 @@ rcl_remap_copy(
|
|||
const rcl_remap_t * rule,
|
||||
rcl_remap_t * rule_out)
|
||||
{
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);
|
||||
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(rule, RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(rule_out, RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(rule->impl, RCL_RET_INVALID_ARGUMENT);
|
||||
|
@ -289,6 +293,11 @@ rcl_remap_node_name(
|
|||
rcl_allocator_t allocator,
|
||||
char ** output_name)
|
||||
{
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_NODE_INVALID_NAME);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_ERROR);
|
||||
|
||||
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT);
|
||||
return _rcl_remap_name(
|
||||
local_arguments, global_arguments, RCL_NODENAME_REMAP, NULL, node_name, NULL, NULL,
|
||||
|
@ -303,6 +312,11 @@ rcl_remap_node_namespace(
|
|||
rcl_allocator_t allocator,
|
||||
char ** output_namespace)
|
||||
{
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_NODE_INVALID_NAMESPACE);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_ERROR);
|
||||
|
||||
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "allocator is invalid", return RCL_RET_INVALID_ARGUMENT);
|
||||
return _rcl_remap_name(
|
||||
local_arguments, global_arguments, RCL_NAMESPACE_REMAP, NULL, node_name, NULL, NULL,
|
||||
|
|
|
@ -18,6 +18,7 @@
|
|||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
|
||||
#include <rcutils/macros.h>
|
||||
#include <rcutils/snprintf.h>
|
||||
|
||||
#include "rmw/validate_namespace.h"
|
||||
|
@ -32,9 +33,7 @@ rcl_validate_enclave_name(
|
|||
int * validation_result,
|
||||
size_t * invalid_index)
|
||||
{
|
||||
if (!enclave) {
|
||||
return RCL_RET_INVALID_ARGUMENT;
|
||||
}
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(enclave, RCL_RET_INVALID_ARGUMENT);
|
||||
return rcl_validate_enclave_name_with_size(
|
||||
enclave, strlen(enclave), validation_result, invalid_index);
|
||||
}
|
||||
|
@ -46,12 +45,11 @@ rcl_validate_enclave_name_with_size(
|
|||
int * validation_result,
|
||||
size_t * invalid_index)
|
||||
{
|
||||
if (!enclave) {
|
||||
return RCL_RET_INVALID_ARGUMENT;
|
||||
}
|
||||
if (!validation_result) {
|
||||
return RCL_RET_INVALID_ARGUMENT;
|
||||
}
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
|
||||
RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_ERROR);
|
||||
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(enclave, RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(validation_result, RCL_RET_INVALID_ARGUMENT);
|
||||
|
||||
int tmp_validation_result;
|
||||
size_t tmp_invalid_index;
|
||||
|
|
|
@ -74,7 +74,7 @@ function(test_target_function)
|
|||
SRCS rcl/test_context.cpp
|
||||
ENV ${rmw_implementation_env_var} ${memory_tools_ld_preload_env_var}
|
||||
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
||||
LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools
|
||||
LIBRARIES ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools
|
||||
AMENT_DEPENDENCIES ${rmw_implementation}
|
||||
)
|
||||
|
||||
|
@ -157,7 +157,7 @@ function(test_target_function)
|
|||
SRCS rcl/test_init.cpp
|
||||
ENV ${rmw_implementation_env_var} ${memory_tools_ld_preload_env_var}
|
||||
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
||||
LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools
|
||||
LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools mimick
|
||||
AMENT_DEPENDENCIES ${rmw_implementation}
|
||||
)
|
||||
|
||||
|
@ -165,8 +165,9 @@ function(test_target_function)
|
|||
SRCS rcl/test_node.cpp
|
||||
ENV ${rmw_implementation_env_var} ${memory_tools_ld_preload_env_var}
|
||||
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
||||
LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools
|
||||
LIBRARIES ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools
|
||||
AMENT_DEPENDENCIES ${rmw_implementation} "osrf_testing_tools_cpp"
|
||||
TIMEOUT 240 # Large timeout to wait for fault injection tests
|
||||
)
|
||||
|
||||
rcl_add_custom_gtest(test_arguments${target_suffix}
|
||||
|
@ -200,7 +201,7 @@ function(test_target_function)
|
|||
SRCS rcl/test_guard_condition.cpp
|
||||
ENV ${rmw_implementation_env_var} ${memory_tools_ld_preload_env_var}
|
||||
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
||||
LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools
|
||||
LIBRARIES ${PROJECT_NAME} mimick osrf_testing_tools_cpp::memory_tools
|
||||
AMENT_DEPENDENCIES ${rmw_implementation} "osrf_testing_tools_cpp"
|
||||
)
|
||||
|
||||
|
@ -383,7 +384,7 @@ rcl_add_custom_gtest(test_expand_topic_name
|
|||
rcl_add_custom_gtest(test_security
|
||||
SRCS rcl/test_security.cpp
|
||||
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
|
||||
LIBRARIES ${PROJECT_NAME}
|
||||
LIBRARIES ${PROJECT_NAME} mimick
|
||||
AMENT_DEPENDENCIES "osrf_testing_tools_cpp"
|
||||
)
|
||||
|
||||
|
|
|
@ -20,6 +20,10 @@
|
|||
#include "rcl/error_handling.h"
|
||||
#include "rcl/init.h"
|
||||
|
||||
#include "rmw/rmw.h"
|
||||
|
||||
#include "../mocking_utils/patch.hpp"
|
||||
|
||||
#ifdef RMW_IMPLEMENTATION
|
||||
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
|
||||
# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX)
|
||||
|
@ -148,6 +152,10 @@ TEST_F(CLASSNAME(TestContextFixture, RMW_IMPLEMENTATION), bad_fini) {
|
|||
ret = rcl_shutdown(&context);
|
||||
EXPECT_EQ(ret, RCL_RET_OK);
|
||||
|
||||
ret = rcl_context_fini(&context);
|
||||
EXPECT_EQ(ret, RCL_RET_OK);
|
||||
{
|
||||
auto mock = mocking_utils::inject_on_return(
|
||||
"lib:rcl", rmw_context_fini, RMW_RET_ERROR);
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_context_fini(&context));
|
||||
rcl_reset_error();
|
||||
}
|
||||
}
|
||||
|
|
|
@ -24,6 +24,10 @@
|
|||
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
||||
#include "rcl/error_handling.h"
|
||||
|
||||
#include "rmw/rmw.h"
|
||||
|
||||
#include "../mocking_utils/patch.hpp"
|
||||
|
||||
#ifdef RMW_IMPLEMENTATION
|
||||
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
|
||||
# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX)
|
||||
|
@ -188,6 +192,14 @@ TEST_F(
|
|||
ASSERT_EQ(RCL_RET_BAD_ALLOC, ret) << "Expected RCL_RET_BAD_ALLOC";
|
||||
ASSERT_TRUE(rcl_error_is_set());
|
||||
rcl_reset_error();
|
||||
// Try init but force an internal error.
|
||||
{
|
||||
auto mock = mocking_utils::patch_to_fail(
|
||||
"lib:rcl", rmw_create_guard_condition, "internal error", nullptr);
|
||||
ret = rcl_guard_condition_init(&guard_condition, &context, default_options);
|
||||
EXPECT_EQ(RCL_RET_ERROR, ret);
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
||||
// Try fini with invalid arguments.
|
||||
ret = rcl_guard_condition_fini(nullptr);
|
||||
|
@ -202,6 +214,18 @@ TEST_F(
|
|||
EXPECT_EQ(RCL_RET_OK, ret);
|
||||
ret = rcl_guard_condition_fini(&guard_condition);
|
||||
EXPECT_EQ(RCL_RET_OK, ret);
|
||||
// Try normal init and fini, but force an internal error on first try.
|
||||
{
|
||||
auto mock = mocking_utils::inject_on_return(
|
||||
"lib:rcl", rmw_destroy_guard_condition, RMW_RET_ERROR);
|
||||
ret = rcl_guard_condition_init(&guard_condition, &context, default_options);
|
||||
EXPECT_EQ(RCL_RET_OK, ret);
|
||||
ret = rcl_guard_condition_fini(&guard_condition);
|
||||
EXPECT_EQ(RCL_RET_ERROR, ret);
|
||||
rcl_reset_error();
|
||||
}
|
||||
ret = rcl_guard_condition_fini(&guard_condition);
|
||||
EXPECT_EQ(RCL_RET_OK, ret);
|
||||
// Try repeated init and fini calls.
|
||||
ret = rcl_guard_condition_init(&guard_condition, &context, default_options);
|
||||
EXPECT_EQ(RCL_RET_OK, ret);
|
||||
|
|
|
@ -23,8 +23,12 @@
|
|||
#include "rcutils/env.h"
|
||||
#include "rcutils/format_string.h"
|
||||
#include "rcutils/snprintf.h"
|
||||
#include "rcutils/testing/fault_injection.h"
|
||||
|
||||
#include "rmw/rmw.h"
|
||||
|
||||
#include "./allocator_testing_utils.h"
|
||||
#include "../mocking_utils/patch.hpp"
|
||||
#include "../src/rcl/init_options_impl.h"
|
||||
|
||||
#ifdef RMW_IMPLEMENTATION
|
||||
|
@ -297,6 +301,76 @@ TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_init_and_shutdown
|
|||
context = rcl_get_zero_initialized_context();
|
||||
}
|
||||
|
||||
/* Tests rcl_init() deals with internal errors correctly.
|
||||
*/
|
||||
TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_init_internal_error) {
|
||||
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
|
||||
rcl_ret_t ret = rcl_init_options_init(&init_options, rcl_get_default_allocator());
|
||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str;
|
||||
});
|
||||
FakeTestArgv test_args;
|
||||
rcl_context_t context = rcl_get_zero_initialized_context();
|
||||
|
||||
{
|
||||
auto mock = mocking_utils::patch_to_fail(
|
||||
"lib:rcl", rmw_init, "internal error", RMW_RET_ERROR);
|
||||
ret = rcl_init(test_args.argc, test_args.argv, &init_options, &context);
|
||||
EXPECT_EQ(RCL_RET_ERROR, ret);
|
||||
EXPECT_TRUE(rcl_error_is_set());
|
||||
rcl_reset_error();
|
||||
EXPECT_FALSE(rcl_context_is_valid(&context));
|
||||
}
|
||||
|
||||
RCUTILS_FAULT_INJECTION_TEST(
|
||||
{
|
||||
ret = rcl_init(test_args.argc, test_args.argv, &init_options, &context);
|
||||
|
||||
int64_t count = rcutils_fault_injection_get_count();
|
||||
rcutils_fault_injection_set_count(RCUTILS_FAULT_INJECTION_NEVER_FAIL);
|
||||
|
||||
if (RCL_RET_OK == ret) {
|
||||
ASSERT_TRUE(rcl_context_is_valid(&context));
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_shutdown(&context)) << rcl_get_error_string().str;
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_context_fini(&context)) << rcl_get_error_string().str;
|
||||
} else {
|
||||
ASSERT_FALSE(rcl_context_is_valid(&context));
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
||||
rcutils_fault_injection_set_count(count);
|
||||
});
|
||||
}
|
||||
|
||||
/* Tests rcl_shutdown() deals with internal errors correctly.
|
||||
*/
|
||||
TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_shutdown_internal_error) {
|
||||
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
|
||||
rcl_ret_t ret = rcl_init_options_init(&init_options, rcl_get_default_allocator());
|
||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str;
|
||||
});
|
||||
rcl_context_t context = rcl_get_zero_initialized_context();
|
||||
|
||||
ret = rcl_init(0, nullptr, &init_options, &context);
|
||||
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_shutdown(&context)) << rcl_get_error_string().str;
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_context_fini(&context)) << rcl_get_error_string().str;
|
||||
});
|
||||
EXPECT_TRUE(rcl_context_is_valid(&context));
|
||||
|
||||
auto mock = mocking_utils::patch_to_fail(
|
||||
"lib:rcl", rmw_shutdown, "internal error", RMW_RET_ERROR);
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_shutdown(&context));
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
||||
/* Tests the rcl_get_instance_id() function.
|
||||
*/
|
||||
TEST_F(CLASSNAME(TestRCLFixture, RMW_IMPLEMENTATION), test_rcl_get_instance_id) {
|
||||
|
|
|
@ -21,11 +21,18 @@
|
|||
#include "rcl/rcl.h"
|
||||
#include "rcl/node.h"
|
||||
#include "rmw/rmw.h" // For rmw_get_implementation_identifier.
|
||||
#include "rmw/validate_namespace.h"
|
||||
#include "rmw/validate_node_name.h"
|
||||
|
||||
#include "./failing_allocator_functions.hpp"
|
||||
#include "osrf_testing_tools_cpp/memory_tools/memory_tools.hpp"
|
||||
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
||||
#include "rcutils/testing/fault_injection.h"
|
||||
#include "rcl/error_handling.h"
|
||||
#include "rcl/logging.h"
|
||||
#include "rcl/logging_rosout.h"
|
||||
|
||||
#include "../mocking_utils/patch.hpp"
|
||||
|
||||
#ifdef RMW_IMPLEMENTATION
|
||||
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
|
||||
|
@ -385,24 +392,6 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_life_cycle)
|
|||
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
|
||||
ASSERT_TRUE(rcl_error_is_set());
|
||||
rcl_reset_error();
|
||||
// Try with invalid allocator.
|
||||
rcl_node_options_t options_with_invalid_allocator = rcl_node_get_default_options();
|
||||
options_with_invalid_allocator.allocator.allocate = nullptr;
|
||||
options_with_invalid_allocator.allocator.deallocate = nullptr;
|
||||
options_with_invalid_allocator.allocator.reallocate = nullptr;
|
||||
ret = rcl_node_init(&node, name, namespace_, &context, &options_with_invalid_allocator);
|
||||
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << "Expected RCL_RET_INVALID_ARGUMENT";
|
||||
ASSERT_TRUE(rcl_error_is_set());
|
||||
rcl_reset_error();
|
||||
// Try with failing allocator.
|
||||
rcl_node_options_t options_with_failing_allocator = rcl_node_get_default_options();
|
||||
options_with_failing_allocator.allocator.allocate = failing_malloc;
|
||||
options_with_failing_allocator.allocator.reallocate = failing_realloc;
|
||||
ret = rcl_node_init(&node, name, namespace_, &context, &options_with_failing_allocator);
|
||||
EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << "Expected RCL_RET_BAD_ALLOC";
|
||||
ASSERT_TRUE(rcl_error_is_set());
|
||||
rcl_reset_error();
|
||||
|
||||
// Try fini with invalid arguments.
|
||||
ret = rcl_node_fini(nullptr);
|
||||
EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << "Expected RCL_RET_NODE_INVALID";
|
||||
|
@ -442,6 +431,121 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_life_cycle)
|
|||
}
|
||||
}
|
||||
|
||||
TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_init_with_internal_errors) {
|
||||
rcl_ret_t ret;
|
||||
rcl_context_t context = rcl_get_zero_initialized_context();
|
||||
rcl_node_t node = rcl_get_zero_initialized_node();
|
||||
const char * name = "test_rcl_node_init_with_internal_errors";
|
||||
const char * namespace_ = "ns"; // force non-absolute namespace handling
|
||||
rcl_node_options_t options = rcl_node_get_default_options();
|
||||
options.enable_rosout = true; // enable logging to cover more ground
|
||||
// Initialize rcl with rcl_init().
|
||||
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
|
||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||
ret = rcl_init_options_init(&init_options, allocator);
|
||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str;
|
||||
});
|
||||
ret = rcl_init(0, nullptr, &init_options, &context);
|
||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_shutdown(&context)) << rcl_get_error_string().str;
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_context_fini(&context)) << rcl_get_error_string().str;
|
||||
});
|
||||
// Initialize logging and rosout.
|
||||
ret = rcl_logging_configure(&context.global_arguments, &allocator);
|
||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_logging_fini()) << rcl_get_error_string().str;
|
||||
});
|
||||
ret = rcl_logging_rosout_init(&allocator);
|
||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
|
||||
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
|
||||
{
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_logging_rosout_fini()) << rcl_get_error_string().str;
|
||||
});
|
||||
// Try with invalid allocator.
|
||||
rcl_node_options_t options_with_invalid_allocator = rcl_node_get_default_options();
|
||||
options_with_invalid_allocator.allocator.allocate = nullptr;
|
||||
options_with_invalid_allocator.allocator.deallocate = nullptr;
|
||||
options_with_invalid_allocator.allocator.reallocate = nullptr;
|
||||
ret = rcl_node_init(&node, name, namespace_, &context, &options_with_invalid_allocator);
|
||||
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << "Expected RCL_RET_INVALID_ARGUMENT";
|
||||
ASSERT_TRUE(rcl_error_is_set());
|
||||
rcl_reset_error();
|
||||
// Try with failing allocator.
|
||||
rcl_node_options_t options_with_failing_allocator = rcl_node_get_default_options();
|
||||
options_with_failing_allocator.allocator.allocate = failing_malloc;
|
||||
options_with_failing_allocator.allocator.reallocate = failing_realloc;
|
||||
ret = rcl_node_init(&node, name, namespace_, &context, &options_with_failing_allocator);
|
||||
EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << "Expected RCL_RET_BAD_ALLOC";
|
||||
ASSERT_TRUE(rcl_error_is_set());
|
||||
rcl_reset_error();
|
||||
// Try init but force internal errors.
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return("lib:rcl", rmw_create_node, nullptr);
|
||||
ret = rcl_node_init(&node, name, namespace_, &context, &options);
|
||||
EXPECT_EQ(RCL_RET_ERROR, ret);
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rcl", rmw_node_get_graph_guard_condition, nullptr);
|
||||
ret = rcl_node_init(&node, name, namespace_, &context, &options);
|
||||
EXPECT_EQ(RCL_RET_ERROR, ret);
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rcl", rmw_validate_node_name, RMW_RET_ERROR);
|
||||
ret = rcl_node_init(&node, name, namespace_, &context, &options);
|
||||
EXPECT_EQ(RCL_RET_ERROR, ret);
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
||||
{
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rcl", rmw_validate_namespace, RMW_RET_ERROR);
|
||||
ret = rcl_node_init(&node, name, namespace_, &context, &options);
|
||||
EXPECT_EQ(RCL_RET_ERROR, ret);
|
||||
rcl_reset_error();
|
||||
}
|
||||
// Try normal init but force an internal error on fini.
|
||||
{
|
||||
ret = rcl_node_init(&node, name, namespace_, &context, &options);
|
||||
EXPECT_EQ(RCL_RET_OK, ret);
|
||||
auto mock = mocking_utils::inject_on_return("lib:rcl", rmw_destroy_node, RMW_RET_ERROR);
|
||||
ret = rcl_node_fini(&node);
|
||||
EXPECT_EQ(RCL_RET_ERROR, ret);
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
||||
// Battle test node init.
|
||||
RCUTILS_FAULT_INJECTION_TEST(
|
||||
{
|
||||
ret = rcl_node_init(&node, name, namespace_, &context, &options);
|
||||
|
||||
int64_t count = rcutils_fault_injection_get_count();
|
||||
rcutils_fault_injection_set_count(RCUTILS_FAULT_INJECTION_NEVER_FAIL);
|
||||
|
||||
if (RCL_RET_OK == ret) {
|
||||
ASSERT_TRUE(rcl_node_is_valid(&node));
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_node_fini(&node)) << rcl_get_error_string().str;
|
||||
} else {
|
||||
ASSERT_FALSE(rcl_node_is_valid(&node));
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
||||
rcutils_fault_injection_set_count(count);
|
||||
});
|
||||
}
|
||||
|
||||
/* Tests the node name restrictions enforcement.
|
||||
*/
|
||||
TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_name_restrictions) {
|
||||
|
|
|
@ -16,17 +16,22 @@
|
|||
|
||||
#include <algorithm>
|
||||
#include <cstring>
|
||||
#include <map>
|
||||
#include <string>
|
||||
|
||||
#include "rcl/security.h"
|
||||
#include "rcl/error_handling.h"
|
||||
|
||||
#include "rcutils/filesystem.h"
|
||||
#include "rcutils/get_env.h"
|
||||
|
||||
#include "rmw/error_handling.h"
|
||||
#include "rmw/rmw.h"
|
||||
|
||||
#include "osrf_testing_tools_cpp/scope_exit.hpp"
|
||||
|
||||
#include "./allocator_testing_utils.h"
|
||||
#include "../mocking_utils/patch.hpp"
|
||||
|
||||
#define TEST_SECURITY_DIRECTORY_RESOURCES_DIR_NAME "/test_security_directory"
|
||||
#define TEST_ENCLAVE "dummy_enclave"
|
||||
|
@ -253,3 +258,148 @@ TEST_F(TestGetSecureRoot, test_get_security_options) {
|
|||
PATH_SEPARATOR "enclaves" PATH_SEPARATOR TEST_ENCLAVE,
|
||||
options.security_root_path);
|
||||
}
|
||||
|
||||
TEST_F(TestGetSecureRoot, test_rcl_security_enabled) {
|
||||
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_security_enabled(nullptr));
|
||||
rcl_reset_error();
|
||||
|
||||
{
|
||||
bool use_security;
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rcl", rcutils_get_env, "internal error");
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_security_enabled(&use_security));
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
||||
{
|
||||
bool use_security = false;
|
||||
putenv_wrapper(ROS_SECURITY_ENABLE_VAR_NAME "=true");
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_security_enabled(&use_security));
|
||||
EXPECT_TRUE(use_security);
|
||||
unsetenv_wrapper(ROS_SECURITY_ENABLE_VAR_NAME);
|
||||
}
|
||||
|
||||
{
|
||||
bool use_security = true;
|
||||
putenv_wrapper(ROS_SECURITY_ENABLE_VAR_NAME "=false");
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_security_enabled(&use_security));
|
||||
EXPECT_FALSE(use_security);
|
||||
unsetenv_wrapper(ROS_SECURITY_ENABLE_VAR_NAME);
|
||||
}
|
||||
|
||||
{
|
||||
bool use_security = true;
|
||||
putenv_wrapper(ROS_SECURITY_ENABLE_VAR_NAME "=foo");
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_security_enabled(&use_security));
|
||||
EXPECT_FALSE(use_security);
|
||||
unsetenv_wrapper(ROS_SECURITY_ENABLE_VAR_NAME);
|
||||
}
|
||||
|
||||
{
|
||||
bool use_security = true;
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_security_enabled(&use_security));
|
||||
EXPECT_FALSE(use_security);
|
||||
}
|
||||
}
|
||||
|
||||
TEST_F(TestGetSecureRoot, test_rcl_get_enforcement_policy) {
|
||||
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_get_enforcement_policy(nullptr));
|
||||
rcl_reset_error();
|
||||
|
||||
{
|
||||
rmw_security_enforcement_policy_t policy;
|
||||
auto mock = mocking_utils::patch_and_return(
|
||||
"lib:rcl", rcutils_get_env, "internal error");
|
||||
EXPECT_EQ(RCL_RET_ERROR, rcl_get_enforcement_policy(&policy));
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
||||
{
|
||||
rmw_security_enforcement_policy_t policy = RMW_SECURITY_ENFORCEMENT_PERMISSIVE;
|
||||
putenv_wrapper(ROS_SECURITY_STRATEGY_VAR_NAME "=Enforce");
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_get_enforcement_policy(&policy));
|
||||
EXPECT_EQ(RMW_SECURITY_ENFORCEMENT_ENFORCE, policy);
|
||||
unsetenv_wrapper(ROS_SECURITY_STRATEGY_VAR_NAME);
|
||||
}
|
||||
|
||||
{
|
||||
rmw_security_enforcement_policy_t policy = RMW_SECURITY_ENFORCEMENT_ENFORCE;
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_get_enforcement_policy(&policy));
|
||||
EXPECT_EQ(RMW_SECURITY_ENFORCEMENT_PERMISSIVE, policy);
|
||||
}
|
||||
|
||||
{
|
||||
rmw_security_enforcement_policy_t policy = RMW_SECURITY_ENFORCEMENT_ENFORCE;
|
||||
putenv_wrapper(ROS_SECURITY_STRATEGY_VAR_NAME "=foo");
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_get_enforcement_policy(&policy));
|
||||
EXPECT_EQ(RMW_SECURITY_ENFORCEMENT_PERMISSIVE, policy);
|
||||
unsetenv_wrapper(ROS_SECURITY_STRATEGY_VAR_NAME);
|
||||
}
|
||||
|
||||
{
|
||||
rmw_security_enforcement_policy_t policy = RMW_SECURITY_ENFORCEMENT_ENFORCE;
|
||||
putenv_wrapper(ROS_SECURITY_STRATEGY_VAR_NAME "=ENFORCE");
|
||||
EXPECT_EQ(RCL_RET_OK, rcl_get_enforcement_policy(&policy));
|
||||
EXPECT_EQ(RMW_SECURITY_ENFORCEMENT_PERMISSIVE, policy);
|
||||
unsetenv_wrapper(ROS_SECURITY_STRATEGY_VAR_NAME);
|
||||
}
|
||||
}
|
||||
|
||||
TEST_F(TestGetSecureRoot, test_rcl_get_secure_root_with_bad_arguments) {
|
||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||
EXPECT_EQ(nullptr, rcl_get_secure_root(nullptr, &allocator));
|
||||
EXPECT_TRUE(rcl_error_is_set());
|
||||
rcl_reset_error();
|
||||
|
||||
EXPECT_EQ(nullptr, rcl_get_secure_root("test", nullptr));
|
||||
EXPECT_TRUE(rcl_error_is_set());
|
||||
rcl_reset_error();
|
||||
|
||||
rcl_allocator_t invalid_allocator = rcutils_get_zero_initialized_allocator();
|
||||
EXPECT_EQ(nullptr, rcl_get_secure_root("test", &invalid_allocator));
|
||||
EXPECT_TRUE(rcl_error_is_set());
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
||||
TEST_F(TestGetSecureRoot, test_rcl_get_secure_root_with_internal_errors) {
|
||||
rcl_allocator_t allocator = rcl_get_default_allocator();
|
||||
rcl_allocator_t failing_allocator = get_time_bombed_allocator();
|
||||
|
||||
std::map<std::string, std::string> env;
|
||||
auto mock = mocking_utils::patch(
|
||||
"lib:rcl", rcutils_get_env,
|
||||
[&](const char * name, const char ** value) -> const char * {
|
||||
if (env.count(name) == 0) {
|
||||
return "internal error";
|
||||
}
|
||||
*value = env[name].c_str();
|
||||
return nullptr;
|
||||
});
|
||||
|
||||
// fail to get ROS_SECURITY_KEYSTORE_VAR_NAME from environment
|
||||
EXPECT_EQ(nullptr, rcl_get_secure_root("test", &allocator));
|
||||
EXPECT_TRUE(rcl_error_is_set());
|
||||
rcl_reset_error();
|
||||
|
||||
env[ROS_SECURITY_KEYSTORE_VAR_NAME] =
|
||||
TEST_RESOURCES_DIRECTORY TEST_SECURITY_DIRECTORY_RESOURCES_DIR_NAME;
|
||||
|
||||
// fail to copy ROS_SECURITY_KEYSTORE_VAR_NAME value
|
||||
set_time_bombed_allocator_count(failing_allocator, 0);
|
||||
EXPECT_EQ(nullptr, rcl_get_secure_root("test", &failing_allocator));
|
||||
EXPECT_TRUE(rcl_error_is_set());
|
||||
rcl_reset_error();
|
||||
|
||||
// fail to get ROS_SECURITY_ENCLAVE_OVERRIDE from environment
|
||||
EXPECT_EQ(nullptr, rcl_get_secure_root("test", &allocator));
|
||||
EXPECT_TRUE(rcl_error_is_set());
|
||||
rcl_reset_error();
|
||||
|
||||
env[ROS_SECURITY_ENCLAVE_OVERRIDE] = TEST_ENCLAVE_ABSOLUTE;
|
||||
|
||||
// fail to copy ROS_SECURITY_ENCLAVE_OVERRIDE value
|
||||
set_time_bombed_allocator_count(failing_allocator, 1);
|
||||
EXPECT_EQ(nullptr, rcl_get_secure_root("test", &failing_allocator));
|
||||
EXPECT_TRUE(rcl_error_is_set());
|
||||
rcl_reset_error();
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue