@@ -72,7 +72,7 @@ rcl_subscription_init(
7272 rcutils_string_map_t substitutions_map = rcutils_get_zero_initialized_string_map ();
7373 rcutils_ret_t rcutils_ret = rcutils_string_map_init (& substitutions_map , 0 , rcutils_allocator );
7474 if (rcutils_ret != RCUTILS_RET_OK ) {
75- RCL_SET_ERROR_MSG (rcutils_get_error_string ().str );
75+ // RCL_SET_ERROR_MSG(rcutils_get_error_string().str);
7676 if (RCUTILS_RET_BAD_ALLOC == rcutils_ret ) {
7777 return RCL_RET_BAD_ALLOC ;
7878 }
@@ -104,7 +104,7 @@ rcl_subscription_init(
104104 & expanded_topic_name );
105105 rcutils_ret = rcutils_string_map_fini (& substitutions_map );
106106 if (rcutils_ret != RCUTILS_RET_OK ) {
107- RCL_SET_ERROR_MSG (rcutils_get_error_string ().str );
107+ // RCL_SET_ERROR_MSG(rcutils_get_error_string().str);
108108 ret = RCL_RET_ERROR ;
109109 goto cleanup ;
110110 }
@@ -141,7 +141,7 @@ rcl_subscription_init(
141141 int validation_result ;
142142 rmw_ret_t rmw_ret = rmw_validate_full_topic_name (remapped_topic_name , & validation_result , NULL );
143143 if (rmw_ret != RMW_RET_OK ) {
144- RCL_SET_ERROR_MSG (rmw_get_error_string ().str );
144+ // RCL_SET_ERROR_MSG(rmw_get_error_string().str);
145145 ret = RCL_RET_ERROR ;
146146 goto cleanup ;
147147 }
@@ -165,15 +165,15 @@ rcl_subscription_init(
165165 & (options -> qos ),
166166 & (options -> rmw_subscription_options ));
167167 if (!subscription -> impl -> rmw_handle ) {
168- RCL_SET_ERROR_MSG (rmw_get_error_string ().str );
168+ // RCL_SET_ERROR_MSG(rmw_get_error_string().str);
169169 goto fail ;
170170 }
171171 // get actual qos, and store it
172172 rmw_ret = rmw_subscription_get_actual_qos (
173173 subscription -> impl -> rmw_handle ,
174174 & subscription -> impl -> actual_qos );
175175 if (RMW_RET_OK != rmw_ret ) {
176- RCL_SET_ERROR_MSG (rmw_get_error_string ().str );
176+ // RCL_SET_ERROR_MSG(rmw_get_error_string().str);
177177 ret = RCL_RET_ERROR ;
178178 goto fail ;
179179 }
@@ -194,6 +194,7 @@ rcl_subscription_init(
194194fail :
195195 if (subscription -> impl ) {
196196 allocator -> deallocate (subscription -> impl , allocator -> state );
197+ subscription -> impl = NULL ;
197198 }
198199 ret = fail_ret ;
199200 // Fall through to cleanup
@@ -229,6 +230,7 @@ rcl_subscription_fini(rcl_subscription_t * subscription, rcl_node_t * node)
229230 result = RCL_RET_ERROR ;
230231 }
231232 allocator .deallocate (subscription -> impl , allocator .state );
233+ subscription -> impl = NULL ;
232234 }
233235 RCUTILS_LOG_DEBUG_NAMED (ROS_PACKAGE_NAME , "Subscription finalized" );
234236 return result ;
@@ -269,11 +271,8 @@ rcl_take(
269271 rmw_ret_t ret = rmw_take_with_info (
270272 subscription -> impl -> rmw_handle , ros_message , & taken , message_info_local , allocation );
271273 if (ret != RMW_RET_OK ) {
272- RCL_SET_ERROR_MSG (rmw_get_error_string ().str );
273- if (RMW_RET_BAD_ALLOC == ret ) {
274- return RCL_RET_BAD_ALLOC ;
275- }
276- return RCL_RET_ERROR ;
274+ // RCL_SET_ERROR_MSG(rmw_get_error_string().str);
275+ return rcl_convert_rmw_ret_to_rcl_ret (ret );
277276 }
278277 RCUTILS_LOG_DEBUG_NAMED (
279278 ROS_PACKAGE_NAME , "Subscription take succeeded: %s" , taken ? "true" : "false" );
@@ -292,10 +291,6 @@ rcl_take_sequence(
292291 rmw_subscription_allocation_t * allocation
293292)
294293{
295- // Set the sizes to zero to indicate that there are no valid messages
296- message_sequence -> size = 0u ;
297- message_info_sequence -> size = 0u ;
298-
299294 RCUTILS_LOG_DEBUG_NAMED (ROS_PACKAGE_NAME , "Subscription taking %zu messages" , count );
300295 if (!rcl_subscription_is_valid (subscription )) {
301296 return RCL_RET_SUBSCRIPTION_INVALID ; // error message already set
@@ -313,12 +308,16 @@ rcl_take_sequence(
313308 return RCL_RET_INVALID_ARGUMENT ;
314309 }
315310
311+ // Set the sizes to zero to indicate that there are no valid messages
312+ message_sequence -> size = 0u ;
313+ message_info_sequence -> size = 0u ;
314+
316315 size_t taken = 0u ;
317316 rmw_ret_t ret = rmw_take_sequence (
318317 subscription -> impl -> rmw_handle , count , message_sequence , message_info_sequence , & taken ,
319318 allocation );
320319 if (ret != RMW_RET_OK ) {
321- RCL_SET_ERROR_MSG (rmw_get_error_string ().str );
320+ // RCL_SET_ERROR_MSG(rmw_get_error_string().str);
322321 return rcl_convert_rmw_ret_to_rcl_ret (ret );
323322 }
324323 RCUTILS_LOG_DEBUG_NAMED (
@@ -351,11 +350,8 @@ rcl_take_serialized_message(
351350 rmw_ret_t ret = rmw_take_serialized_message_with_info (
352351 subscription -> impl -> rmw_handle , serialized_message , & taken , message_info_local , allocation );
353352 if (ret != RMW_RET_OK ) {
354- RCL_SET_ERROR_MSG (rmw_get_error_string ().str );
355- if (RMW_RET_BAD_ALLOC == ret ) {
356- return RCL_RET_BAD_ALLOC ;
357- }
358- return RCL_RET_ERROR ;
353+ // RCL_SET_ERROR_MSG(rmw_get_error_string().str);
354+ return rcl_convert_rmw_ret_to_rcl_ret (ret );
359355 }
360356 RCUTILS_LOG_DEBUG_NAMED (
361357 ROS_PACKAGE_NAME , "Subscription serialized take succeeded: %s" , taken ? "true" : "false" );
@@ -376,6 +372,7 @@ rcl_take_loaned_message(
376372 if (!rcl_subscription_is_valid (subscription )) {
377373 return RCL_RET_SUBSCRIPTION_INVALID ; // error already set
378374 }
375+ RCL_CHECK_ARGUMENT_FOR_NULL (loaned_message , RCL_RET_INVALID_ARGUMENT );
379376 if (* loaned_message ) {
380377 RCL_SET_ERROR_MSG ("loaned message is already initialized" );
381378 return RCL_RET_INVALID_ARGUMENT ;
@@ -389,11 +386,7 @@ rcl_take_loaned_message(
389386 rmw_ret_t ret = rmw_take_loaned_message_with_info (
390387 subscription -> impl -> rmw_handle , loaned_message , & taken , message_info_local , allocation );
391388 if (ret != RMW_RET_OK ) {
392- RCL_SET_ERROR_MSG (rmw_get_error_string ().str );
393- if (RMW_RET_BAD_ALLOC == ret ) {
394- return RCL_RET_BAD_ALLOC ;
395- }
396- return RCL_RET_ERROR ;
389+ return rcl_convert_rmw_ret_to_rcl_ret (ret );
397390 }
398391 RCUTILS_LOG_DEBUG_NAMED (
399392 ROS_PACKAGE_NAME , "Subscription loaned take succeeded: %s" , taken ? "true" : "false" );
@@ -413,8 +406,9 @@ rcl_return_loaned_message_from_subscription(
413406 return RCL_RET_SUBSCRIPTION_INVALID ; // error already set
414407 }
415408 RCL_CHECK_ARGUMENT_FOR_NULL (loaned_message , RCL_RET_INVALID_ARGUMENT );
416- return rmw_return_loaned_message_from_subscription (
417- subscription -> impl -> rmw_handle , loaned_message );
409+ return rcl_convert_rmw_ret_to_rcl_ret (
410+ rmw_return_loaned_message_from_subscription (
411+ subscription -> impl -> rmw_handle , loaned_message ));
418412}
419413
420414const char *
0 commit comments