Add missing calls to rcl_convert_rmw_ret_to_rcl_ret (#738)
Signed-off-by: Jorge Perez <jjperez@ekumenlabs.com>
This commit is contained in:
parent
c1bf050bff
commit
f3a8bb0127
2 changed files with 10 additions and 16 deletions
|
@ -272,7 +272,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
|
||||
|
@ -284,7 +285,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
|
||||
|
|
|
@ -281,10 +281,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");
|
||||
|
@ -363,10 +360,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");
|
||||
|
@ -402,10 +396,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");
|
||||
|
@ -425,8 +416,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 *
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue