Skip to content

Commit

Permalink
Complete subscription test coverage
Browse files Browse the repository at this point in the history
Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
  • Loading branch information
hidmic committed Aug 7, 2020
1 parent e94e46e commit 6cac41c
Show file tree
Hide file tree
Showing 3 changed files with 207 additions and 79 deletions.
40 changes: 17 additions & 23 deletions rcl/src/rcl/subscription.c
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ rcl_subscription_init(
rcutils_string_map_t substitutions_map = rcutils_get_zero_initialized_string_map();
rcutils_ret_t rcutils_ret = rcutils_string_map_init(&substitutions_map, 0, rcutils_allocator);
if (rcutils_ret != RCUTILS_RET_OK) {
RCL_SET_ERROR_MSG(rcutils_get_error_string().str);
// RCL_SET_ERROR_MSG(rcutils_get_error_string().str);
if (RCUTILS_RET_BAD_ALLOC == rcutils_ret) {
return RCL_RET_BAD_ALLOC;
}
Expand Down Expand Up @@ -104,7 +104,7 @@ rcl_subscription_init(
&expanded_topic_name);
rcutils_ret = rcutils_string_map_fini(&substitutions_map);
if (rcutils_ret != RCUTILS_RET_OK) {
RCL_SET_ERROR_MSG(rcutils_get_error_string().str);
// RCL_SET_ERROR_MSG(rcutils_get_error_string().str);
ret = RCL_RET_ERROR;
goto cleanup;
}
Expand Down Expand Up @@ -141,7 +141,7 @@ rcl_subscription_init(
int validation_result;
rmw_ret_t rmw_ret = rmw_validate_full_topic_name(remapped_topic_name, &validation_result, NULL);
if (rmw_ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
// RCL_SET_ERROR_MSG(rmw_get_error_string().str);
ret = RCL_RET_ERROR;
goto cleanup;
}
Expand All @@ -165,15 +165,15 @@ rcl_subscription_init(
&(options->qos),
&(options->rmw_subscription_options));
if (!subscription->impl->rmw_handle) {
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
// RCL_SET_ERROR_MSG(rmw_get_error_string().str);
goto fail;
}
// get actual qos, and store it
rmw_ret = rmw_subscription_get_actual_qos(
subscription->impl->rmw_handle,
&subscription->impl->actual_qos);
if (RMW_RET_OK != rmw_ret) {
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
// RCL_SET_ERROR_MSG(rmw_get_error_string().str);
ret = RCL_RET_ERROR;
goto fail;
}
Expand Down Expand Up @@ -269,11 +269,8 @@ rcl_take(
rmw_ret_t ret = rmw_take_with_info(
subscription->impl->rmw_handle, ros_message, &taken, message_info_local, allocation);
if (ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
if (RMW_RET_BAD_ALLOC == ret) {
return RCL_RET_BAD_ALLOC;
}
return RCL_RET_ERROR;
// RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return rcl_convert_rmw_ret_to_rcl_ret(ret);
}
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Subscription take succeeded: %s", taken ? "true" : "false");
Expand All @@ -292,10 +289,6 @@ rcl_take_sequence(
rmw_subscription_allocation_t * allocation
)
{
// Set the sizes to zero to indicate that there are no valid messages
message_sequence->size = 0u;
message_info_sequence->size = 0u;

RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription taking %zu messages", count);
if (!rcl_subscription_is_valid(subscription)) {
return RCL_RET_SUBSCRIPTION_INVALID; // error message already set
Expand All @@ -313,12 +306,16 @@ rcl_take_sequence(
return RCL_RET_INVALID_ARGUMENT;
}

// Set the sizes to zero to indicate that there are no valid messages
message_sequence->size = 0u;
message_info_sequence->size = 0u;

size_t taken = 0u;
rmw_ret_t ret = rmw_take_sequence(
subscription->impl->rmw_handle, count, message_sequence, message_info_sequence, &taken,
allocation);
if (ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
// RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return rcl_convert_rmw_ret_to_rcl_ret(ret);
}
RCUTILS_LOG_DEBUG_NAMED(
Expand Down Expand Up @@ -351,11 +348,8 @@ rcl_take_serialized_message(
rmw_ret_t ret = rmw_take_serialized_message_with_info(
subscription->impl->rmw_handle, serialized_message, &taken, message_info_local, allocation);
if (ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
if (RMW_RET_BAD_ALLOC == ret) {
return RCL_RET_BAD_ALLOC;
}
return RCL_RET_ERROR;
// RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return rcl_convert_rmw_ret_to_rcl_ret(ret);
}
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Subscription serialized take succeeded: %s", taken ? "true" : "false");
Expand Down Expand Up @@ -390,7 +384,7 @@ rcl_take_loaned_message(
rmw_ret_t ret = rmw_take_loaned_message_with_info(
subscription->impl->rmw_handle, loaned_message, &taken, message_info_local, allocation);
if (ret != RMW_RET_OK) {
return ret;
return rcl_convert_rmw_ret_to_rcl_ret(ret);
}
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Subscription loaned take succeeded: %s", taken ? "true" : "false");
Expand All @@ -410,8 +404,8 @@ rcl_return_loaned_message_from_subscription(
return RCL_RET_SUBSCRIPTION_INVALID; // error already set
}
RCL_CHECK_ARGUMENT_FOR_NULL(loaned_message, RCL_RET_INVALID_ARGUMENT);
return rmw_return_loaned_message_from_subscription(
subscription->impl->rmw_handle, loaned_message);
return rcl_convert_rmw_ret_to_rcl_ret(rmw_return_loaned_message_from_subscription(
subscription->impl->rmw_handle, loaned_message));
}

const char *
Expand Down
37 changes: 26 additions & 11 deletions rcl/test/rcl/mocking_utils/patch.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -216,11 +216,8 @@ class Patch<ID, ReturnT(ArgTs...)>
* \return a mocking_utils::Patch instance.
*/
explicit Patch(const std::string & target, std::function<ReturnT(ArgTs...)> proxy)
: proxy_(proxy)
: target_(target), proxy_(proxy)
{
auto MMK_MANGLE(mock_type, create) =
PatchTraits<ID, ReturnT(ArgTs...)>::MMK_MANGLE(mock_type, create);
mock_ = mmk_mock(target.c_str(), mock_type);
}

// Copy construction and assignment are disabled.
Expand Down Expand Up @@ -252,18 +249,14 @@ class Patch<ID, ReturnT(ArgTs...)>
/// Inject a @p replacement for the patched function.
Patch & then_call(std::function<ReturnT(ArgTs...)> replacement) &
{
auto type_erased_trampoline =
reinterpret_cast<mmk_fn>(prepare_trampoline<ID>(replacement));
mmk_when(proxy_(any<ArgTs>()...), .then_call = type_erased_trampoline);
replace_with(replacement);
return *this;
}

/// Inject a @p replacement for the patched function.
Patch && then_call(std::function<ReturnT(ArgTs...)> replacement) &&
{
auto type_erased_trampoline =
reinterpret_cast<mmk_fn>(prepare_trampoline<ID>(replacement));
mmk_when(proxy_(any<ArgTs>()...), .then_call = type_erased_trampoline);
replace_with(replacement);
return std::move(*this);
}

Expand All @@ -273,7 +266,21 @@ class Patch<ID, ReturnT(ArgTs...)>
template<typename T>
T any() {return mmk_any(T);}

mock_type mock_;
void replace_with(std::function<ReturnT(ArgTs...)> replacement)
{
if (mock_) {
throw std::logic_error("Cannot configure patch more than once");
}
auto type_erased_trampoline =
reinterpret_cast<mmk_fn>(prepare_trampoline<ID>(replacement));
auto MMK_MANGLE(mock_type, create) =
PatchTraits<ID, ReturnT(ArgTs...)>::MMK_MANGLE(mock_type, create);
mock_ = mmk_mock(target_.c_str(), mock_type);
mmk_when(proxy_(any<ArgTs>()...), .then_call = type_erased_trampoline);
}

mock_type mock_{nullptr};
std::string target_;
std::function<ReturnT(ArgTs...)> proxy_;
};

Expand Down Expand Up @@ -339,6 +346,14 @@ auto make_patch(const std::string & target, std::function<SignatureT> proxy)
#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<void>(base(std::forward<decltype(__args)>(__args)...)); \
return return_code; \
}))

} // namespace mocking_utils

#ifdef MOCKING_UTILS_SUPPORT_VA_LIST
Expand Down
Loading

0 comments on commit 6cac41c

Please sign in to comment.