Function rcl_subscription_init

Function Documentation

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.

After calling this function on a rcl_subscription_t, it can be used to take messages of the given type to the given topic using rcl_take().

The given rcl_node_t must be valid and the resulting rcl_subscription_t is only valid as long as the given rcl_node_t remains valid.

The rosidl_message_type_support_t is obtained on a per .msg type basis. When the user defines a ROS message, code is generated which provides the required rosidl_message_type_support_t object. This object can be obtained using a language appropriate mechanism.

Todo:

TODO(wjwwood) write these instructions once and link to it instead For C a macro can be used (for example std_msgs/String):

#include <rosidl_runtime_c/message_type_support_struct.h>
#include <std_msgs/msg/string.h>
const rosidl_message_type_support_t * string_ts =
  ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String);

For C++ a template function is used:

#include <rosidl_typesupport_cpp/message_type_support.hpp>
#include <std_msgs/msgs/string.hpp>
using rosidl_typesupport_cpp::get_message_type_support_handle;
const rosidl_message_type_support_t * string_ts =
  get_message_type_support_handle<std_msgs::msg::String>();

The rosidl_message_type_support_t object contains message type specific information used to publish messages.

The topic name must be a c string which follows the topic and service name format rules for unexpanded names, also known as non-fully qualified names:

The options struct allows the user to set the quality of service settings as well as a custom allocator which is used when (de)initializing the subscription to allocate space for incidental things, e.g. the topic name string.

Expected usage (for C messages):

#include <rcl/rcl.h>
#include <rosidl_runtime_c/message_type_support_struct.h>
#include <std_msgs/msg/string.h>

rcl_node_t node = rcl_get_zero_initialized_node();
rcl_node_options_t node_ops = rcl_node_get_default_options();
rcl_ret_t ret = rcl_node_init(&node, "node_name", "/my_namespace", &node_ops);
// ... error handling
const rosidl_message_type_support_t * ts =
  ROSIDL_GET_MSG_TYPE_SUPPORT(std_msgs, msg, String);
rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
rcl_subscription_options_t subscription_ops = rcl_subscription_get_default_options();
ret = rcl_subscription_init(&subscription, &node, ts, "chatter", &subscription_ops);
// ... error handling, and when finished deinitialization
ret = rcl_subscription_fini(&subscription, &node);
// ... error handling for rcl_subscription_fini()
ret = rcl_node_fini(&node);
// ... error handling for rcl_node_fini()

Attribute

Adherence

Allocates Memory

Yes

Thread-Safe

No

Uses Atomics

No

Lock-Free

Yes

Parameters:
  • subscription[out] preallocated subscription structure

  • node[in] valid rcl node handle

  • type_support[in] type support object for the topic’s type

  • topic_name[in] the name of the topic

  • options[in] subscription options, including quality of service settings

Returns:

RCL_RET_OK if subscription was initialized successfully, or

Returns:

RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or

Returns:

RCL_RET_ALREADY_INIT if the subcription is already initialized, or

Returns:

RCL_RET_NODE_INVALID if the node is invalid, or

Returns:

RCL_RET_BAD_ALLOC if allocating memory failed, or

Returns:

RCL_RET_TOPIC_NAME_INVALID if the given topic name is invalid, or

Returns:

RCL_RET_ERROR if an unspecified error occurs.