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 <[email protected]>
  • Loading branch information
hidmic committed Aug 10, 2020
1 parent c417f7b commit 519d2bf
Show file tree
Hide file tree
Showing 5 changed files with 750 additions and 67 deletions.
1 change: 1 addition & 0 deletions rcl/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@
<test_depend>launch_testing_ament_cmake</test_depend>
<test_depend>osrf_testing_tools_cpp</test_depend>
<test_depend>test_msgs</test_depend>
<test_depend>mimick_vendor</test_depend>

<group_depend>rcl_logging_packages</group_depend>

Expand Down
48 changes: 21 additions & 27 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 All @@ -194,6 +194,7 @@ rcl_subscription_init(
fail:
if (subscription->impl) {
allocator->deallocate(subscription->impl, allocator->state);
subscription->impl = NULL;
}
ret = fail_ret;
// Fall through to cleanup
Expand Down Expand Up @@ -229,6 +230,7 @@ rcl_subscription_fini(rcl_subscription_t * subscription, rcl_node_t * node)
result = RCL_RET_ERROR;
}
allocator.deallocate(subscription->impl, allocator.state);
subscription->impl = NULL;
}
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription finalized");
return result;
Expand Down Expand Up @@ -269,11 +271,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 +291,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 +308,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 +350,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 All @@ -376,6 +372,7 @@ rcl_take_loaned_message(
if (!rcl_subscription_is_valid(subscription)) {
return RCL_RET_SUBSCRIPTION_INVALID; // error already set
}
RCL_CHECK_ARGUMENT_FOR_NULL(loaned_message, RCL_RET_INVALID_ARGUMENT);
if (*loaned_message) {
RCL_SET_ERROR_MSG("loaned message is already initialized");
return RCL_RET_INVALID_ARGUMENT;
Expand All @@ -389,11 +386,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) {
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
if (RMW_RET_BAD_ALLOC == ret) {
return RCL_RET_BAD_ALLOC;
}
return RCL_RET_ERROR;
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 @@ -413,8 +406,9 @@ 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
3 changes: 2 additions & 1 deletion rcl/test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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(rcpputils REQUIRED)
Expand Down Expand Up @@ -223,7 +224,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
Expand Down
Loading

0 comments on commit 519d2bf

Please sign in to comment.