rcl  master
C API providing common ROS client library functionality.
subscription.h
1 // Copyright 2015 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCL__SUBSCRIPTION_H_
16 #define RCL__SUBSCRIPTION_H_
17 
18 #ifdef __cplusplus
19 extern "C"
20 {
21 #endif
22 
23 #include "rosidl_runtime_c/message_type_support_struct.h"
24 
25 #include "rcl/macros.h"
26 #include "rcl/node.h"
27 #include "rcl/visibility_control.h"
28 
29 #include "rmw/message_sequence.h"
30 
32 struct rcl_subscription_impl_t;
33 
35 typedef struct rcl_subscription_t
36 {
38  struct rcl_subscription_impl_t * impl;
40 
43 {
47 
52 
54 
58 RCL_PUBLIC
59 RCL_WARN_UNUSED
61 rcl_get_zero_initialized_subscription(void);
62 
64 
152 RCL_PUBLIC
153 RCL_WARN_UNUSED
154 rcl_ret_t
155 rcl_subscription_init(
156  rcl_subscription_t * subscription,
157  const rcl_node_t * node,
158  const rosidl_message_type_support_t * type_support,
159  const char * topic_name,
160  const rcl_subscription_options_t * options
161 );
162 
164 
189 RCL_PUBLIC
190 RCL_WARN_UNUSED
191 rcl_ret_t
192 rcl_subscription_fini(rcl_subscription_t * subscription, rcl_node_t * node);
193 
195 
202 RCL_PUBLIC
203 RCL_WARN_UNUSED
205 rcl_subscription_get_default_options(void);
206 
208 
263 RCL_PUBLIC
264 RCL_WARN_UNUSED
265 rcl_ret_t
266 rcl_take(
267  const rcl_subscription_t * subscription,
268  void * ros_message,
269  rmw_message_info_t * message_info,
270  rmw_subscription_allocation_t * allocation
271 );
272 
274 
314 RCL_PUBLIC
315 RCL_WARN_UNUSED
316 rcl_ret_t
317 rcl_take_sequence(
318  const rcl_subscription_t * subscription,
319  size_t count,
320  rmw_message_sequence_t * message_sequence,
321  rmw_message_info_sequence_t * message_info_sequence,
322  rmw_subscription_allocation_t * allocation
323 );
324 
326 
361 RCL_PUBLIC
362 RCL_WARN_UNUSED
363 rcl_ret_t
364 rcl_take_serialized_message(
365  const rcl_subscription_t * subscription,
366  rcl_serialized_message_t * serialized_message,
367  rmw_message_info_t * message_info,
368  rmw_subscription_allocation_t * allocation);
369 
371 
399 RCL_PUBLIC
400 RCL_WARN_UNUSED
401 rcl_ret_t
402 rcl_take_loaned_message(
403  const rcl_subscription_t * subscription,
404  void ** loaned_message,
405  rmw_message_info_t * message_info,
406  rmw_subscription_allocation_t * allocation);
407 
409 
431 RCL_PUBLIC
432 RCL_WARN_UNUSED
433 rcl_ret_t
434 rcl_return_loaned_message_from_subscription(
435  const rcl_subscription_t * subscription,
436  void * loaned_message);
437 
439 
460 RCL_PUBLIC
461 RCL_WARN_UNUSED
462 const char *
463 rcl_subscription_get_topic_name(const rcl_subscription_t * subscription);
464 
466 
487 RCL_PUBLIC
488 RCL_WARN_UNUSED
490 rcl_subscription_get_options(const rcl_subscription_t * subscription);
491 
493 
518 RCL_PUBLIC
519 RCL_WARN_UNUSED
521 rcl_subscription_get_rmw_handle(const rcl_subscription_t * subscription);
522 
524 
541 RCL_PUBLIC
542 bool
543 rcl_subscription_is_valid(const rcl_subscription_t * subscription);
544 
546 
565 RCL_PUBLIC
566 RCL_WARN_UNUSED
567 rmw_ret_t
568 rcl_subscription_get_publisher_count(
569  const rcl_subscription_t * subscription,
570  size_t * publisher_count);
571 
573 
593 RCL_PUBLIC
594 RCL_WARN_UNUSED
595 const rmw_qos_profile_t *
596 rcl_subscription_get_actual_qos(const rcl_subscription_t * subscription);
597 
599 
603 RCL_PUBLIC
604 bool
605 rcl_subscription_can_loan_messages(const rcl_subscription_t * subscription);
606 
607 #ifdef __cplusplus
608 }
609 #endif
610 
611 #endif // RCL__SUBSCRIPTION_H_
rcl_node_t
Structure which encapsulates a ROS Node.
Definition: node.h:37
rcl_subscription_options_t::allocator
rcl_allocator_t allocator
Custom allocator for the subscription, used for incidental allocations.
Definition: subscription.h:48
rcl_subscription_options_t::rmw_subscription_options
rmw_subscription_options_t rmw_subscription_options
rmw specific subscription options, e.g. the rmw implementation specific payload.
Definition: subscription.h:50
rmw_message_info_t
rmw_subscription_allocation_t
rcl_subscription_t::impl
struct rcl_subscription_impl_t * impl
Pointer to the subscription implementation.
Definition: subscription.h:38
rcutils_uint8_array_t
rmw_message_info_sequence_t
rcl_subscription_options_t::qos
rmw_qos_profile_t qos
Middleware quality of service settings for the subscription.
Definition: subscription.h:45
rmw_subscription_t
rmw_ret_t
int32_t rmw_ret_t
rmw_message_sequence_t
rcl_subscription_options_t
Options available for a rcl subscription.
Definition: subscription.h:42
rmw_subscription_options_t
message_sequence.h
rcutils_allocator_t
rcl_subscription_t
Structure which encapsulates a ROS Subscription.
Definition: subscription.h:35
rmw_qos_profile_t