From 17a5e449dd8e5d927ead4d10c4a29f9f537f9544 Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Mon, 18 May 2020 14:03:00 -0300 Subject: [PATCH 1/3] Add test coverage for rmw_init_options API. Signed-off-by: Michel Hidalgo --- rmw_fastrtps_shared_cpp/package.xml | 1 + rmw_fastrtps_shared_cpp/test/CMakeLists.txt | 7 + .../test/test_rmw_init_options.cpp | 198 ++++++++++++++++++ 3 files changed, 206 insertions(+) create mode 100644 rmw_fastrtps_shared_cpp/test/test_rmw_init_options.cpp diff --git a/rmw_fastrtps_shared_cpp/package.xml b/rmw_fastrtps_shared_cpp/package.xml index c716f5966..678337639 100644 --- a/rmw_fastrtps_shared_cpp/package.xml +++ b/rmw_fastrtps_shared_cpp/package.xml @@ -31,6 +31,7 @@ ament_lint_auto ament_lint_common + osrf_testing_tools_cpp ament_cmake diff --git a/rmw_fastrtps_shared_cpp/test/CMakeLists.txt b/rmw_fastrtps_shared_cpp/test/CMakeLists.txt index 19201042a..fd7d467d2 100644 --- a/rmw_fastrtps_shared_cpp/test/CMakeLists.txt +++ b/rmw_fastrtps_shared_cpp/test/CMakeLists.txt @@ -1,4 +1,5 @@ find_package(ament_cmake_gtest REQUIRED) +find_package(osrf_testing_tools_cpp REQUIRED) ament_add_gtest(test_dds_attributes_to_rmw_qos test_dds_attributes_to_rmw_qos.cpp) if(TARGET test_dds_attributes_to_rmw_qos) @@ -11,3 +12,9 @@ if(TARGET test_security_logging) ament_target_dependencies(test_security_logging) target_link_libraries(test_security_logging ${PROJECT_NAME}) endif() + +ament_add_gtest(test_rmw_init_options test_rmw_init_options.cpp) +if(TARGET test_rmw_init_options) + ament_target_dependencies(test_rmw_init_options osrf_testing_tools_cpp rcutils rmw) + target_link_libraries(test_rmw_init_options ${PROJECT_NAME}) +endif() diff --git a/rmw_fastrtps_shared_cpp/test/test_rmw_init_options.cpp b/rmw_fastrtps_shared_cpp/test/test_rmw_init_options.cpp new file mode 100644 index 000000000..4eab9afef --- /dev/null +++ b/rmw_fastrtps_shared_cpp/test/test_rmw_init_options.cpp @@ -0,0 +1,198 @@ +// 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 "rcutils/allocator.h" +#include "rcutils/strdup.h" +#include "rmw/init_options.h" +#include "rmw/security_options.h" +#include "rmw/types.h" + +#include "osrf_testing_tools_cpp/scope_exit.hpp" + +#include "rmw_fastrtps_shared_cpp/rmw_init.hpp" + +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; + +TEST(RMWInitOptionsTest, init_w_invalid_args_fails) { + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + EXPECT_EQ( + RMW_RET_INVALID_ARGUMENT, + 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(); + EXPECT_EQ( + RMW_RET_INVALID_ARGUMENT, + rmw_init_options_init("some_identifier", &options, invalid_allocator)); + rcutils_reset_error(); +} + + +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)) << + 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)) << + rcutils_get_error_string().str; + rcutils_reset_error(); + }); + + EXPECT_EQ( + RMW_RET_INVALID_ARGUMENT, + rmw_init_options_init("some_identifier", &options, allocator)); + rcutils_reset_error(); +} + + +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)) << + 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)) << + rcutils_get_error_string().str; + rcutils_reset_error(); + }); + + EXPECT_EQ("some_identifier", options.implementation_identifier); +} + + +TEST(RMWInitOptionsTest, copy_w_invalid_args_fails) { + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + rmw_init_options_t not_initialized_options = rmw_get_zero_initialized_init_options(); + rmw_init_options_t initialized_options = rmw_get_zero_initialized_init_options(); + + ASSERT_EQ( + RMW_RET_OK, + rmw_init_options_init( + "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)) << + rcutils_get_error_string().str; + rcutils_reset_error(); + }); + + EXPECT_EQ( + RMW_RET_INVALID_ARGUMENT, + rmw_init_options_copy( + "some_identifier", + nullptr, + ¬_initialized_options)); + rcutils_reset_error(); + + EXPECT_EQ( + RMW_RET_INVALID_ARGUMENT, + rmw_init_options_copy( + "some_identifier", + &initialized_options, + nullptr)); + rcutils_reset_error(); + + EXPECT_EQ( + RMW_RET_INCORRECT_RMW_IMPLEMENTATION, + rmw_init_options_copy( + "another_identifier", + &initialized_options, + ¬_initialized_options)); + rcutils_reset_error(); + + EXPECT_EQ( + RMW_RET_INVALID_ARGUMENT, rmw_init_options_copy( + "some_identifier", + &initialized_options, + &initialized_options)); + rcutils_reset_error(); +} + + +TEST(RMWInitOptionsTest, copy) { + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + 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)) << + 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)) << + rcutils_get_error_string().str; + rcutils_reset_error(); + }); + preset_options.instance_id = 23lu; + preset_options.enclave = rcutils_strdup("/test", allocator); + ASSERT_TRUE(preset_options.enclave != nullptr); + preset_options.security_options.security_root_path = rcutils_strdup("/root", allocator); + 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)) << + 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)) << + rcutils_get_error_string().str; + rcutils_reset_error(); + }); + EXPECT_EQ(23lu, options.instance_id); + EXPECT_STREQ("/test", options.enclave); + EXPECT_STREQ("/root", options.security_options.security_root_path); +} + +TEST(RMWInitOptionsTest, fini_w_invalid_args_fails) { + 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(); + 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)) << + 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)) << + rcutils_get_error_string().str; + rcutils_reset_error(); + }); + + EXPECT_EQ( + RMW_RET_INCORRECT_RMW_IMPLEMENTATION, + rmw_init_options_fini("another_identifier", &options)); + rcutils_reset_error(); +} From c879be7bde8609876f533870290051d6bb96b1d3 Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Mon, 18 May 2020 15:24:52 -0300 Subject: [PATCH 2/3] Comment test cases for future reference. Signed-off-by: Michel Hidalgo --- rmw_fastrtps_shared_cpp/test/test_rmw_init_options.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/rmw_fastrtps_shared_cpp/test/test_rmw_init_options.cpp b/rmw_fastrtps_shared_cpp/test/test_rmw_init_options.cpp index 4eab9afef..d1790c86b 100644 --- a/rmw_fastrtps_shared_cpp/test/test_rmw_init_options.cpp +++ b/rmw_fastrtps_shared_cpp/test/test_rmw_init_options.cpp @@ -30,6 +30,7 @@ using rmw_fastrtps_shared_cpp::rmw_init_options_fini; 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)); @@ -37,6 +38,7 @@ TEST(RMWInitOptionsTest, init_w_invalid_args_fails) { 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)); @@ -103,6 +105,7 @@ TEST(RMWInitOptionsTest, copy_w_invalid_args_fails) { rcutils_reset_error(); }); + // Cannot copy from a null options instance. EXPECT_EQ( RMW_RET_INVALID_ARGUMENT, rmw_init_options_copy( @@ -111,6 +114,7 @@ TEST(RMWInitOptionsTest, copy_w_invalid_args_fails) { ¬_initialized_options)); rcutils_reset_error(); + // Cannot copy to a null options instance. EXPECT_EQ( RMW_RET_INVALID_ARGUMENT, rmw_init_options_copy( @@ -119,6 +123,7 @@ TEST(RMWInitOptionsTest, copy_w_invalid_args_fails) { nullptr)); rcutils_reset_error(); + // Cannot copy an options instance if implementation identifiers do not match. EXPECT_EQ( RMW_RET_INCORRECT_RMW_IMPLEMENTATION, rmw_init_options_copy( @@ -127,6 +132,7 @@ TEST(RMWInitOptionsTest, copy_w_invalid_args_fails) { ¬_initialized_options)); rcutils_reset_error(); + // Cannot copy to an already initialized options instance. EXPECT_EQ( RMW_RET_INVALID_ARGUMENT, rmw_init_options_copy( "some_identifier", @@ -173,10 +179,12 @@ TEST(RMWInitOptionsTest, copy) { } 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)); 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)); rcutils_reset_error(); @@ -191,6 +199,7 @@ TEST(RMWInitOptionsTest, fini_w_invalid_args_fails) { rcutils_reset_error(); }); + // Cannot finalize an options instance if implementation identifiers do not match. EXPECT_EQ( RMW_RET_INCORRECT_RMW_IMPLEMENTATION, rmw_init_options_fini("another_identifier", &options)); From 06070cb2477a59923ee170f2aa1dccad4121c186 Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Mon, 18 May 2020 16:01:43 -0300 Subject: [PATCH 3/3] Achieve 100% line coverage for rmw_init.cpp Signed-off-by: Michel Hidalgo --- .../test/test_rmw_init_options.cpp | 32 +++++++++++++++++++ 1 file changed, 32 insertions(+) diff --git a/rmw_fastrtps_shared_cpp/test/test_rmw_init_options.cpp b/rmw_fastrtps_shared_cpp/test/test_rmw_init_options.cpp index d1790c86b..10a7e24b8 100644 --- a/rmw_fastrtps_shared_cpp/test/test_rmw_init_options.cpp +++ b/rmw_fastrtps_shared_cpp/test/test_rmw_init_options.cpp @@ -178,6 +178,38 @@ TEST(RMWInitOptionsTest, copy) { EXPECT_STREQ("/root", options.security_options.security_root_path); } +static void * failing_allocate(size_t size, void * state) +{ + (void)size; + (void)state; + return NULL; +} + +TEST(RMWInitOptionsTest, bad_alloc_on_copy) { + rcutils_allocator_t failing_allocator = rcutils_get_default_allocator(); + failing_allocator.allocate = failing_allocate; + + 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)) << + 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)) << + rcutils_get_error_string().str; + rcutils_reset_error(); + }); + preset_options.enclave = rcutils_strdup("/test", rcutils_get_default_allocator()); + ASSERT_TRUE(preset_options.enclave != nullptr); + + 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)); +} + 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));