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

Complete init/shutdown API test coverage. #107

Merged
merged 4 commits into from
Jul 1, 2020
Merged
Changes from 3 commits
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
89 changes: 83 additions & 6 deletions test_rmw_implementation/test/test_init_shutdown.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,20 +28,97 @@
# define CLASSNAME(NAME, SUFFIX) NAME
#endif

class CLASSNAME (TestInitShutdown, RMW_IMPLEMENTATION) : public ::testing::Test {};
class CLASSNAME (TestInitShutdown, RMW_IMPLEMENTATION) : public ::testing::Test
{
protected:
void SetUp() override
{
options = rmw_get_zero_initialized_init_options();
rmw_ret_t ret = rmw_init_options_init(&options, rcutils_get_default_allocator());
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
}

TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), init_shutdown) {
void TearDown() override
{
rmw_ret_t ret = rmw_init_options_fini(&options);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
}

rmw_init_options_t options;
};

TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), init_with_bad_arguments) {
rmw_context_t context = rmw_get_zero_initialized_context();
rmw_init_options_t options = rmw_get_zero_initialized_init_options();
rmw_ret_t ret = rmw_init_options_init(&options, rcutils_get_default_allocator());
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, rmw_init(nullptr, &context));
rcutils_reset_error();

context = rmw_get_zero_initialized_context();
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, rmw_init(&options, nullptr));
rcutils_reset_error();

const char * implementation_identifier = options.implementation_identifier;
options.implementation_identifier = "not-a-real-rmw-implementation-identifier";
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, rmw_init(&options, &context));
options.implementation_identifier = implementation_identifier;
rcutils_reset_error();
}

TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), shutdown_with_bad_arguments) {
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, rmw_shutdown(nullptr));
rcutils_reset_error();

rmw_context_t context = rmw_get_zero_initialized_context();
rmw_ret_t ret = rmw_shutdown(&context);
EXPECT_TRUE(
(RMW_RET_INCORRECT_RMW_IMPLEMENTATION == ret) ||
(RMW_RET_INVALID_ARGUMENT == ret));
rcutils_reset_error();

ret = rmw_init(&options, &context);
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(&options);
rmw_ret_t ret = rmw_shutdown(&context);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
ret = rmw_context_fini(&context);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
});

ret = rmw_init(&options, &context);
const char * implementation_identifier = context.implementation_identifier;
context.implementation_identifier = "not-a-real-rmw-implementation-identifier";
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, rmw_shutdown(&context));
context.implementation_identifier = implementation_identifier;
rcutils_reset_error();
}

TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), context_fini_with_bad_arguments) {
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, rmw_context_fini(nullptr));
rcutils_reset_error();

rmw_context_t context = rmw_get_zero_initialized_context();
rmw_ret_t ret = rmw_init(&options, &context);
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rmw_ret_t ret = rmw_shutdown(&context);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
ret = rmw_context_fini(&context);
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
});

const char * implementation_identifier = context.implementation_identifier;
context.implementation_identifier = "not-a-real-rmw-implementation-identifier";
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, rmw_context_fini(&context));
context.implementation_identifier = implementation_identifier;
rcutils_reset_error();

EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, rmw_context_fini(&context));
rcutils_reset_error();
}

TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), init_shutdown) {
rmw_context_t context = rmw_get_zero_initialized_context();
rmw_ret_t ret = rmw_init(&options, &context);
ASSERT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
Expand Down