rcl  master
C API providing common ROS client library functionality.
subscription.h
Go to the documentation of this file.
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_generator_c/message_type_support_struct.h"
24 
25 #include "rcl/macros.h"
26 #include "rcl/node.h"
27 #include "rcl/visibility_control.h"
28 
30 struct rcl_subscription_impl_t;
31 
33 typedef struct rcl_subscription_t
34 {
35  struct rcl_subscription_impl_t * impl;
37 
40 {
46 
49 
51 
59 
61 
150 rcl_ret_t
152  rcl_subscription_t * subscription,
153  const rcl_node_t * node,
154  const rosidl_message_type_support_t * type_support,
155  const char * topic_name,
156  const rcl_subscription_options_t * options);
157 
159 
186 rcl_ret_t
187 rcl_subscription_fini(rcl_subscription_t * subscription, rcl_node_t * node);
188 
190 
201 
203 
259 rcl_ret_t
260 rcl_take(
261  const rcl_subscription_t * subscription,
262  void * ros_message,
263  rmw_message_info_t * message_info);
264 
266 
302 rcl_ret_t
304  const rcl_subscription_t * subscription,
305  rcl_serialized_message_t * serialized_message,
306  rmw_message_info_t * message_info);
307 
309 
332 const char *
334 
336 
361 
363 
392 
394 
412 bool
413 rcl_subscription_is_valid(const rcl_subscription_t * subscription);
414 
416 
437 rmw_ret_t
439  const rcl_subscription_t * subscription,
440  size_t * publisher_count);
441 
442 #ifdef __cplusplus
443 }
444 #endif
445 
446 #endif // RCL__SUBSCRIPTION_H_
rmw_subscription_t * rcl_subscription_get_rmw_handle(const rcl_subscription_t *subscription)
Return the rmw subscription handle.
Options available for a rcl subscription.
Definition: subscription.h:39
struct rcl_subscription_t rcl_subscription_t
Structure which encapsulates a ROS Subscription.
rmw_ret_t rcl_ret_t
Definition: types.h:20
rcl_ret_t rcl_subscription_init(rcl_subscription_t *subscription, const rcl_node_t *node, const rosidl_message_type_support_t *type_support, const char *topic_name, const rcl_subscription_options_t *options)
Initialize a ROS subscription.
rmw_qos_profile_t qos
Middleware quality of service settings for the subscription.
Definition: subscription.h:42
bool rcl_subscription_is_valid(const rcl_subscription_t *subscription)
Check that the subscription is valid.
const rcl_subscription_options_t * rcl_subscription_get_options(const rcl_subscription_t *subscription)
Return the rcl subscription options.
rcl_subscription_options_t rcl_subscription_get_default_options(void)
Return the default subscription options in a rcl_subscription_options_t.
#define RCL_WARN_UNUSED
Ignored return values of functions with this macro will emit a warning.
Definition: macros.h:25
struct rcl_subscription_options_t rcl_subscription_options_t
Options available for a rcl subscription.
#define RCL_PUBLIC
Definition: visibility_control.h:48
rcl_ret_t rcl_take_serialized_message(const rcl_subscription_t *subscription, rcl_serialized_message_t *serialized_message, rmw_message_info_t *message_info)
Take a serialized raw message from a topic using a rcl subscription.
rmw_ret_t rcl_subscription_get_publisher_count(const rcl_subscription_t *subscription, size_t *publisher_count)
Get the number of publishers matched to a subscription.
struct rcl_subscription_impl_t * impl
Definition: subscription.h:35
Structure which encapsulates a ROS Subscription.
Definition: subscription.h:33
rcl_ret_t rcl_take(const rcl_subscription_t *subscription, void *ros_message, rmw_message_info_t *message_info)
Take a ROS message from a topic using a rcl subscription.
int32_t rmw_ret_t
bool ignore_local_publications
If true, messages published from within the same node are ignored.
Definition: subscription.h:44
rcl_allocator_t allocator
Custom allocator for the subscription, used for incidental allocations.
Definition: subscription.h:47
Structure which encapsulates a ROS Node.
Definition: node.h:39
const char * rcl_subscription_get_topic_name(const rcl_subscription_t *subscription)
Get the topic name for the subscription.
rcl_ret_t rcl_subscription_fini(rcl_subscription_t *subscription, rcl_node_t *node)
Finalize a rcl_subscription_t.
rcl_subscription_t rcl_get_zero_initialized_subscription(void)
Return a rcl_subscription_t struct with members set to NULL.