Skip to content

Commit

Permalink
Bump test coverage. (#764)
Browse files Browse the repository at this point in the history
* 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>
  • Loading branch information
hidmic authored and ahcorde committed Oct 30, 2020
1 parent bfff4c1 commit adfb2e9
Show file tree
Hide file tree
Showing 14 changed files with 440 additions and 42 deletions.
3 changes: 3 additions & 0 deletions rcl/src/rcl/arguments.c
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
7 changes: 4 additions & 3 deletions rcl/src/rcl/domain_id.c
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down
7 changes: 7 additions & 0 deletions rcl/src/rcl/expand_topic_name.c
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
11 changes: 11 additions & 0 deletions rcl/src/rcl/init_options.c
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand All @@ -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");
Expand All @@ -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);
Expand Down
6 changes: 3 additions & 3 deletions rcl/src/rcl/localhost.c
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down
7 changes: 5 additions & 2 deletions rcl/src/rcl/node_options.c
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@ extern "C"
{
#endif

#include "rcutils/macros.h"

#include "rcl/node_options.h"

#include "rcl/arguments.h"
Expand Down Expand Up @@ -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) {
Expand All @@ -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;
}
Expand Down
14 changes: 14 additions & 0 deletions rcl/src/rcl/remap.c
Original file line number Diff line number Diff line change
Expand Up @@ -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"

Expand All @@ -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);
Expand Down Expand Up @@ -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,
Expand All @@ -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,
Expand Down
16 changes: 7 additions & 9 deletions rcl/src/rcl/validate_enclave_name.c
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <stdio.h>
#include <string.h>

#include <rcutils/macros.h>
#include <rcutils/snprintf.h>

#include "rmw/validate_namespace.h"
Expand All @@ -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);
}
Expand All @@ -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;
Expand Down
11 changes: 6 additions & 5 deletions rcl/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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}
)

Expand Down Expand Up @@ -157,16 +157,17 @@ 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}
)

rcl_add_custom_gtest(test_node${target_suffix}
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}
Expand Down Expand Up @@ -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"
)

Expand Down Expand Up @@ -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"
)

Expand Down
12 changes: 10 additions & 2 deletions rcl/test/rcl/test_context.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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 changes: 24 additions & 0 deletions rcl/test/rcl/test_guard_condition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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);
Expand All @@ -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);
Expand Down
74 changes: 74 additions & 0 deletions rcl/test/rcl/test_init.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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) {
Expand Down
Loading

0 comments on commit adfb2e9

Please sign in to comment.