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 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
86 changes: 80 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,94 @@
# 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;
}

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();
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();

TEST_F(CLASSNAME(TestInitShutdown, RMW_IMPLEMENTATION), init_shutdown) {
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_NE(RMW_RET_OK, rmw_shutdown(&context));
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is there a specific error you are expecting? RMW_RET_ERROR?

Copy link
Contributor Author

@hidmic hidmic Jun 22, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Based on rmw_shutdown() API contract, an RMW implementation could equally return RMW_RET_INVALID_ARGUMENT or RMW_RET_INCORRECT_IMPLEMENTATION. That's why I don't check for a specific return code.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Since you already test the incorrect_implementation error below, wouldn't it make more sense to test the invalid_argument error here? Set context.implementation_identifier to a known valid identifier, then check that it returns invalid argument?

Copy link
Contributor Author

@hidmic hidmic Jun 22, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hmm, problem is that we get into bad initialization territory. Here I deal with the four (4) known context states: zero-initialized, initialized and not shutdown, initialized and shutdown, finalized. Anything outside that is UB. So if we want to be specific about the assertion we have to further clarify API contracts i.e. what it means for a context to be invalid for all rmw implementations.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If you don't want to monkey around with the identifier field to force the invalid argument, then I recommend to at least narrow down the expect statement to only two errors you expect. Something like:

EXPECT_TRUE((ret == RMW_RET_INVALID_ARGUMENT || 
             ret == RMW_RET_INCORRECT_IMPLEMENTATION))

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sure, we can do that. See 9bff7f2

rcutils_reset_error();

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_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