From 89d7d99ca19ebe2e4dfb0723b7029fd8fae1ac6f Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Wed, 5 Aug 2020 20:02:59 -0300 Subject: [PATCH 01/10] Complete subscription test coverage. Signed-off-by: Michel Hidalgo --- rcl/package.xml | 1 + rcl/test/CMakeLists.txt | 3 +- rcl/test/rcl/mocking_utils/patch.hpp | 373 +++++++++++++++++++++++++ rcl/test/rcl/test_subscription.cpp | 392 ++++++++++++++++++++++++--- 4 files changed, 729 insertions(+), 40 deletions(-) create mode 100644 rcl/test/rcl/mocking_utils/patch.hpp diff --git a/rcl/package.xml b/rcl/package.xml index a28382aff..014efbc4c 100644 --- a/rcl/package.xml +++ b/rcl/package.xml @@ -34,6 +34,7 @@ launch_testing_ament_cmake osrf_testing_tools_cpp test_msgs + mimick_vendor rcl_logging_packages diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index c177d2ed2..fcc4eafab 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -1,6 +1,7 @@ find_package(ament_cmake_gtest REQUIRED) find_package(launch_testing_ament_cmake REQUIRED) +find_package(mimick_vendor REQUIRED) find_package(test_msgs REQUIRED) find_package(mimick_vendor REQUIRED) @@ -225,7 +226,7 @@ function(test_target_function) SRCS rcl/test_subscription.cpp rcl/wait_for_entity_helpers.cpp ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} - LIBRARIES ${PROJECT_NAME} + LIBRARIES ${PROJECT_NAME} mimick AMENT_DEPENDENCIES ${rmw_implementation} "osrf_testing_tools_cpp" "test_msgs" ) if(rmw_implementation STREQUAL "rmw_fastrtps_cpp" OR diff --git a/rcl/test/rcl/mocking_utils/patch.hpp b/rcl/test/rcl/mocking_utils/patch.hpp new file mode 100644 index 000000000..bc62306d4 --- /dev/null +++ b/rcl/test/rcl/mocking_utils/patch.hpp @@ -0,0 +1,373 @@ +// 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. + +#ifndef RCL__MOCKING_UTILS__PATCH_HPP_ +#define RCL__MOCKING_UTILS__PATCH_HPP_ + +#define MOCKING_UTILS_SUPPORT_VA_LIST +#if (defined(__aarch64__) || defined(__arm__) || defined(_M_ARM) || defined(__thumb__)) +// In ARM machines, va_list does not define comparison operators +// nor the compiler allows defining them via operator overloads. +// Thus, Mimick argument matching code will not compile. +#undef MOCKING_UTILS_SUPPORT_VA_LIST +#endif + +#ifdef MOCKING_UTILS_SUPPORT_VA_LIST +#include +#endif + +#include +#include +#include +#include + +#include "mimick/mimick.h" +#include "rcutils/macros.h" + +namespace mocking_utils +{ + +/// Mimick specific traits for each mocking_utils::Patch instance. +/** + * \tparam ID Numerical identifier of the patch. Ought to be unique. + * \tparam SignatureT Type of the symbol to be patched. +*/ +template +struct PatchTraits; + +/// Traits specialization for ReturnT(void) free functions. +/** + * \tparam ID Numerical identifier of the patch. Ought to be unique. + * \tparam ReturnT Return value type. + */ +template +struct PatchTraits +{ + mmk_mock_define(mock_type, ReturnT); +}; + +/// Traits specialization for ReturnT(ArgT0) free functions. +/** + * \tparam ID Numerical identifier of the patch. Ought to be unique. + * \tparam ReturnT Return value type. + * \tparam ArgT0 Argument type. + */ +template +struct PatchTraits +{ + mmk_mock_define(mock_type, ReturnT, ArgT0); +}; + +/// Traits specialization for ReturnT(ArgT0, ArgT1) free functions. +/** + * \tparam ID Numerical identifier of the patch. Ought to be unique. + * \tparam ReturnT Return value type. + * \tparam ArgTx Argument types. + */ +template +struct PatchTraits +{ + mmk_mock_define(mock_type, ReturnT, ArgT0, ArgT1); +}; + +/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2) free functions. +/** + * \tparam ID Numerical identifier of the patch. Ought to be unique. + * \tparam ReturnT Return value type. + * \tparam ArgTx Argument types. + */ +template +struct PatchTraits +{ + mmk_mock_define(mock_type, ReturnT, ArgT0, ArgT1, ArgT2); +}; + +/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2, ArgT3) free functions. +/** + * \tparam ID Numerical identifier of the patch. Ought to be unique. + * \tparam ReturnT Return value type. + * \tparam ArgTx Argument types. + */ +template +struct PatchTraits +{ + mmk_mock_define(mock_type, ReturnT, ArgT0, ArgT1, ArgT2, ArgT3); +}; + +/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4) +/// free functions. +/** + * \tparam ID Numerical identifier of the patch. Ought to be unique. + * \tparam ReturnT Return value type. + * \tparam ArgTx Argument types. + */ +template +struct PatchTraits +{ + mmk_mock_define(mock_type, ReturnT, ArgT0, ArgT1, ArgT2, ArgT3, ArgT4); +}; + +/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5) +/// free functions. +/** + * \tparam ID Numerical identifier of the patch. Ought to be unique. + * \tparam ReturnT Return value type. + * \tparam ArgTx Argument types. + */ +template +struct PatchTraits +{ + mmk_mock_define( + mock_type, ReturnT, ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5); +}; + +/// Generic trampoline to wrap generalized callables in plain functions. +/** + * \tparam ID Numerical identifier of this trampoline. Ought to be unique. + * \tparam SignatureT Type of the symbol this trampoline replaces. + */ +template +struct Trampoline; + +/// Trampoline specialization for free functions. +template +struct Trampoline +{ + static ReturnT base(ArgTs... args) + { + return target(std::forward(args)...); + } + + static std::function target; +}; + +template +std::function +Trampoline::target; + +/// Setup trampoline with the given @p target. +/** + * \param[in] target Callable that this trampoline will target. + * \return the plain base function of this trampoline. + * + * \tparam ID Numerical identifier of this trampoline. Ought to be unique. + * \tparam SignatureT Type of the symbol this trampoline replaces. + */ +template +auto prepare_trampoline(std::function target) +{ + Trampoline::target = target; + return Trampoline::base; +} + +/// Patch class for binary API mocking +/** + * Built on top of Mimick, to enable symbol mocking on a per dynamically + * linked binary object basis. + * + * \tparam ID Numerical identifier for this patch. Ought to be unique. + * \tparam SignatureT Type of the symbol to be patched. + */ +template +class Patch; + +/// Patch specialization for ReturnT(ArgTs...) free functions. +/** + * \tparam ID Numerical identifier for this patch. Ought to be unique. + * \tparam ReturnT Return value type. + * \tparam ArgTs Argument types. + */ +template +class Patch +{ +public: + using mock_type = typename PatchTraits::mock_type; + + /// Construct a patch. + /** + * \param[in] target Symbol target string, using Mimick syntax + * i.e. "symbol(@scope)?", where scope may be "self" to target the current + * binary, "lib:library_name" to target a given library, "file:path/to/library" + * to target a given file, or "sym:other_symbol" to target the first library + * that defines said symbol. + * \param[in] proxy An indirection to call the target function. + * This indirection must ensure this call goes through the function's + * trampoline, as setup by the dynamic linker. + * \return a mocking_utils::Patch instance. + */ + explicit Patch(const std::string & target, std::function proxy) + : target_(target), proxy_(proxy) + { + } + + // Copy construction and assignment are disabled. + Patch(const Patch &) = delete; + Patch & operator=(const Patch &) = delete; + + Patch(Patch && other) + { + mock_ = other.mock_; + other.mock_ = nullptr; + } + + Patch & operator=(Patch && other) + { + if (mock_) { + mmk_reset(mock_); + } + mock_ = other.mock_; + other.mock_ = nullptr; + } + + ~Patch() + { + if (mock_) { + mmk_reset(mock_); + } + } + + /// Inject a @p replacement for the patched function. + Patch & then_call(std::function replacement) & + { + replace_with(replacement); + return *this; + } + + /// Inject a @p replacement for the patched function. + Patch && then_call(std::function replacement) && + { + replace_with(replacement); + return std::move(*this); + } + +private: + // Helper for template parameter pack expansion using `mmk_any` + // macro as pattern. + template + T any() {return mmk_any(T);} + + void replace_with(std::function replacement) + { + if (mock_) { + throw std::logic_error("Cannot configure patch more than once"); + } + auto type_erased_trampoline = + reinterpret_cast(prepare_trampoline(replacement)); + auto MMK_MANGLE(mock_type, create) = + PatchTraits::MMK_MANGLE(mock_type, create); + mock_ = mmk_mock(target_.c_str(), mock_type); + mmk_when(proxy_(any()...), .then_call = type_erased_trampoline); + } + + mock_type mock_{nullptr}; + std::string target_; + std::function proxy_; +}; + +/// Make a patch for a `target` function. +/** + * Useful for type deduction during \ref mocking_utils::Patch construction. + * + * \param[in] target Symbol target string, using Mimick syntax. + * \param[in] proxy An indirection to call the target function. + * \return a mocking_utils::Patch instance. + * + * \tparam ID Numerical identifier for this patch. Ought to be unique. + * \tparam SignatureT Type of the function to be patched. + * + * \sa mocking_utils::Patch for further reference. + */ +template +auto make_patch(const std::string & target, std::function proxy) +{ + return Patch(target, proxy); +} + +/// Define a dummy operator `op` for a given `type`. +/** + * Useful to enable patching functions that take arguments whose types + * do not define basic comparison operators, as required by Mimick. +*/ +#define MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(type_, op) \ + template \ + typename std::enable_if::value, bool>::type \ + operator op(const T &, const T &) { \ + return false; \ + } + +/// Get the exact \ref mocking_utils::Patch type for a given `id` and `function`. +/** + * Useful to avoid ignored attribute warnings when using the \b decltype operator. + */ +#define MOCKING_UTILS_PATCH_TYPE(id, function) \ + decltype(mocking_utils::make_patch("", nullptr)) + +/// A transparent forwarding proxy to a given `function`. +/** + * Useful to ensure a call to `function` goes through its trampoline. + */ +#define MOCKING_UTILS_PATCH_PROXY(function) \ + [] (auto && ... args)->decltype(auto) { \ + return function(std::forward(args)...); \ + } + +/// Compute a Mimick symbol target string based on which `function` is to be patched +/// in which `scope`. +#define MOCKING_UTILS_PATCH_TARGET(scope, function) \ + (std::string(RCUTILS_STRINGIFY(function)) + "@" + (scope)) + +/// Prepare a mocking_utils::Patch for patching a `function` in a given `scope` +/// but defer applying any changes. +#define prepare_patch(scope, function) \ + make_patch<__COUNTER__, decltype(function)>( \ + MOCKING_UTILS_PATCH_TARGET(scope, function), MOCKING_UTILS_PATCH_PROXY(function) \ + ) + +/// Patch a `function` with a used-provided `replacement` in a given `scope`. +#define patch(scope, function, replacement) \ + prepare_patch(scope, function).then_call(replacement) + +/// Patch a `function` to always yield a given `return_code` in a given `scope`. +#define patch_and_return(scope, function, return_code) \ + patch(scope, function, [&](auto && ...) {return return_code;}) + +/// Patch a `function` to execute normally but always yield a given `return_code` +/// in a given `scope`. +#define inject_on_return(scope, function, return_code) \ + patch( \ + scope, function, ([&, base = function](auto && ... __args) { \ + static_cast(base(std::forward(__args)...)); \ + return return_code; \ + })) + +} // namespace mocking_utils + +#ifdef MOCKING_UTILS_SUPPORT_VA_LIST +// Define dummy comparison operators for C standard va_list type +MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(va_list, ==) +MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(va_list, !=) +MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(va_list, <) +MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(va_list, >) +#endif + +#endif // RCL__MOCKING_UTILS__PATCH_HPP_ diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index 2dcbd4490..10cf5927a 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -20,6 +20,8 @@ #include "rcl/subscription.h" #include "rcl/rcl.h" +#include "rmw/rmw.h" +#include "rmw/validate_full_topic_name.h" #include "test_msgs/msg/basic_types.h" #include "test_msgs/msg/strings.h" @@ -30,6 +32,7 @@ #include "wait_for_entity_helpers.hpp" #include "./allocator_testing_utils.h" +#include "./mocking_utils/patch.hpp" #ifdef RMW_IMPLEMENTATION # define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX @@ -143,6 +146,11 @@ TEST_F( rcl_reset_error(); } +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, >) + // Bad arguments for init and fini TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_bad_init) { const rosidl_message_type_support_t * ts = @@ -153,12 +161,16 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription rcl_node_t invalid_node = rcl_get_zero_initialized_node(); ASSERT_FALSE(rcl_node_is_valid_except_context(&invalid_node)); + rcl_reset_error(); + EXPECT_EQ(nullptr, rcl_node_get_rmw_handle(&invalid_node)); + rcl_reset_error(); EXPECT_EQ( RCL_RET_NODE_INVALID, rcl_subscription_init(&subscription, nullptr, ts, topic, &subscription_options)); rcl_reset_error(); + EXPECT_EQ( RCL_RET_NODE_INVALID, rcl_subscription_init(&subscription, &invalid_node, ts, topic, &subscription_options)); @@ -173,9 +185,57 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription EXPECT_EQ(RCL_RET_TOPIC_NAME_INVALID, ret) << rcl_get_error_string().str; rcl_reset_error(); - rcl_subscription_options_t bad_subscription_options = rcl_subscription_get_default_options(); - bad_subscription_options.allocator = get_failing_allocator(); - ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &bad_subscription_options); + { + rcutils_ret_t rcutils_string_map_init_returns = RCUTILS_RET_BAD_ALLOC; + auto mock = mocking_utils::patch_and_return( + "lib:rcl", rcutils_string_map_init, rcutils_string_map_init_returns); + ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); + EXPECT_EQ(RCL_RET_BAD_ALLOC, ret); + rcl_reset_error(); + + rcutils_string_map_init_returns = RCUTILS_RET_ERROR; + ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); + EXPECT_EQ(RCL_RET_ERROR, ret); + rcl_reset_error(); + } + { + auto mock = + mocking_utils::inject_on_return("lib:rcl", rcutils_string_map_fini, RCUTILS_RET_ERROR); + ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); + EXPECT_EQ(RCL_RET_ERROR, ret); + rcl_reset_error(); + } + { + rmw_ret_t rmw_validate_full_topic_name_returns = RMW_RET_OK; + auto mock = mocking_utils::patch( + "lib:rcl", rmw_validate_full_topic_name, + [&](auto, int * result, auto) { + *result = RMW_TOPIC_INVALID_TOO_LONG; + return rmw_validate_full_topic_name_returns; + }); + ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); + EXPECT_EQ(RCL_RET_TOPIC_NAME_INVALID, ret); + rcl_reset_error(); + + rmw_validate_full_topic_name_returns = RMW_RET_ERROR; + ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); + EXPECT_EQ(RCL_RET_ERROR, ret); + rcl_reset_error(); + } + { + auto mock = + mocking_utils::patch_and_return("lib:rcl", rmw_create_subscription, nullptr); + ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); + EXPECT_EQ(RCL_RET_ERROR, ret); + rcl_reset_error(); + } + { + auto mock = + mocking_utils::patch_and_return("lib:rcl", rmw_subscription_get_actual_qos, RMW_RET_ERROR); + ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); + EXPECT_EQ(RCL_RET_ERROR, ret); + rcl_reset_error(); + } ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -184,13 +244,20 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription EXPECT_EQ(RCL_RET_ALREADY_INIT, ret) << rcl_get_error_string().str; rcl_reset_error(); + EXPECT_EQ(RCL_RET_SUBSCRIPTION_INVALID, rcl_subscription_fini(nullptr, this->node_ptr)); + rcl_reset_error(); EXPECT_EQ(RCL_RET_NODE_INVALID, rcl_subscription_fini(&subscription, nullptr)); rcl_reset_error(); EXPECT_EQ(RCL_RET_NODE_INVALID, rcl_subscription_fini(&subscription, &invalid_node)); rcl_reset_error(); - ret = rcl_subscription_fini(&subscription, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + auto mock = + mocking_utils::inject_on_return("lib:rcl", rmw_destroy_subscription, RMW_RET_ERROR); + EXPECT_EQ(RCL_RET_ERROR, rcl_subscription_fini(&subscription, this->node_ptr)); + rcl_reset_error(); + + // Make sure finalization completed anyways. + ASSERT_EQ(NULL, subscription.impl); } /* Basic nominal test of a subscription @@ -528,6 +595,139 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription } } +/* Test for all failure modes in subscription take with loaned messages function. + */ +TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_bad_take_loaned_message) { + const char * topic = "rcl_loan"; + const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); + rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); + + rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); + rmw_ret_t ret = rcl_subscription_init( + &subscription, this->node_ptr, ts, topic, + &subscription_options); + ASSERT_EQ(RMW_RET_OK, ret) << rcl_get_error_string().str; + + test_msgs__msg__Strings * loaned_message = nullptr; + void ** type_erased_loaned_message_pointer = reinterpret_cast(&loaned_message); + EXPECT_EQ( + RCL_RET_SUBSCRIPTION_INVALID, rcl_take_loaned_message( + nullptr, type_erased_loaned_message_pointer, nullptr, nullptr)); + rcl_reset_error(); + + EXPECT_EQ( + RCL_RET_INVALID_ARGUMENT, + rcl_take_loaned_message(&subscription, nullptr, nullptr, nullptr)); + rcl_reset_error(); + + test_msgs__msg__Strings dummy_message; + loaned_message = &dummy_message; + EXPECT_EQ( + RCL_RET_INVALID_ARGUMENT, rcl_take_loaned_message( + &subscription, type_erased_loaned_message_pointer, nullptr, nullptr)); + rcl_reset_error(); + loaned_message = nullptr; + + { + rmw_ret_t rmw_take_loaned_message_with_info_returns = RMW_RET_OK; + auto mock = mocking_utils::patch( + "lib:rcl", rmw_take_loaned_message_with_info, + [&](auto, auto, bool * taken, auto && ...) { + *taken = false; + return rmw_take_loaned_message_with_info_returns; + }); + + EXPECT_EQ( + RCL_RET_SUBSCRIPTION_TAKE_FAILED, rcl_take_loaned_message( + &subscription, type_erased_loaned_message_pointer, nullptr, nullptr)); + rcl_reset_error(); + + rmw_take_loaned_message_with_info_returns = RMW_RET_BAD_ALLOC; + EXPECT_EQ( + RCL_RET_BAD_ALLOC, rcl_take_loaned_message( + &subscription, type_erased_loaned_message_pointer, nullptr, nullptr)); + rcl_reset_error(); + + rmw_take_loaned_message_with_info_returns = RMW_RET_UNSUPPORTED; + EXPECT_EQ( + RCL_RET_UNSUPPORTED, rcl_take_loaned_message( + &subscription, type_erased_loaned_message_pointer, nullptr, nullptr)); + rcl_reset_error(); + + rmw_take_loaned_message_with_info_returns = RMW_RET_ERROR; + EXPECT_EQ( + RCL_RET_ERROR, rcl_take_loaned_message( + &subscription, type_erased_loaned_message_pointer, nullptr, nullptr)); + rcl_reset_error(); + } + + EXPECT_EQ( + RCL_RET_OK, + rcl_subscription_fini(&subscription, this->node_ptr)) << rcl_get_error_string().str; +} + +/* Test for all failure modes in subscription return loaned messages function. + */ +TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_bad_return_loaned_message) { + const char * topic = "rcl_loan"; + const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); + rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); + rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); + test_msgs__msg__Strings dummy_message; + test_msgs__msg__Strings__init(&dummy_message); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + test_msgs__msg__Strings__fini(&dummy_message); + }); + void * loaned_message = &dummy_message; + + EXPECT_EQ( + RCL_RET_SUBSCRIPTION_INVALID, + rcl_return_loaned_message_from_subscription(nullptr, loaned_message)); + rcl_reset_error(); + + EXPECT_EQ( + RCL_RET_SUBSCRIPTION_INVALID, + rcl_return_loaned_message_from_subscription(&subscription, loaned_message)); + rcl_reset_error(); + + rmw_ret_t ret = rcl_subscription_init( + &subscription, this->node_ptr, ts, topic, + &subscription_options); + ASSERT_EQ(RMW_RET_OK, ret) << rcl_get_error_string().str; + + EXPECT_EQ( + RCL_RET_INVALID_ARGUMENT, rcl_return_loaned_message_from_subscription(&subscription, nullptr)); + rcl_reset_error(); + + { + rmw_ret_t rmw_return_loaned_message_from_subscription_returns = RMW_RET_OK; + auto mock = mocking_utils::patch_and_return( + "lib:rcl", rmw_return_loaned_message_from_subscription, + rmw_return_loaned_message_from_subscription_returns); + + EXPECT_EQ( + RCL_RET_OK, rcl_return_loaned_message_from_subscription(&subscription, loaned_message)) << + rcl_get_error_string().str; + + rmw_return_loaned_message_from_subscription_returns = RMW_RET_UNSUPPORTED; + EXPECT_EQ( + RCL_RET_UNSUPPORTED, rcl_return_loaned_message_from_subscription( + &subscription, + loaned_message)); + rcl_reset_error(); + + rmw_return_loaned_message_from_subscription_returns = RMW_RET_ERROR; + EXPECT_EQ( + RCL_RET_ERROR, rcl_return_loaned_message_from_subscription(&subscription, loaned_message)); + rcl_reset_error(); + } + + EXPECT_EQ( + RCL_RET_OK, + rcl_subscription_fini(&subscription, this->node_ptr)) << rcl_get_error_string().str; +} + /* Basic test for subscription loan functions */ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_loaned) { @@ -565,28 +765,54 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription } ASSERT_TRUE(wait_for_subscription_to_be_ready(&subscription, context_ptr, 10, 100)); { - test_msgs__msg__Strings msg; - test_msgs__msg__Strings * msg_loaned; - test_msgs__msg__Strings__init(&msg); - OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( - { - test_msgs__msg__Strings__fini(&msg); - }); - + auto patch_take = + mocking_utils::prepare_patch("lib:rcl", rmw_take_loaned_message_with_info); + auto patch_return = + mocking_utils::prepare_patch("lib:rcl", rmw_return_loaned_message_from_subscription); // Only if rmw supports the functionality - if (rcl_subscription_can_loan_messages(&subscription)) { - ret = rcl_take_loaned_message( - &subscription, reinterpret_cast(&msg_loaned), nullptr, nullptr); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ASSERT_EQ( - std::string(test_string), - std::string(msg_loaned->string_value.data, msg_loaned->string_value.size)); - } else { - ret = rcl_take(&subscription, &msg, nullptr, nullptr); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - ASSERT_EQ( - std::string(test_string), std::string(msg.string_value.data, msg.string_value.size)); + if (!rcl_subscription_can_loan_messages(&subscription)) { + patch_take.then_call( + [](const rmw_subscription_t * subscription, + void ** loaned_message, bool * taken, + rmw_message_info_t * message_info, + rmw_subscription_allocation_t * allocation) + { + auto msg = new(std::nothrow) test_msgs__msg__Strings{}; + if (!msg) { + return RMW_RET_BAD_ALLOC; + } + test_msgs__msg__Strings__init(msg); + *loaned_message = static_cast(msg); + rmw_ret_t ret = rmw_take_with_info( + subscription, + *loaned_message, + taken, + message_info, + allocation); + if (RMW_RET_OK != ret) { + delete msg; + } + return ret; + }); + patch_return.then_call( + [](auto, void * loaned_message) { + auto msg = reinterpret_cast(loaned_message); + test_msgs__msg__Strings__fini(msg); + delete msg; + + return RMW_RET_OK; + }); } + + test_msgs__msg__Strings * msg_loaned = nullptr; + ret = rcl_take_loaned_message( + &subscription, reinterpret_cast(&msg_loaned), nullptr, nullptr); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + EXPECT_EQ( + std::string(test_string), + std::string(msg_loaned->string_value.data, msg_loaned->string_value.size)); + ret = rcl_return_loaned_message_from_subscription(&subscription, msg_loaned); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } } @@ -629,9 +855,27 @@ TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_subscrip RCL_RET_SUBSCRIPTION_INVALID, rcl_take(&subscription_zero_init, &msg, &message_info, nullptr)); rcl_reset_error(); + rmw_ret_t rmw_take_with_info_returns = RMW_RET_OK; + auto mock = mocking_utils::patch( + "lib:rcl", rmw_take_with_info, + [&](auto, auto, bool * taken, auto...) { + *taken = false; + return rmw_take_with_info_returns; + }); + EXPECT_EQ( RCL_RET_SUBSCRIPTION_TAKE_FAILED, rcl_take(&subscription, &msg, &message_info, nullptr)); rcl_reset_error(); + + rmw_take_with_info_returns = RMW_RET_BAD_ALLOC; + EXPECT_EQ( + RCL_RET_BAD_ALLOC, rcl_take(&subscription, &msg, &message_info, nullptr)); + rcl_reset_error(); + + rmw_take_with_info_returns = RMW_RET_ERROR; + EXPECT_EQ( + RCL_RET_ERROR, rcl_take(&subscription, &msg, &message_info, nullptr)); + rcl_reset_error(); } /* bad take_serialized @@ -640,10 +884,11 @@ TEST_F( CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_subscription_bad_take_serialized) { rcl_serialized_message_t serialized_msg = rmw_get_zero_initialized_serialized_message(); - size_t initial_capacity_ser = 0u; + size_t initial_serialization_capacity = 0u; ASSERT_EQ( RCL_RET_OK, rmw_serialized_message_init( - &serialized_msg, initial_capacity_ser, &allocator)) << rcl_get_error_string().str; + &serialized_msg, initial_serialization_capacity, &allocator)) << + rcl_get_error_string().str; EXPECT_EQ( RCL_RET_SUBSCRIPTION_INVALID, @@ -654,10 +899,35 @@ TEST_F( rcl_take_serialized_message(&subscription_zero_init, &serialized_msg, nullptr, nullptr)); rcl_reset_error(); + EXPECT_EQ( + RCL_RET_INVALID_ARGUMENT, + rcl_take_serialized_message(&subscription, nullptr, nullptr, nullptr)); + rcl_reset_error(); + + rmw_ret_t rmw_take_serialized_message_with_info_returns = RMW_RET_OK; + auto mock = mocking_utils::patch( + "lib:rcl", rmw_take_serialized_message_with_info, + [&](auto, auto, bool * taken, auto...) { + *taken = false; + return rmw_take_serialized_message_with_info_returns; + }); + EXPECT_EQ( RCL_RET_SUBSCRIPTION_TAKE_FAILED, rcl_take_serialized_message(&subscription, &serialized_msg, nullptr, nullptr)); rcl_reset_error(); + + rmw_take_serialized_message_with_info_returns = RMW_RET_BAD_ALLOC; + EXPECT_EQ( + RCL_RET_BAD_ALLOC, + rcl_take_serialized_message(&subscription, &serialized_msg, nullptr, nullptr)); + rcl_reset_error(); + + rmw_take_serialized_message_with_info_returns = RMW_RET_ERROR; + EXPECT_EQ( + RCL_RET_ERROR, + rcl_take_serialized_message(&subscription, &serialized_msg, nullptr, nullptr)); + rcl_reset_error(); } /* Bad arguments take_sequence @@ -705,24 +975,72 @@ TEST_F( rcl_take_sequence(&subscription, seq_size, &messages, &message_infos_short, nullptr)); rcl_reset_error(); - // This test fails for rmw_cyclonedds_cpp function rmw_take_sequence - // Tracked here: https://github.com/ros2/rmw_cyclonedds/issues/193 - /* + EXPECT_EQ( + RCL_RET_INVALID_ARGUMENT, + rcl_take_sequence(&subscription, seq_size, nullptr, &message_infos, nullptr)); + rcl_reset_error(); + + EXPECT_EQ( + RCL_RET_INVALID_ARGUMENT, + rcl_take_sequence(&subscription, seq_size, &messages, nullptr, nullptr)); + rcl_reset_error(); + + rmw_ret_t rmw_take_sequence_returns = RMW_RET_OK; + auto mock = mocking_utils::patch( + "lib:rcl", rmw_take_sequence, + [&](auto, auto, auto, auto, size_t * taken, auto) { + *taken = 0u; + return rmw_take_sequence_returns; + }); + EXPECT_EQ( RCL_RET_SUBSCRIPTION_TAKE_FAILED, rcl_take_sequence(&subscription, seq_size, &messages, &message_infos, nullptr)); rcl_reset_error(); - */ + + rmw_take_sequence_returns = RMW_RET_BAD_ALLOC; + EXPECT_EQ( + RCL_RET_BAD_ALLOC, + rcl_take_sequence(&subscription, seq_size, &messages, &message_infos, nullptr)); + rcl_reset_error(); + + rmw_take_sequence_returns = RMW_RET_ERROR; + EXPECT_EQ( + RCL_RET_ERROR, + rcl_take_sequence(&subscription, seq_size, &messages, &message_infos, nullptr)); + rcl_reset_error(); } -/* Using bad arguments subscription methods +/* Test for all failure modes in subscription get_publisher_count function. */ -TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_subscription_bad_argument) { - size_t pub_count = 0; +TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_bad_get_publisher_count) { + size_t publisher_count = 0; + EXPECT_EQ( + RCL_RET_SUBSCRIPTION_INVALID, + rcl_subscription_get_publisher_count(nullptr, &publisher_count)); + rcl_reset_error(); + + EXPECT_EQ( + RCL_RET_SUBSCRIPTION_INVALID, + rcl_subscription_get_publisher_count(&subscription_zero_init, &publisher_count)); + rcl_reset_error(); EXPECT_EQ( - RCL_RET_SUBSCRIPTION_INVALID, rcl_subscription_get_publisher_count(nullptr, &pub_count)); + RCL_RET_INVALID_ARGUMENT, + rcl_subscription_get_publisher_count(&subscription, nullptr)); rcl_reset_error(); + + auto mock = mocking_utils::patch_and_return( + "lib:rcl", rmw_subscription_count_matched_publishers, RMW_RET_ERROR); + EXPECT_EQ( + RCL_RET_ERROR, + rcl_subscription_get_publisher_count(&subscription, &publisher_count)); + rcl_reset_error(); +} + +/* Using bad arguments subscription methods + */ +TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_subscription_bad_argument) { EXPECT_EQ(NULL, rcl_subscription_get_actual_qos(nullptr)); rcl_reset_error(); EXPECT_FALSE(rcl_subscription_can_loan_messages(nullptr)); @@ -734,10 +1052,6 @@ TEST_F(CLASSNAME(TestSubscriptionFixtureInit, RMW_IMPLEMENTATION), test_subscrip EXPECT_EQ(NULL, rcl_subscription_get_options(nullptr)); rcl_reset_error(); - EXPECT_EQ( - RCL_RET_SUBSCRIPTION_INVALID, - rcl_subscription_get_publisher_count(&subscription_zero_init, &pub_count)); - rcl_reset_error(); EXPECT_EQ(NULL, rcl_subscription_get_actual_qos(&subscription_zero_init)); rcl_reset_error(); EXPECT_FALSE(rcl_subscription_can_loan_messages(&subscription_zero_init)); From 2546414d7890b5448f1917f376b95b4b6d243a27 Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Tue, 11 Aug 2020 11:04:53 -0300 Subject: [PATCH 02/10] Address peer review comments. Signed-off-by: Michel Hidalgo --- rcl/test/rcl/test_subscription.cpp | 32 ++++++++++++++++++------------ 1 file changed, 19 insertions(+), 13 deletions(-) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index 10cf5927a..8cbb042df 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -610,21 +610,23 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_bad_take_loa test_msgs__msg__Strings * loaned_message = nullptr; void ** type_erased_loaned_message_pointer = reinterpret_cast(&loaned_message); + rmw_message_info_t * message_info = nullptr; // is a valid argument + rmw_subscription_allocation_t * allocation = nullptr; // is a valid argument EXPECT_EQ( RCL_RET_SUBSCRIPTION_INVALID, rcl_take_loaned_message( - nullptr, type_erased_loaned_message_pointer, nullptr, nullptr)); + nullptr, type_erased_loaned_message_pointer, message_info, allocation)); rcl_reset_error(); EXPECT_EQ( RCL_RET_INVALID_ARGUMENT, - rcl_take_loaned_message(&subscription, nullptr, nullptr, nullptr)); + rcl_take_loaned_message(&subscription, nullptr, message_info, allocation)); rcl_reset_error(); test_msgs__msg__Strings dummy_message; loaned_message = &dummy_message; EXPECT_EQ( RCL_RET_INVALID_ARGUMENT, rcl_take_loaned_message( - &subscription, type_erased_loaned_message_pointer, nullptr, nullptr)); + &subscription, type_erased_loaned_message_pointer, message_info, allocation)); rcl_reset_error(); loaned_message = nullptr; @@ -639,25 +641,25 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_bad_take_loa EXPECT_EQ( RCL_RET_SUBSCRIPTION_TAKE_FAILED, rcl_take_loaned_message( - &subscription, type_erased_loaned_message_pointer, nullptr, nullptr)); + &subscription, type_erased_loaned_message_pointer, message_info, allocation)); rcl_reset_error(); rmw_take_loaned_message_with_info_returns = RMW_RET_BAD_ALLOC; EXPECT_EQ( RCL_RET_BAD_ALLOC, rcl_take_loaned_message( - &subscription, type_erased_loaned_message_pointer, nullptr, nullptr)); + &subscription, type_erased_loaned_message_pointer, message_info, allocation)); rcl_reset_error(); rmw_take_loaned_message_with_info_returns = RMW_RET_UNSUPPORTED; EXPECT_EQ( RCL_RET_UNSUPPORTED, rcl_take_loaned_message( - &subscription, type_erased_loaned_message_pointer, nullptr, nullptr)); + &subscription, type_erased_loaned_message_pointer, message_info, allocation)); rcl_reset_error(); rmw_take_loaned_message_with_info_returns = RMW_RET_ERROR; EXPECT_EQ( RCL_RET_ERROR, rcl_take_loaned_message( - &subscription, type_erased_loaned_message_pointer, nullptr, nullptr)); + &subscription, type_erased_loaned_message_pointer, message_info, allocation)); rcl_reset_error(); } @@ -890,18 +892,22 @@ TEST_F( &serialized_msg, initial_serialization_capacity, &allocator)) << rcl_get_error_string().str; + rmw_message_info_t * message_info = nullptr; // is a valid argument + rmw_subscription_allocation_t * allocation = nullptr; // is a valid argument EXPECT_EQ( RCL_RET_SUBSCRIPTION_INVALID, - rcl_take_serialized_message(nullptr, &serialized_msg, nullptr, nullptr)); + rcl_take_serialized_message(nullptr, &serialized_msg, message_info, allocation)); rcl_reset_error(); EXPECT_EQ( RCL_RET_SUBSCRIPTION_INVALID, - rcl_take_serialized_message(&subscription_zero_init, &serialized_msg, nullptr, nullptr)); + rcl_take_serialized_message( + &subscription_zero_init, &serialized_msg, + message_info, allocation)); rcl_reset_error(); EXPECT_EQ( RCL_RET_INVALID_ARGUMENT, - rcl_take_serialized_message(&subscription, nullptr, nullptr, nullptr)); + rcl_take_serialized_message(&subscription, nullptr, message_info, allocation)); rcl_reset_error(); rmw_ret_t rmw_take_serialized_message_with_info_returns = RMW_RET_OK; @@ -914,19 +920,19 @@ TEST_F( EXPECT_EQ( RCL_RET_SUBSCRIPTION_TAKE_FAILED, - rcl_take_serialized_message(&subscription, &serialized_msg, nullptr, nullptr)); + rcl_take_serialized_message(&subscription, &serialized_msg, message_info, allocation)); rcl_reset_error(); rmw_take_serialized_message_with_info_returns = RMW_RET_BAD_ALLOC; EXPECT_EQ( RCL_RET_BAD_ALLOC, - rcl_take_serialized_message(&subscription, &serialized_msg, nullptr, nullptr)); + rcl_take_serialized_message(&subscription, &serialized_msg, message_info, allocation)); rcl_reset_error(); rmw_take_serialized_message_with_info_returns = RMW_RET_ERROR; EXPECT_EQ( RCL_RET_ERROR, - rcl_take_serialized_message(&subscription, &serialized_msg, nullptr, nullptr)); + rcl_take_serialized_message(&subscription, &serialized_msg, message_info, allocation)); rcl_reset_error(); } From 3f3b2fcd3a8e14119e0401f185bc44447cfed15c Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Tue, 11 Aug 2020 11:11:55 -0300 Subject: [PATCH 03/10] Collapse mocking_utils into one. Signed-off-by: Michel Hidalgo --- rcl/test/mocking_utils/patch.hpp | 55 ++-- rcl/test/rcl/mocking_utils/patch.hpp | 373 --------------------------- rcl/test/rcl/test_subscription.cpp | 2 +- 3 files changed, 39 insertions(+), 391 deletions(-) delete mode 100644 rcl/test/rcl/mocking_utils/patch.hpp diff --git a/rcl/test/mocking_utils/patch.hpp b/rcl/test/mocking_utils/patch.hpp index 544dec27a..d170c7fa3 100644 --- a/rcl/test/mocking_utils/patch.hpp +++ b/rcl/test/mocking_utils/patch.hpp @@ -219,11 +219,8 @@ class Patch * \return a mocking_utils::Patch instance. */ explicit Patch(const std::string & target, std::function proxy) - : proxy_(proxy) + : target_(target), proxy_(proxy) { - auto MMK_MANGLE(mock_type, create) = - PatchTraits::MMK_MANGLE(mock_type, create); - mock_ = mmk_mock(target.c_str(), mock_type); } // Copy construction and assignment are disabled. @@ -255,18 +252,14 @@ class Patch /// Inject a @p replacement for the patched function. Patch & then_call(std::function replacement) & { - auto type_erased_trampoline = - reinterpret_cast(prepare_trampoline(replacement)); - mmk_when(proxy_(any()...), .then_call = type_erased_trampoline); + replace_with(replacement); return *this; } /// Inject a @p replacement for the patched function. Patch && then_call(std::function replacement) && { - auto type_erased_trampoline = - reinterpret_cast(prepare_trampoline(replacement)); - mmk_when(proxy_(any()...), .then_call = type_erased_trampoline); + replace_with(replacement); return std::move(*this); } @@ -276,7 +269,21 @@ class Patch template T any() {return mmk_any(T);} - mock_type mock_; + void replace_with(std::function replacement) + { + if (mock_) { + throw std::logic_error("Cannot configure patch more than once"); + } + auto type_erased_trampoline = + reinterpret_cast(prepare_trampoline(replacement)); + auto MMK_MANGLE(mock_type, create) = + PatchTraits::MMK_MANGLE(mock_type, create); + mock_ = mmk_mock(target_.c_str(), mock_type); + mmk_when(proxy_(any()...), .then_call = type_erased_trampoline); + } + + mock_type mock_{nullptr}; + std::string target_; std::function proxy_; }; @@ -332,15 +339,29 @@ auto make_patch(const std::string & target, std::function proxy) #define MOCKING_UTILS_PATCH_TARGET(scope, function) \ (std::string(RCUTILS_STRINGIFY(function)) + "@" + (scope)) -/// Patch a `function` with a used-provided `replacement` in a given `scope`. -#define patch(scope, function, replacement) \ +/// Prepare a mocking_utils::Patch for patching a `function` in a given `scope` +/// but defer applying any changes. +#define prepare_patch(scope, function) \ make_patch<__COUNTER__, decltype(function)>( \ MOCKING_UTILS_PATCH_TARGET(scope, function), MOCKING_UTILS_PATCH_PROXY(function) \ - ).then_call(replacement) + ) -/// Patch a function with a function that only returns a value -#define patch_and_return(scope, function, return_value) \ - patch(scope, function, [&](auto && ...) {return return_value;}) +/// Patch a `function` with a used-provided `replacement` in a given `scope`. +#define patch(scope, function, replacement) \ + prepare_patch(scope, function).then_call(replacement) + +/// Patch a `function` to always yield a given `return_code` in a given `scope`. +#define patch_and_return(scope, function, return_code) \ + patch(scope, function, [&](auto && ...) {return return_code;}) + +/// Patch a `function` to execute normally but always yield a given `return_code` +/// in a given `scope`. +#define inject_on_return(scope, function, return_code) \ + patch( \ + scope, function, ([&, base = function](auto && ... __args) { \ + static_cast(base(std::forward(__args)...)); \ + return return_code; \ + })) } // namespace mocking_utils diff --git a/rcl/test/rcl/mocking_utils/patch.hpp b/rcl/test/rcl/mocking_utils/patch.hpp deleted file mode 100644 index bc62306d4..000000000 --- a/rcl/test/rcl/mocking_utils/patch.hpp +++ /dev/null @@ -1,373 +0,0 @@ -// 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. - -#ifndef RCL__MOCKING_UTILS__PATCH_HPP_ -#define RCL__MOCKING_UTILS__PATCH_HPP_ - -#define MOCKING_UTILS_SUPPORT_VA_LIST -#if (defined(__aarch64__) || defined(__arm__) || defined(_M_ARM) || defined(__thumb__)) -// In ARM machines, va_list does not define comparison operators -// nor the compiler allows defining them via operator overloads. -// Thus, Mimick argument matching code will not compile. -#undef MOCKING_UTILS_SUPPORT_VA_LIST -#endif - -#ifdef MOCKING_UTILS_SUPPORT_VA_LIST -#include -#endif - -#include -#include -#include -#include - -#include "mimick/mimick.h" -#include "rcutils/macros.h" - -namespace mocking_utils -{ - -/// Mimick specific traits for each mocking_utils::Patch instance. -/** - * \tparam ID Numerical identifier of the patch. Ought to be unique. - * \tparam SignatureT Type of the symbol to be patched. -*/ -template -struct PatchTraits; - -/// Traits specialization for ReturnT(void) free functions. -/** - * \tparam ID Numerical identifier of the patch. Ought to be unique. - * \tparam ReturnT Return value type. - */ -template -struct PatchTraits -{ - mmk_mock_define(mock_type, ReturnT); -}; - -/// Traits specialization for ReturnT(ArgT0) free functions. -/** - * \tparam ID Numerical identifier of the patch. Ought to be unique. - * \tparam ReturnT Return value type. - * \tparam ArgT0 Argument type. - */ -template -struct PatchTraits -{ - mmk_mock_define(mock_type, ReturnT, ArgT0); -}; - -/// Traits specialization for ReturnT(ArgT0, ArgT1) free functions. -/** - * \tparam ID Numerical identifier of the patch. Ought to be unique. - * \tparam ReturnT Return value type. - * \tparam ArgTx Argument types. - */ -template -struct PatchTraits -{ - mmk_mock_define(mock_type, ReturnT, ArgT0, ArgT1); -}; - -/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2) free functions. -/** - * \tparam ID Numerical identifier of the patch. Ought to be unique. - * \tparam ReturnT Return value type. - * \tparam ArgTx Argument types. - */ -template -struct PatchTraits -{ - mmk_mock_define(mock_type, ReturnT, ArgT0, ArgT1, ArgT2); -}; - -/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2, ArgT3) free functions. -/** - * \tparam ID Numerical identifier of the patch. Ought to be unique. - * \tparam ReturnT Return value type. - * \tparam ArgTx Argument types. - */ -template -struct PatchTraits -{ - mmk_mock_define(mock_type, ReturnT, ArgT0, ArgT1, ArgT2, ArgT3); -}; - -/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4) -/// free functions. -/** - * \tparam ID Numerical identifier of the patch. Ought to be unique. - * \tparam ReturnT Return value type. - * \tparam ArgTx Argument types. - */ -template -struct PatchTraits -{ - mmk_mock_define(mock_type, ReturnT, ArgT0, ArgT1, ArgT2, ArgT3, ArgT4); -}; - -/// Traits specialization for ReturnT(ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5) -/// free functions. -/** - * \tparam ID Numerical identifier of the patch. Ought to be unique. - * \tparam ReturnT Return value type. - * \tparam ArgTx Argument types. - */ -template -struct PatchTraits -{ - mmk_mock_define( - mock_type, ReturnT, ArgT0, ArgT1, ArgT2, ArgT3, ArgT4, ArgT5); -}; - -/// Generic trampoline to wrap generalized callables in plain functions. -/** - * \tparam ID Numerical identifier of this trampoline. Ought to be unique. - * \tparam SignatureT Type of the symbol this trampoline replaces. - */ -template -struct Trampoline; - -/// Trampoline specialization for free functions. -template -struct Trampoline -{ - static ReturnT base(ArgTs... args) - { - return target(std::forward(args)...); - } - - static std::function target; -}; - -template -std::function -Trampoline::target; - -/// Setup trampoline with the given @p target. -/** - * \param[in] target Callable that this trampoline will target. - * \return the plain base function of this trampoline. - * - * \tparam ID Numerical identifier of this trampoline. Ought to be unique. - * \tparam SignatureT Type of the symbol this trampoline replaces. - */ -template -auto prepare_trampoline(std::function target) -{ - Trampoline::target = target; - return Trampoline::base; -} - -/// Patch class for binary API mocking -/** - * Built on top of Mimick, to enable symbol mocking on a per dynamically - * linked binary object basis. - * - * \tparam ID Numerical identifier for this patch. Ought to be unique. - * \tparam SignatureT Type of the symbol to be patched. - */ -template -class Patch; - -/// Patch specialization for ReturnT(ArgTs...) free functions. -/** - * \tparam ID Numerical identifier for this patch. Ought to be unique. - * \tparam ReturnT Return value type. - * \tparam ArgTs Argument types. - */ -template -class Patch -{ -public: - using mock_type = typename PatchTraits::mock_type; - - /// Construct a patch. - /** - * \param[in] target Symbol target string, using Mimick syntax - * i.e. "symbol(@scope)?", where scope may be "self" to target the current - * binary, "lib:library_name" to target a given library, "file:path/to/library" - * to target a given file, or "sym:other_symbol" to target the first library - * that defines said symbol. - * \param[in] proxy An indirection to call the target function. - * This indirection must ensure this call goes through the function's - * trampoline, as setup by the dynamic linker. - * \return a mocking_utils::Patch instance. - */ - explicit Patch(const std::string & target, std::function proxy) - : target_(target), proxy_(proxy) - { - } - - // Copy construction and assignment are disabled. - Patch(const Patch &) = delete; - Patch & operator=(const Patch &) = delete; - - Patch(Patch && other) - { - mock_ = other.mock_; - other.mock_ = nullptr; - } - - Patch & operator=(Patch && other) - { - if (mock_) { - mmk_reset(mock_); - } - mock_ = other.mock_; - other.mock_ = nullptr; - } - - ~Patch() - { - if (mock_) { - mmk_reset(mock_); - } - } - - /// Inject a @p replacement for the patched function. - Patch & then_call(std::function replacement) & - { - replace_with(replacement); - return *this; - } - - /// Inject a @p replacement for the patched function. - Patch && then_call(std::function replacement) && - { - replace_with(replacement); - return std::move(*this); - } - -private: - // Helper for template parameter pack expansion using `mmk_any` - // macro as pattern. - template - T any() {return mmk_any(T);} - - void replace_with(std::function replacement) - { - if (mock_) { - throw std::logic_error("Cannot configure patch more than once"); - } - auto type_erased_trampoline = - reinterpret_cast(prepare_trampoline(replacement)); - auto MMK_MANGLE(mock_type, create) = - PatchTraits::MMK_MANGLE(mock_type, create); - mock_ = mmk_mock(target_.c_str(), mock_type); - mmk_when(proxy_(any()...), .then_call = type_erased_trampoline); - } - - mock_type mock_{nullptr}; - std::string target_; - std::function proxy_; -}; - -/// Make a patch for a `target` function. -/** - * Useful for type deduction during \ref mocking_utils::Patch construction. - * - * \param[in] target Symbol target string, using Mimick syntax. - * \param[in] proxy An indirection to call the target function. - * \return a mocking_utils::Patch instance. - * - * \tparam ID Numerical identifier for this patch. Ought to be unique. - * \tparam SignatureT Type of the function to be patched. - * - * \sa mocking_utils::Patch for further reference. - */ -template -auto make_patch(const std::string & target, std::function proxy) -{ - return Patch(target, proxy); -} - -/// Define a dummy operator `op` for a given `type`. -/** - * Useful to enable patching functions that take arguments whose types - * do not define basic comparison operators, as required by Mimick. -*/ -#define MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(type_, op) \ - template \ - typename std::enable_if::value, bool>::type \ - operator op(const T &, const T &) { \ - return false; \ - } - -/// Get the exact \ref mocking_utils::Patch type for a given `id` and `function`. -/** - * Useful to avoid ignored attribute warnings when using the \b decltype operator. - */ -#define MOCKING_UTILS_PATCH_TYPE(id, function) \ - decltype(mocking_utils::make_patch("", nullptr)) - -/// A transparent forwarding proxy to a given `function`. -/** - * Useful to ensure a call to `function` goes through its trampoline. - */ -#define MOCKING_UTILS_PATCH_PROXY(function) \ - [] (auto && ... args)->decltype(auto) { \ - return function(std::forward(args)...); \ - } - -/// Compute a Mimick symbol target string based on which `function` is to be patched -/// in which `scope`. -#define MOCKING_UTILS_PATCH_TARGET(scope, function) \ - (std::string(RCUTILS_STRINGIFY(function)) + "@" + (scope)) - -/// Prepare a mocking_utils::Patch for patching a `function` in a given `scope` -/// but defer applying any changes. -#define prepare_patch(scope, function) \ - make_patch<__COUNTER__, decltype(function)>( \ - MOCKING_UTILS_PATCH_TARGET(scope, function), MOCKING_UTILS_PATCH_PROXY(function) \ - ) - -/// Patch a `function` with a used-provided `replacement` in a given `scope`. -#define patch(scope, function, replacement) \ - prepare_patch(scope, function).then_call(replacement) - -/// Patch a `function` to always yield a given `return_code` in a given `scope`. -#define patch_and_return(scope, function, return_code) \ - patch(scope, function, [&](auto && ...) {return return_code;}) - -/// Patch a `function` to execute normally but always yield a given `return_code` -/// in a given `scope`. -#define inject_on_return(scope, function, return_code) \ - patch( \ - scope, function, ([&, base = function](auto && ... __args) { \ - static_cast(base(std::forward(__args)...)); \ - return return_code; \ - })) - -} // namespace mocking_utils - -#ifdef MOCKING_UTILS_SUPPORT_VA_LIST -// Define dummy comparison operators for C standard va_list type -MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(va_list, ==) -MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(va_list, !=) -MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(va_list, <) -MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(va_list, >) -#endif - -#endif // RCL__MOCKING_UTILS__PATCH_HPP_ diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index 8cbb042df..6a6408801 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -32,7 +32,7 @@ #include "wait_for_entity_helpers.hpp" #include "./allocator_testing_utils.h" -#include "./mocking_utils/patch.hpp" +#include "../mocking_utils/patch.hpp" #ifdef RMW_IMPLEMENTATION # define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX From d9acecf04d7efe1c7078e1ba1aaf73b1b8cfee76 Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Tue, 11 Aug 2020 12:53:59 -0300 Subject: [PATCH 04/10] Comment on message loaning mocks. Signed-off-by: Michel Hidalgo --- rcl/test/rcl/test_subscription.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index 6a6408801..2eb5a993b 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -771,8 +771,10 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription mocking_utils::prepare_patch("lib:rcl", rmw_take_loaned_message_with_info); auto patch_return = mocking_utils::prepare_patch("lib:rcl", rmw_return_loaned_message_from_subscription); - // Only if rmw supports the functionality + if (!rcl_subscription_can_loan_messages(&subscription)) { + // If rcl (and ultimately rmw) does not support message loaning, + // mock it so that a unit test can still be constructed. patch_take.then_call( [](const rmw_subscription_t * subscription, void ** loaned_message, bool * taken, From 436842b7aaf033ff0df0a940afffccaec071911a Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Tue, 11 Aug 2020 15:24:54 -0300 Subject: [PATCH 05/10] Alphasort package test dependencies. Signed-off-by: Michel Hidalgo --- rcl/package.xml | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/rcl/package.xml b/rcl/package.xml index 014efbc4c..62396c764 100644 --- a/rcl/package.xml +++ b/rcl/package.xml @@ -25,16 +25,15 @@ ament_cmake_gtest ament_lint_auto ament_lint_common - mimick_vendor - rcpputils - rmw - rmw_implementation_cmake launch launch_testing launch_testing_ament_cmake + mimick_vendor osrf_testing_tools_cpp + rcpputils + rmw + rmw_implementation_cmake test_msgs - mimick_vendor rcl_logging_packages From bafb0e04b07c7559257a9f8bf0c9f568f45c2a7a Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Tue, 11 Aug 2020 15:26:08 -0300 Subject: [PATCH 06/10] Comment on dummy comparison operators. Signed-off-by: Michel Hidalgo --- rcl/test/rcl/test_subscription.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index 2eb5a993b..c6f2568a0 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -146,6 +146,8 @@ TEST_F( rcl_reset_error(); } +// Define dummy comparison operators for rcutils_allocator_t type +// to use with the Mimick mocking library 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, <) From 5f3d1adefca14a7b73ed55940b7e609b79b91436 Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Tue, 11 Aug 2020 15:30:58 -0300 Subject: [PATCH 07/10] Use constexpr where possible. Signed-off-by: Michel Hidalgo --- rcl/test/rcl/test_subscription.cpp | 30 +++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index c6f2568a0..eb67394a5 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -64,7 +64,7 @@ class CLASSNAME (TestSubscriptionFixture, RMW_IMPLEMENTATION) : public ::testing } this->node_ptr = new rcl_node_t; *this->node_ptr = rcl_get_zero_initialized_node(); - const char * name = "test_subscription_node"; + constexpr char name[] = "test_subscription_node"; rcl_node_options_t node_options = rcl_node_get_default_options(); ret = rcl_node_init(this->node_ptr, name, "", this->context_ptr, &node_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -125,8 +125,8 @@ TEST_F( const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); - const char * topic = "chatter"; - const char * expected_topic = "/chatter"; + constexpr char topic[] = "chatter"; + constexpr char expected_topic[] = "/chatter"; rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); @@ -157,7 +157,7 @@ MOCKING_UTILS_BOOL_OPERATOR_RETURNS_FALSE(rcutils_allocator_t, >) TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_bad_init) { const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); - const char * topic = "/chatter"; + constexpr char topic[] = "/chatter"; rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_node_t invalid_node = rcl_get_zero_initialized_node(); @@ -269,7 +269,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, BasicTypes); - const char * topic = "/chatter"; + constexpr char topic[] = "/chatter"; rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -342,7 +342,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); - const char * topic = "rcl_test_subscription_nominal_string_chatter"; + constexpr char topic[] = "rcl_test_subscription_nominal_string_chatter"; rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -361,7 +361,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; }); ASSERT_TRUE(wait_for_established_subscription(&publisher, 10, 100)); - const char * test_string = "testing"; + constexpr char test_string[] = "testing"; { test_msgs__msg__Strings msg; test_msgs__msg__Strings__init(&msg); @@ -394,7 +394,7 @@ TEST_F( rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); - const char * topic = "rcl_test_subscription_nominal_string_sequence_chatter"; + constexpr char topic[] = "rcl_test_subscription_nominal_string_sequence_chatter"; rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -413,7 +413,7 @@ TEST_F( EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; }); ASSERT_TRUE(wait_for_established_subscription(&publisher, 10, 100)); - const char * test_string = "testing"; + constexpr char test_string[] = "testing"; { test_msgs__msg__Strings msg; test_msgs__msg__Strings__init(&msg); @@ -539,7 +539,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription rcutils_allocator_t allocator = rcl_get_default_allocator(); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); - const char * topic = "/chatterSer"; + constexpr char topic[] = "/chatterSer"; rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -554,7 +554,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription ASSERT_EQ( RCL_RET_OK, rmw_serialized_message_init( &serialized_msg, initial_capacity_ser, &allocator)) << rcl_get_error_string().str; - const char * test_string = "testing"; + constexpr char test_string[] = "testing"; test_msgs__msg__Strings msg; test_msgs__msg__Strings__init(&msg); ASSERT_TRUE(rosidl_runtime_c__String__assign(&msg.string_value, test_string)); @@ -600,7 +600,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription /* Test for all failure modes in subscription take with loaned messages function. */ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_bad_take_loaned_message) { - const char * topic = "rcl_loan"; + constexpr char topic[] = "rcl_loan"; const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); @@ -673,7 +673,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_bad_take_loa /* Test for all failure modes in subscription return loaned messages function. */ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_bad_return_loaned_message) { - const char * topic = "rcl_loan"; + constexpr char topic[] = "rcl_loan"; const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); @@ -739,7 +739,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); - const char * topic = "rcl_loan"; + constexpr char topic[] = "rcl_loan"; rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -826,7 +826,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_get_options) rcl_ret_t ret; const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); - const char * topic = "test_get_options"; + constexpr char topic[] = "test_get_options"; rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); From c0cf8612bf3ef56a0068741e9b81d85851834a71 Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Tue, 11 Aug 2020 15:33:59 -0300 Subject: [PATCH 08/10] Relocate loaned messages API tests. Signed-off-by: Michel Hidalgo --- rcl/test/rcl/test_subscription.cpp | 180 ++++++++++++++--------------- 1 file changed, 90 insertions(+), 90 deletions(-) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index eb67394a5..d1dd8af90 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -597,6 +597,96 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription } } +/* Basic test for subscription loan functions + */ +TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_loaned) { + rcl_ret_t ret; + rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); + const rosidl_message_type_support_t * ts = + ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); + constexpr char topic[] = "rcl_loan"; + rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); + ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + }); + rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); + rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); + ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + }); + ASSERT_TRUE(wait_for_established_subscription(&publisher, 10, 100)); + const char * test_string = "testing"; + { + test_msgs__msg__Strings msg; + test_msgs__msg__Strings__init(&msg); + ASSERT_TRUE(rosidl_runtime_c__String__assign(&msg.string_value, test_string)); + ret = rcl_publish(&publisher, &msg, nullptr); + test_msgs__msg__Strings__fini(&msg); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + } + ASSERT_TRUE(wait_for_subscription_to_be_ready(&subscription, context_ptr, 10, 100)); + { + auto patch_take = + mocking_utils::prepare_patch("lib:rcl", rmw_take_loaned_message_with_info); + auto patch_return = + mocking_utils::prepare_patch("lib:rcl", rmw_return_loaned_message_from_subscription); + + if (!rcl_subscription_can_loan_messages(&subscription)) { + // If rcl (and ultimately rmw) does not support message loaning, + // mock it so that a unit test can still be constructed. + patch_take.then_call( + [](const rmw_subscription_t * subscription, + void ** loaned_message, bool * taken, + rmw_message_info_t * message_info, + rmw_subscription_allocation_t * allocation) + { + auto msg = new(std::nothrow) test_msgs__msg__Strings{}; + if (!msg) { + return RMW_RET_BAD_ALLOC; + } + test_msgs__msg__Strings__init(msg); + *loaned_message = static_cast(msg); + rmw_ret_t ret = rmw_take_with_info( + subscription, + *loaned_message, + taken, + message_info, + allocation); + if (RMW_RET_OK != ret) { + delete msg; + } + return ret; + }); + patch_return.then_call( + [](auto, void * loaned_message) { + auto msg = reinterpret_cast(loaned_message); + test_msgs__msg__Strings__fini(msg); + delete msg; + + return RMW_RET_OK; + }); + } + + test_msgs__msg__Strings * msg_loaned = nullptr; + ret = rcl_take_loaned_message( + &subscription, reinterpret_cast(&msg_loaned), nullptr, nullptr); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + EXPECT_EQ( + std::string(test_string), + std::string(msg_loaned->string_value.data, msg_loaned->string_value.size)); + ret = rcl_return_loaned_message_from_subscription(&subscription, msg_loaned); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + } +} + /* Test for all failure modes in subscription take with loaned messages function. */ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_bad_take_loaned_message) { @@ -732,96 +822,6 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_bad_return_l rcl_subscription_fini(&subscription, this->node_ptr)) << rcl_get_error_string().str; } -/* Basic test for subscription loan functions - */ -TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription_loaned) { - rcl_ret_t ret; - rcl_publisher_t publisher = rcl_get_zero_initialized_publisher(); - const rosidl_message_type_support_t * ts = - ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings); - constexpr char topic[] = "rcl_loan"; - rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options(); - ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( - { - rcl_ret_t ret = rcl_publisher_fini(&publisher, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - }); - rcl_subscription_t subscription = rcl_get_zero_initialized_subscription(); - rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options(); - ret = rcl_subscription_init(&subscription, this->node_ptr, ts, topic, &subscription_options); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( - { - rcl_ret_t ret = rcl_subscription_fini(&subscription, this->node_ptr); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - }); - ASSERT_TRUE(wait_for_established_subscription(&publisher, 10, 100)); - const char * test_string = "testing"; - { - test_msgs__msg__Strings msg; - test_msgs__msg__Strings__init(&msg); - ASSERT_TRUE(rosidl_runtime_c__String__assign(&msg.string_value, test_string)); - ret = rcl_publish(&publisher, &msg, nullptr); - test_msgs__msg__Strings__fini(&msg); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - } - ASSERT_TRUE(wait_for_subscription_to_be_ready(&subscription, context_ptr, 10, 100)); - { - auto patch_take = - mocking_utils::prepare_patch("lib:rcl", rmw_take_loaned_message_with_info); - auto patch_return = - mocking_utils::prepare_patch("lib:rcl", rmw_return_loaned_message_from_subscription); - - if (!rcl_subscription_can_loan_messages(&subscription)) { - // If rcl (and ultimately rmw) does not support message loaning, - // mock it so that a unit test can still be constructed. - patch_take.then_call( - [](const rmw_subscription_t * subscription, - void ** loaned_message, bool * taken, - rmw_message_info_t * message_info, - rmw_subscription_allocation_t * allocation) - { - auto msg = new(std::nothrow) test_msgs__msg__Strings{}; - if (!msg) { - return RMW_RET_BAD_ALLOC; - } - test_msgs__msg__Strings__init(msg); - *loaned_message = static_cast(msg); - rmw_ret_t ret = rmw_take_with_info( - subscription, - *loaned_message, - taken, - message_info, - allocation); - if (RMW_RET_OK != ret) { - delete msg; - } - return ret; - }); - patch_return.then_call( - [](auto, void * loaned_message) { - auto msg = reinterpret_cast(loaned_message); - test_msgs__msg__Strings__fini(msg); - delete msg; - - return RMW_RET_OK; - }); - } - - test_msgs__msg__Strings * msg_loaned = nullptr; - ret = rcl_take_loaned_message( - &subscription, reinterpret_cast(&msg_loaned), nullptr, nullptr); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - EXPECT_EQ( - std::string(test_string), - std::string(msg_loaned->string_value.data, msg_loaned->string_value.size)); - ret = rcl_return_loaned_message_from_subscription(&subscription, msg_loaned); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - } -} - TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_get_options) { rcl_ret_t ret; const rosidl_message_type_support_t * ts = From cf68a3778258a86a840c548faf593774b9dbb4f5 Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Tue, 11 Aug 2020 15:42:53 -0300 Subject: [PATCH 09/10] Reformat mocking lambda. Signed-off-by: Michel Hidalgo --- rcl/test/rcl/test_subscription.cpp | 13 ++----------- 1 file changed, 2 insertions(+), 11 deletions(-) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index d1dd8af90..54b8b80ab 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -643,23 +643,14 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription // If rcl (and ultimately rmw) does not support message loaning, // mock it so that a unit test can still be constructed. patch_take.then_call( - [](const rmw_subscription_t * subscription, - void ** loaned_message, bool * taken, - rmw_message_info_t * message_info, - rmw_subscription_allocation_t * allocation) - { + [](auto sub, void ** loaned_message, auto taken, auto msg_info, auto allocation) { auto msg = new(std::nothrow) test_msgs__msg__Strings{}; if (!msg) { return RMW_RET_BAD_ALLOC; } test_msgs__msg__Strings__init(msg); *loaned_message = static_cast(msg); - rmw_ret_t ret = rmw_take_with_info( - subscription, - *loaned_message, - taken, - message_info, - allocation); + rmw_ret_t ret = rmw_take_with_info(sub, *loaned_message, taken, msg_info, allocation); if (RMW_RET_OK != ret) { delete msg; } From ccf23dfbc25f6c6c57c41083c8533ed3049d76d6 Mon Sep 17 00:00:00 2001 From: Michel Hidalgo Date: Tue, 11 Aug 2020 15:49:15 -0300 Subject: [PATCH 10/10] Use named variable for improved readability. Signed-off-by: Michel Hidalgo --- rcl/test/rcl/test_subscription.cpp | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/rcl/test/rcl/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp index 54b8b80ab..1e5b8c779 100644 --- a/rcl/test/rcl/test_subscription.cpp +++ b/rcl/test/rcl/test_subscription.cpp @@ -957,33 +957,34 @@ TEST_F( { EXPECT_EQ(RMW_RET_OK, rmw_message_info_sequence_fini(&message_infos)); }); + rmw_subscription_allocation_t * allocation = nullptr; // is a valid argument EXPECT_EQ( RCL_RET_SUBSCRIPTION_INVALID, - rcl_take_sequence(nullptr, seq_size, &messages, &message_infos, nullptr)); + rcl_take_sequence(nullptr, seq_size, &messages, &message_infos, allocation)); rcl_reset_error(); EXPECT_EQ( RCL_RET_SUBSCRIPTION_INVALID, - rcl_take_sequence(&subscription_zero_init, seq_size, &messages, &message_infos, nullptr)); + rcl_take_sequence(&subscription_zero_init, seq_size, &messages, &message_infos, allocation)); rcl_reset_error(); EXPECT_EQ( RCL_RET_INVALID_ARGUMENT, - rcl_take_sequence(&subscription, seq_size + 1, &messages, &message_infos, nullptr)); + rcl_take_sequence(&subscription, seq_size + 1, &messages, &message_infos, allocation)); rcl_reset_error(); EXPECT_EQ( RCL_RET_INVALID_ARGUMENT, - rcl_take_sequence(&subscription, seq_size, &messages, &message_infos_short, nullptr)); + rcl_take_sequence(&subscription, seq_size, &messages, &message_infos_short, allocation)); rcl_reset_error(); EXPECT_EQ( RCL_RET_INVALID_ARGUMENT, - rcl_take_sequence(&subscription, seq_size, nullptr, &message_infos, nullptr)); + rcl_take_sequence(&subscription, seq_size, nullptr, &message_infos, allocation)); rcl_reset_error(); EXPECT_EQ( RCL_RET_INVALID_ARGUMENT, - rcl_take_sequence(&subscription, seq_size, &messages, nullptr, nullptr)); + rcl_take_sequence(&subscription, seq_size, &messages, nullptr, allocation)); rcl_reset_error(); rmw_ret_t rmw_take_sequence_returns = RMW_RET_OK; @@ -996,19 +997,19 @@ TEST_F( EXPECT_EQ( RCL_RET_SUBSCRIPTION_TAKE_FAILED, - rcl_take_sequence(&subscription, seq_size, &messages, &message_infos, nullptr)); + rcl_take_sequence(&subscription, seq_size, &messages, &message_infos, allocation)); rcl_reset_error(); rmw_take_sequence_returns = RMW_RET_BAD_ALLOC; EXPECT_EQ( RCL_RET_BAD_ALLOC, - rcl_take_sequence(&subscription, seq_size, &messages, &message_infos, nullptr)); + rcl_take_sequence(&subscription, seq_size, &messages, &message_infos, allocation)); rcl_reset_error(); rmw_take_sequence_returns = RMW_RET_ERROR; EXPECT_EQ( RCL_RET_ERROR, - rcl_take_sequence(&subscription, seq_size, &messages, &message_infos, nullptr)); + rcl_take_sequence(&subscription, seq_size, &messages, &message_infos, allocation)); rcl_reset_error(); }