rclcpp
master
C++ ROS Client Library API
|
#include <subscription_base.hpp>
Public Types | |
using | IntraProcessManagerWeakPtr = std::weak_ptr< rclcpp::experimental::IntraProcessManager > |
Public Member Functions | |
SubscriptionBase (rclcpp::node_interfaces::NodeBaseInterface *node_base, const rosidl_message_type_support_t &type_support_handle, const std::string &topic_name, const rcl_subscription_options_t &subscription_options, bool is_serialized=false) | |
Constructor. More... | |
virtual | ~SubscriptionBase () |
Destructor. More... | |
const char * | get_topic_name () const |
Get the topic that this subscription is subscribed on. More... | |
std::shared_ptr< rcl_subscription_t > | get_subscription_handle () |
std::shared_ptr< const rcl_subscription_t > | get_subscription_handle () const |
const std::vector< std::shared_ptr< rclcpp::QOSEventHandlerBase > > & | get_event_handlers () const |
Get all the QoS event handlers associated with this subscription. More... | |
rclcpp::QoS | get_actual_qos () const |
Get the actual QoS settings, after the defaults have been determined. More... | |
bool | take_type_erased (void *message_out, rclcpp::MessageInfo &message_info_out) |
Take the next inter-process message from the subscription as a type erased pointer. More... | |
bool | take_serialized (rclcpp::SerializedMessage &message_out, rclcpp::MessageInfo &message_info_out) |
Take the next inter-process message, in its serialized form, from the subscription. More... | |
virtual std::shared_ptr< void > | create_message ()=0 |
Borrow a new message. More... | |
virtual std::shared_ptr< rclcpp::SerializedMessage > | create_serialized_message ()=0 |
Borrow a new serialized message. More... | |
virtual void | handle_message (std::shared_ptr< void > &message, const rclcpp::MessageInfo &message_info)=0 |
Check if we need to handle the message, and execute the callback if we do. More... | |
virtual void | handle_loaned_message (void *loaned_message, const rclcpp::MessageInfo &message_info)=0 |
virtual void | return_message (std::shared_ptr< void > &message)=0 |
Return the message borrowed in create_message. More... | |
virtual void | return_serialized_message (std::shared_ptr< rclcpp::SerializedMessage > &message)=0 |
Return the message borrowed in create_serialized_message. More... | |
const rosidl_message_type_support_t & | get_message_type_support_handle () const |
bool | is_serialized () const |
Return if the subscription is serialized. More... | |
size_t | get_publisher_count () const |
Get matching publisher count. More... | |
bool | can_loan_messages () const |
Check if subscription instance can loan messages. More... | |
void | setup_intra_process (uint64_t intra_process_subscription_id, IntraProcessManagerWeakPtr weak_ipm) |
Implemenation detail. More... | |
rclcpp::Waitable::SharedPtr | get_intra_process_waitable () const |
Return the waitable for intra-process. More... | |
bool | exchange_in_use_by_wait_set_state (void *pointer_to_subscription_part, bool in_use_state) |
Exchange state of whether or not a part of the subscription is used by a wait set. More... | |
std::vector< rclcpp::NetworkFlowEndpoint > | get_network_flow_endpoints () const |
Get network flow endpoints. More... | |
Public Member Functions inherited from std::enable_shared_from_this< SubscriptionBase > | |
T | enable_shared_from_this (T... args) |
T | operator= (T... args) |
T | shared_from_this (T... args) |
T | ~enable_shared_from_this (T... args) |
Protected Member Functions | |
template<typename EventCallbackT > | |
void | add_event_handler (const EventCallbackT &callback, const rcl_subscription_event_type_t event_type) |
void | default_incompatible_qos_callback (QOSRequestedIncompatibleQoSInfo &info) const |
bool | matches_any_intra_process_publishers (const rmw_gid_t *sender_gid) const |
Virtual base class for subscriptions. This pattern allows us to iterate over different template specializations of Subscription, among other things.
using rclcpp::SubscriptionBase::IntraProcessManagerWeakPtr = std::weak_ptr<rclcpp::experimental::IntraProcessManager> |
rclcpp::SubscriptionBase::SubscriptionBase | ( | rclcpp::node_interfaces::NodeBaseInterface * | node_base, |
const rosidl_message_type_support_t & | type_support_handle, | ||
const std::string & | topic_name, | ||
const rcl_subscription_options_t & | subscription_options, | ||
bool | is_serialized = false |
||
) |
Constructor.
This accepts rcl_subscription_options_t instead of rclcpp::SubscriptionOptions because rclcpp::SubscriptionOptions::to_rcl_subscription_options depends on the message type.
[in] | node_base | NodeBaseInterface pointer used in parts of the setup. |
[in] | type_support_handle | rosidl type support struct, for the Message type of the topic. |
[in] | topic_name | Name of the topic to subscribe to. |
[in] | subscription_options | Options for the subscription. |
[in] | is_serialized | is true if the message will be delivered still serialized |
|
virtual |
Destructor.
const char* rclcpp::SubscriptionBase::get_topic_name | ( | ) | const |
Get the topic that this subscription is subscribed on.
std::shared_ptr<rcl_subscription_t> rclcpp::SubscriptionBase::get_subscription_handle | ( | ) |
std::shared_ptr<const rcl_subscription_t> rclcpp::SubscriptionBase::get_subscription_handle | ( | ) | const |
const std::vector<std::shared_ptr<rclcpp::QOSEventHandlerBase> >& rclcpp::SubscriptionBase::get_event_handlers | ( | ) | const |
rclcpp::QoS rclcpp::SubscriptionBase::get_actual_qos | ( | ) | const |
Get the actual QoS settings, after the defaults have been determined.
The actual configuration applied when using RMW_QOS_POLICY_*_SYSTEM_DEFAULT can only be resolved after the creation of the publisher, and it depends on the underlying rmw implementation. If the underlying setting in use can't be represented in ROS terms, it will be set to RMW_QOS_POLICY_*_UNKNOWN. May throw runtime_error when an unexpected error occurs.
std::runtime_error | if failed to get qos settings |
bool rclcpp::SubscriptionBase::take_type_erased | ( | void * | message_out, |
rclcpp::MessageInfo & | message_info_out | ||
) |
Take the next inter-process message from the subscription as a type erased pointer.
The only difference is that it takes a type erased pointer rather than a reference to the exact message type.
This type erased version facilitates using the subscriptions in a type agnostic way using SubscriptionBase::create_message() and SubscriptionBase::handle_message().
[out] | message_out | The type erased message pointer into which take will copy the data. |
[out] | message_info_out | The message info for the taken message. |
any | rcl errors from rcl_take, |
bool rclcpp::SubscriptionBase::take_serialized | ( | rclcpp::SerializedMessage & | message_out, |
rclcpp::MessageInfo & | message_info_out | ||
) |
Take the next inter-process message, in its serialized form, from the subscription.
For now, if data is taken (written) into the message_out and message_info_out then true will be returned. Unlike Subscription::take(), taking data serialized is not possible via intra-process for the time being, so it will not need to de-duplicate data in any case.
[out] | message_out | The serialized message data structure used to store the taken message. |
[out] | message_info_out | The message info for the taken message. |
any | rcl errors from rcl_take, |
|
pure virtual |
Borrow a new message.
Implemented in rclcpp::Subscription< CallbackMessageT, AllocatorT, MessageMemoryStrategyT >, rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >, and rclcpp::GenericSubscription.
|
pure virtual |
Borrow a new serialized message.
Implemented in rclcpp::Subscription< CallbackMessageT, AllocatorT, MessageMemoryStrategyT >, rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >, and rclcpp::GenericSubscription.
|
pure virtual |
Check if we need to handle the message, and execute the callback if we do.
[in] | message | Shared pointer to the message to handle. |
[in] | message_info | Metadata associated with this message. |
Implemented in rclcpp::Subscription< CallbackMessageT, AllocatorT, MessageMemoryStrategyT >, rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >, and rclcpp::GenericSubscription.
|
pure virtual |
|
pure virtual |
Return the message borrowed in create_message.
[in] | message | Shared pointer to the returned message. |
Implemented in rclcpp::Subscription< CallbackMessageT, AllocatorT, MessageMemoryStrategyT >, rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >, and rclcpp::GenericSubscription.
|
pure virtual |
Return the message borrowed in create_serialized_message.
[in] | message | Shared pointer to the returned message. |
Implemented in rclcpp::Subscription< CallbackMessageT, AllocatorT, MessageMemoryStrategyT >, rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >, and rclcpp::GenericSubscription.
const rosidl_message_type_support_t& rclcpp::SubscriptionBase::get_message_type_support_handle | ( | ) | const |
bool rclcpp::SubscriptionBase::is_serialized | ( | ) | const |
Return if the subscription is serialized.
true
if the subscription is serialized, false
otherwise size_t rclcpp::SubscriptionBase::get_publisher_count | ( | ) | const |
Get matching publisher count.
bool rclcpp::SubscriptionBase::can_loan_messages | ( | ) | const |
Check if subscription instance can loan messages.
Depending on the middleware and the message type, this will return true if the middleware can allocate a ROS message instance.
void rclcpp::SubscriptionBase::setup_intra_process | ( | uint64_t | intra_process_subscription_id, |
IntraProcessManagerWeakPtr | weak_ipm | ||
) |
Implemenation detail.
rclcpp::Waitable::SharedPtr rclcpp::SubscriptionBase::get_intra_process_waitable | ( | ) | const |
Return the waitable for intra-process.
std::runtime_error | if the intra process manager is destroyed |
bool rclcpp::SubscriptionBase::exchange_in_use_by_wait_set_state | ( | void * | pointer_to_subscription_part, |
bool | in_use_state | ||
) |
Exchange state of whether or not a part of the subscription is used by a wait set.
Used to ensure parts of the subscription are not used with multiple wait sets simultaneously.
[in] | pointer_to_subscription_part | address of a subscription part |
[in] | in_use_state | the new state to exchange, true means "now in use", and false means "no longer in use". |
std::invalid_argument | If pointer_to_subscription_part is nullptr. |
std::runtime_error | If the pointer given is not a pointer to one of the parts of the subscription which can be used with a wait set. |
std::vector<rclcpp::NetworkFlowEndpoint> rclcpp::SubscriptionBase::get_network_flow_endpoints | ( | ) | const |
Get network flow endpoints.
Describes network flow endpoints that this subscription is receiving messages on
|
inlineprotected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |