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 init options API test coverage. #108

Merged
merged 2 commits into from
Jul 1, 2020
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 10 additions & 0 deletions test_rmw_implementation/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,16 @@ if(BUILD_TESTING)
ament_target_dependencies(test_init_shutdown${target_suffix}
osrf_testing_tools_cpp rcutils rmw rmw_implementation
)

ament_add_gtest(test_init_options${target_suffix}
test/test_init_options.cpp
ENV ${rmw_implementation_env_var}
)
target_compile_definitions(test_init_options${target_suffix}
PUBLIC "RMW_IMPLEMENTATION=${rmw_implementation}")
ament_target_dependencies(test_init_options${target_suffix}
osrf_testing_tools_cpp rcutils rmw rmw_implementation
)
endmacro()

call_for_each_rmw_implementation(test_api)
Expand Down
94 changes: 94 additions & 0 deletions test_rmw_implementation/test/allocator_testing_utils.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,94 @@
// Copyright 2020 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 ALLOCATOR_TESTING_UTILS_H_
#define ALLOCATOR_TESTING_UTILS_H_

#ifdef __cplusplus
extern "C"
{
#endif

#include <stddef.h>

#include "rcutils/allocator.h"

typedef struct __failing_allocator_state
{
bool is_failing;
} __failing_allocator_state;

void *
failing_malloc(size_t size, void * state)
{
if (((__failing_allocator_state *)state)->is_failing) {
return nullptr;
}
return rcutils_get_default_allocator().allocate(size, rcutils_get_default_allocator().state);
}

void *
failing_realloc(void * pointer, size_t size, void * state)
{
if (((__failing_allocator_state *)state)->is_failing) {
return nullptr;
}
return rcutils_get_default_allocator().reallocate(
pointer, size, rcutils_get_default_allocator().state);
}

void
failing_free(void * pointer, void * state)
{
if (((__failing_allocator_state *)state)->is_failing) {
return;
}
rcutils_get_default_allocator().deallocate(pointer, rcutils_get_default_allocator().state);
}

void *
failing_calloc(size_t number_of_elements, size_t size_of_element, void * state)
{
if (((__failing_allocator_state *)state)->is_failing) {
return nullptr;
}
return rcutils_get_default_allocator().zero_allocate(
number_of_elements, size_of_element, rcutils_get_default_allocator().state);
}

static inline rcutils_allocator_t
get_failing_allocator(void)
{
static __failing_allocator_state state;
state.is_failing = true;
auto failing_allocator = rcutils_get_default_allocator();
failing_allocator.allocate = failing_malloc;
failing_allocator.deallocate = failing_free;
failing_allocator.reallocate = failing_realloc;
failing_allocator.zero_allocate = failing_calloc;
failing_allocator.state = &state;
return failing_allocator;
}

static inline void
set_failing_allocator_is_failing(rcutils_allocator_t & failing_allocator, bool state)
{
((__failing_allocator_state *)failing_allocator.state)->is_failing = state;
}

#ifdef __cplusplus
}
#endif

#endif // ALLOCATOR_TESTING_UTILS_H_
149 changes: 149 additions & 0 deletions test_rmw_implementation/test/test_init_options.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,149 @@
// Copyright 2020 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.

#include <gtest/gtest.h>

#include "osrf_testing_tools_cpp/scope_exit.hpp"

#include "rcutils/allocator.h"
#include "rcutils/error_handling.h"

#include "rmw/rmw.h"

#include "./allocator_testing_utils.h"

#ifdef RMW_IMPLEMENTATION
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
# define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX)
#else
# define CLASSNAME(NAME, SUFFIX) NAME
#endif

class CLASSNAME (TestInitOptions, RMW_IMPLEMENTATION) : public ::testing::Test {};

TEST_F(CLASSNAME(TestInitOptions, RMW_IMPLEMENTATION), init_copy_fini) {
rmw_init_options_t src_options = rmw_get_zero_initialized_init_options();
rmw_ret_t ret = rmw_init_options_init(&src_options, rcutils_get_default_allocator());
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;

// Initializing twice fails.
ret = rmw_init_options_init(&src_options, rcutils_get_default_allocator());
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rcutils_reset_error();

rmw_init_options_t dst_options = rmw_get_zero_initialized_init_options();
ret = rmw_init_options_copy(&src_options, &dst_options);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;

// Copying twice fails.
ret = rmw_init_options_copy(&src_options, &dst_options);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret) << rcutils_get_error_string().str;
rcutils_reset_error();

ret = rmw_init_options_fini(&dst_options);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;

ret = rmw_init_options_fini(&src_options);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;

// Finalizing twice fails.
ret = rmw_init_options_fini(&src_options);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rcutils_reset_error();
}

TEST_F(CLASSNAME(TestInitOptions, RMW_IMPLEMENTATION), init_with_bad_arguments) {
rmw_init_options_t options = rmw_get_zero_initialized_init_options();
rmw_ret_t ret = rmw_init_options_init(&options, rcutils_get_zero_initialized_allocator());
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rcutils_reset_error();

ret = rmw_init_options_init(nullptr, rcutils_get_default_allocator());
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rcutils_reset_error();

// Initialization and finalization still succeed.
ret = rmw_init_options_init(&options, rcutils_get_default_allocator());
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
ret = rmw_init_options_fini(&options);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
}

TEST_F(CLASSNAME(TestInitOptions, RMW_IMPLEMENTATION), copy_with_bad_arguments) {
rmw_init_options_t src_options = rmw_get_zero_initialized_init_options();
rmw_init_options_t dst_options = rmw_get_zero_initialized_init_options();

rmw_ret_t ret = rmw_init_options_copy(nullptr, &dst_options);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rcutils_reset_error();

ret = rmw_init_options_copy(&src_options, nullptr);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rcutils_reset_error();

ret = rmw_init_options_copy(&src_options, &dst_options);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rcutils_reset_error();

ret = rmw_init_options_init(&src_options, rcutils_get_default_allocator());
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rmw_ret_t ret = rmw_init_options_fini(&src_options);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
});

const char * implementation_identifier = src_options.implementation_identifier;
src_options.implementation_identifier = "not-an-rmw-implementation-identifier";
ret = rmw_init_options_copy(&src_options, &dst_options);
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ret);
src_options.implementation_identifier = implementation_identifier;
rcutils_reset_error();

// Initialization and finalization still succeed.
ret = rmw_init_options_init(&dst_options, rcutils_get_default_allocator());
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
ret = rmw_init_options_fini(&dst_options);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
}

TEST_F(CLASSNAME(TestInitOptions, RMW_IMPLEMENTATION), fini_with_bad_arguments) {
rmw_init_options_t options = rmw_get_zero_initialized_init_options();
rmw_ret_t ret = rmw_init_options_fini(&options);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rcutils_reset_error();

ret = rmw_init_options_fini(nullptr);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rcutils_reset_error();

ret = rmw_init_options_init(&options, rcutils_get_default_allocator());
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;

const char * implementation_identifier = options.implementation_identifier;
options.implementation_identifier = "not-an-rmw-implementation-identifier";
ret = rmw_init_options_fini(&options);
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ret);
options.implementation_identifier = implementation_identifier;
rcutils_reset_error();

ret = rmw_init_options_fini(&options);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;

// Initialization and finalization still succeed.
ret = rmw_init_options_init(&options, rcutils_get_default_allocator());
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
ret = rmw_init_options_fini(&options);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
}