Skip to content

Commit

Permalink
Do not use string literals as implementation identifiers in tests. (#402
Browse files Browse the repository at this point in the history
)

Compilers are not bound to overlap storage.

Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
  • Loading branch information
hidmic authored Jun 25, 2020
1 parent 3ac640d commit f5820ff
Showing 1 changed file with 28 additions and 25 deletions.
53 changes: 28 additions & 25 deletions rmw_fastrtps_shared_cpp/test/test_rmw_init_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,20 +28,22 @@ using rmw_fastrtps_shared_cpp::rmw_init_options_init;
using rmw_fastrtps_shared_cpp::rmw_init_options_copy;
using rmw_fastrtps_shared_cpp::rmw_init_options_fini;

static const char * const some_identifier = "some_identifier";

TEST(RMWInitOptionsTest, init_w_invalid_args_fails) {
rcutils_allocator_t allocator = rcutils_get_default_allocator();
// Cannot initialize a null options instance.
EXPECT_EQ(
RMW_RET_INVALID_ARGUMENT,
rmw_init_options_init("some_identifier", nullptr, allocator));
rmw_init_options_init(some_identifier, nullptr, allocator));
rcutils_reset_error();

rmw_init_options_t options = rmw_get_zero_initialized_init_options();
rcutils_allocator_t invalid_allocator = rcutils_get_zero_initialized_allocator();
// Cannot initialize using an invalid allocator.
EXPECT_EQ(
RMW_RET_INVALID_ARGUMENT,
rmw_init_options_init("some_identifier", &options, invalid_allocator));
rmw_init_options_init(some_identifier, &options, invalid_allocator));
rcutils_reset_error();
}

Expand All @@ -50,19 +52,19 @@ TEST(RMWInitOptionsTest, init_twice_fails) {
rmw_init_options_t options = rmw_get_zero_initialized_init_options();
rcutils_allocator_t allocator = rcutils_get_default_allocator();

ASSERT_EQ(RMW_RET_OK, rmw_init_options_init("some_identifier", &options, allocator)) <<
ASSERT_EQ(RMW_RET_OK, rmw_init_options_init(some_identifier, &options, allocator)) <<
rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rcutils_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_init_options_fini("some_identifier", &options)) <<
EXPECT_EQ(RMW_RET_OK, rmw_init_options_fini(some_identifier, &options)) <<
rcutils_get_error_string().str;
rcutils_reset_error();
});

EXPECT_EQ(
RMW_RET_INVALID_ARGUMENT,
rmw_init_options_init("some_identifier", &options, allocator));
rmw_init_options_init(some_identifier, &options, allocator));
rcutils_reset_error();
}

Expand All @@ -71,17 +73,17 @@ TEST(RMWInitOptionsTest, init) {
rmw_init_options_t options = rmw_get_zero_initialized_init_options();
rcutils_allocator_t allocator = rcutils_get_default_allocator();

ASSERT_EQ(RMW_RET_OK, rmw_init_options_init("some_identifier", &options, allocator)) <<
ASSERT_EQ(RMW_RET_OK, rmw_init_options_init(some_identifier, &options, allocator)) <<
rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rcutils_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_init_options_fini("some_identifier", &options)) <<
EXPECT_EQ(RMW_RET_OK, rmw_init_options_fini(some_identifier, &options)) <<
rcutils_get_error_string().str;
rcutils_reset_error();
});

EXPECT_EQ("some_identifier", options.implementation_identifier);
EXPECT_EQ(some_identifier, options.implementation_identifier);
}


Expand All @@ -93,14 +95,14 @@ TEST(RMWInitOptionsTest, copy_w_invalid_args_fails) {
ASSERT_EQ(
RMW_RET_OK,
rmw_init_options_init(
"some_identifier",
some_identifier,
&initialized_options,
allocator)) <<
rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rcutils_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_init_options_fini("some_identifier", &initialized_options)) <<
EXPECT_EQ(RMW_RET_OK, rmw_init_options_fini(some_identifier, &initialized_options)) <<
rcutils_get_error_string().str;
rcutils_reset_error();
});
Expand All @@ -109,7 +111,7 @@ TEST(RMWInitOptionsTest, copy_w_invalid_args_fails) {
EXPECT_EQ(
RMW_RET_INVALID_ARGUMENT,
rmw_init_options_copy(
"some_identifier",
some_identifier,
nullptr,
&not_initialized_options));
rcutils_reset_error();
Expand All @@ -118,7 +120,7 @@ TEST(RMWInitOptionsTest, copy_w_invalid_args_fails) {
EXPECT_EQ(
RMW_RET_INVALID_ARGUMENT,
rmw_init_options_copy(
"some_identifier",
some_identifier,
&initialized_options,
nullptr));
rcutils_reset_error();
Expand All @@ -135,7 +137,7 @@ TEST(RMWInitOptionsTest, copy_w_invalid_args_fails) {
// Cannot copy to an already initialized options instance.
EXPECT_EQ(
RMW_RET_INVALID_ARGUMENT, rmw_init_options_copy(
"some_identifier",
some_identifier,
&initialized_options,
&initialized_options));
rcutils_reset_error();
Expand All @@ -147,12 +149,12 @@ TEST(RMWInitOptionsTest, copy) {
rmw_init_options_t preset_options = rmw_get_zero_initialized_init_options();

rcutils_reset_error();
ASSERT_EQ(RMW_RET_OK, rmw_init_options_init("some_identifier", &preset_options, allocator)) <<
ASSERT_EQ(RMW_RET_OK, rmw_init_options_init(some_identifier, &preset_options, allocator)) <<
rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rcutils_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_init_options_fini("some_identifier", &preset_options)) <<
EXPECT_EQ(RMW_RET_OK, rmw_init_options_fini(some_identifier, &preset_options)) <<
rcutils_get_error_string().str;
rcutils_reset_error();
});
Expand All @@ -163,13 +165,13 @@ TEST(RMWInitOptionsTest, copy) {
ASSERT_TRUE(preset_options.security_options.security_root_path != nullptr);

rmw_init_options_t options = rmw_get_zero_initialized_init_options();
ASSERT_EQ(RMW_RET_OK, rmw_init_options_copy("some_identifier", &preset_options, &options)) <<
ASSERT_EQ(RMW_RET_OK, rmw_init_options_copy(some_identifier, &preset_options, &options)) <<
rcutils_get_error_string().str;

OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rcutils_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_init_options_fini("some_identifier", &options)) <<
EXPECT_EQ(RMW_RET_OK, rmw_init_options_fini(some_identifier, &options)) <<
rcutils_get_error_string().str;
rcutils_reset_error();
});
Expand All @@ -192,12 +194,12 @@ TEST(RMWInitOptionsTest, bad_alloc_on_copy) {
rmw_init_options_t preset_options = rmw_get_zero_initialized_init_options();
ASSERT_EQ(
RMW_RET_OK,
rmw_init_options_init("some_identifier", &preset_options, failing_allocator)) <<
rmw_init_options_init(some_identifier, &preset_options, failing_allocator)) <<
rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rcutils_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_init_options_fini("some_identifier", &preset_options)) <<
EXPECT_EQ(RMW_RET_OK, rmw_init_options_fini(some_identifier, &preset_options)) <<
rcutils_get_error_string().str;
rcutils_reset_error();
});
Expand All @@ -207,33 +209,34 @@ TEST(RMWInitOptionsTest, bad_alloc_on_copy) {
rmw_init_options_t options = rmw_get_zero_initialized_init_options();
EXPECT_EQ(
RMW_RET_BAD_ALLOC,
rmw_init_options_copy("some_identifier", &preset_options, &options));
rmw_init_options_copy(some_identifier, &preset_options, &options));
}

TEST(RMWInitOptionsTest, fini_w_invalid_args_fails) {
// Cannot finalize a null options instance.
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, rmw_init_options_fini("some_identifier", nullptr));
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, rmw_init_options_fini(some_identifier, nullptr));
rcutils_reset_error();

rmw_init_options_t options = rmw_get_zero_initialized_init_options();
// Cannot finalize an options instance that has not been initialized.
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, rmw_init_options_fini("some_identifier", &options));
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, rmw_init_options_fini(some_identifier, &options));
rcutils_reset_error();

rcutils_allocator_t allocator = rcutils_get_default_allocator();
ASSERT_EQ(RMW_RET_OK, rmw_init_options_init("some_identifier", &options, allocator)) <<
ASSERT_EQ(RMW_RET_OK, rmw_init_options_init(some_identifier, &options, allocator)) <<
rcutils_get_error_string().str;
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
{
rcutils_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_init_options_fini("some_identifier", &options)) <<
EXPECT_EQ(RMW_RET_OK, rmw_init_options_fini(some_identifier, &options)) <<
rcutils_get_error_string().str;
rcutils_reset_error();
});

// Cannot finalize an options instance if implementation identifiers do not match.
const char * const another_identifier = "another_identifier";
EXPECT_EQ(
RMW_RET_INCORRECT_RMW_IMPLEMENTATION,
rmw_init_options_fini("another_identifier", &options));
rmw_init_options_fini(another_identifier, &options));
rcutils_reset_error();
}

0 comments on commit f5820ff

Please sign in to comment.