diff --git a/rcl/package.xml b/rcl/package.xml
index c40622334..4dbc85cdb 100644
--- a/rcl/package.xml
+++ b/rcl/package.xml
@@ -25,14 +25,14 @@
ament_cmake_pytest
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
rcl_logging_packages
diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt
index bd04416f7..411bcbfde 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)
@@ -224,7 +225,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/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/test_subscription.cpp b/rcl/test/rcl/test_subscription.cpp
index 2dcbd4490..1e5b8c779 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
@@ -61,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;
@@ -122,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();
@@ -143,22 +146,33 @@ 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, <)
+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 =
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();
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 +187,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 +246,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
@@ -200,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;
@@ -273,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;
@@ -292,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);
@@ -325,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;
@@ -344,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);
@@ -470,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;
@@ -485,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));
@@ -535,7 +604,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;
@@ -565,36 +634,190 @@ 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);
- });
-
- // 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));
+ 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(
+ [](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(sub, *loaned_message, taken, msg_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) {
+ 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();
+ 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);
+ 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, message_info, allocation));
+ rcl_reset_error();
+
+ EXPECT_EQ(
+ RCL_RET_INVALID_ARGUMENT,
+ 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, message_info, allocation));
+ 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, 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, 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, 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, message_info, allocation));
+ 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) {
+ 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();
+ 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;
}
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);
@@ -629,9 +852,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,23 +881,53 @@ 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;
+ 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, message_info, allocation));
+ 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_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, 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, message_info, allocation));
rcl_reset_error();
}
@@ -686,43 +957,92 @@ 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, allocation));
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, &messages, nullptr, allocation));
+ 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_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, 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, allocation));
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 +1054,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));