Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add missing calls to rcl_convert_rmw_ret_to_rcl_ret #738

Merged
merged 1 commit into from
Aug 11, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 4 additions & 2 deletions rcl/src/rcl/publisher.c
Original file line number Diff line number Diff line change
Expand Up @@ -262,7 +262,8 @@ rcl_borrow_loaned_message(
if (!rcl_publisher_is_valid(publisher)) {
return RCL_RET_PUBLISHER_INVALID; // error already set
}
return rmw_borrow_loaned_message(publisher->impl->rmw_handle, type_support, ros_message);
return rcl_convert_rmw_ret_to_rcl_ret(
rmw_borrow_loaned_message(publisher->impl->rmw_handle, type_support, ros_message));
}

rcl_ret_t
Expand All @@ -274,7 +275,8 @@ rcl_return_loaned_message_from_publisher(
return RCL_RET_PUBLISHER_INVALID; // error already set
}
RCL_CHECK_ARGUMENT_FOR_NULL(loaned_message, RCL_RET_INVALID_ARGUMENT);
return rmw_return_loaned_message_from_publisher(publisher->impl->rmw_handle, loaned_message);
return rcl_convert_rmw_ret_to_rcl_ret(
rmw_return_loaned_message_from_publisher(publisher->impl->rmw_handle, loaned_message));
}

rcl_ret_t
Expand Down
20 changes: 6 additions & 14 deletions rcl/src/rcl/subscription.c
Original file line number Diff line number Diff line change
Expand Up @@ -270,10 +270,7 @@ rcl_take(
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;
return rcl_convert_rmw_ret_to_rcl_ret(ret);
}
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Subscription take succeeded: %s", taken ? "true" : "false");
Expand Down Expand Up @@ -352,10 +349,7 @@ rcl_take_serialized_message(
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;
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,10 +384,7 @@ rcl_take_loaned_message(
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 +404,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