From c7cde75a5ddf84ebc89834eb87e66fba0d0222c5 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Wed, 30 Sep 2020 08:17:01 -0400 Subject: [PATCH] Add in more tests for init_options coverage. (#1353) Signed-off-by: Chris Lalancette --- rclcpp/src/rclcpp/init_options.cpp | 2 +- rclcpp/test/CMakeLists.txt | 2 +- rclcpp/test/rclcpp/test_init_options.cpp | 36 ++++++++++++++++++++++++ 3 files changed, 38 insertions(+), 2 deletions(-) diff --git a/rclcpp/src/rclcpp/init_options.cpp b/rclcpp/src/rclcpp/init_options.cpp index f9fd6f5f60..f3b80fba1b 100644 --- a/rclcpp/src/rclcpp/init_options.cpp +++ b/rclcpp/src/rclcpp/init_options.cpp @@ -26,7 +26,7 @@ InitOptions::InitOptions(rcl_allocator_t allocator) *init_options_ = rcl_get_zero_initialized_init_options(); rcl_ret_t ret = rcl_init_options_init(init_options_.get(), allocator); if (RCL_RET_OK != ret) { - rclcpp::exceptions::throw_from_rcl_error(ret, "failed to initialized rcl init options"); + rclcpp::exceptions::throw_from_rcl_error(ret, "failed to initialize rcl init options"); } } diff --git a/rclcpp/test/CMakeLists.txt b/rclcpp/test/CMakeLists.txt index 004979461c..5540a96459 100644 --- a/rclcpp/test/CMakeLists.txt +++ b/rclcpp/test/CMakeLists.txt @@ -282,7 +282,7 @@ endif() ament_add_gtest(test_init_options rclcpp/test_init_options.cpp) if(TARGET test_init_options) ament_target_dependencies(test_init_options "rcl") - target_link_libraries(test_init_options ${PROJECT_NAME}) + target_link_libraries(test_init_options ${PROJECT_NAME} mimick) endif() ament_add_gtest(test_parameter_client rclcpp/test_parameter_client.cpp) if(TARGET test_parameter_client) diff --git a/rclcpp/test/rclcpp/test_init_options.cpp b/rclcpp/test/rclcpp/test_init_options.cpp index 3c0cae739a..1e02084c46 100644 --- a/rclcpp/test/rclcpp/test_init_options.cpp +++ b/rclcpp/test/rclcpp/test_init_options.cpp @@ -14,6 +14,7 @@ #include +#include #include #include @@ -22,6 +23,8 @@ #include "rclcpp/init_options.hpp" +#include "../mocking_utils/patch.hpp" +#include "../utils/rclcpp_gtest_macros.hpp" TEST(TestInitOptions, test_construction) { rcl_allocator_t allocator = rcl_get_default_allocator(); @@ -61,3 +64,36 @@ TEST(TestInitOptions, test_initialize_logging) { EXPECT_FALSE(options.auto_initialize_logging()); } } + +// Required for mocking_utils below +MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, ==) +MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, !=) +MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, <) +MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, >) + +TEST(TestInitOptions, constructor_rcl_init_options_init_failed) { + auto mock = mocking_utils::patch_and_return( + "lib:rclcpp", rcl_init_options_init, RCL_RET_ERROR); + RCLCPP_EXPECT_THROW_EQ( + rclcpp::InitOptions(), + std::runtime_error("failed to initialize rcl init options: error not set")); +} + +TEST(TestInitOptions, constructor_rcl_init_options_copy_failed) { + rcl_init_options_t rcl_opts; + auto mock = mocking_utils::patch_and_return( + "lib:rclcpp", rcl_init_options_copy, RCL_RET_ERROR); + RCLCPP_EXPECT_THROW_EQ( + new rclcpp::InitOptions(rcl_opts), + std::runtime_error("failed to copy rcl init options: error not set")); +} + +TEST(TestInitOptions, copy_constructor_rcl_init_options_copy_failed) { + rclcpp::InitOptions options; + rclcpp::InitOptions options2; + auto mock = mocking_utils::patch_and_return( + "lib:rclcpp", rcl_init_options_copy, RCL_RET_ERROR); + RCLCPP_EXPECT_THROW_EQ( + options2.operator=(options), + std::runtime_error("failed to copy rcl init options: error not set")); +}