ROS 2 rclcpp + rcl - jazzy
jazzy
ROS 2 C++ Client Library with ROS Client Library
|
#include <rclcpp/subscription_base.hpp>
Public Types | |
using | IntraProcessManagerWeakPtr = std::weak_ptr< rclcpp::experimental::IntraProcessManager > |
Public Member Functions | |
RCLCPP_PUBLIC | 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, const SubscriptionEventCallbacks &event_callbacks, bool use_default_callbacks, DeliveredMessageKind delivered_message_kind=DeliveredMessageKind::ROS_MESSAGE) |
Constructor. More... | |
virtual RCLCPP_PUBLIC | ~SubscriptionBase () |
Destructor. | |
RCLCPP_PUBLIC void | bind_event_callbacks (const SubscriptionEventCallbacks &event_callbacks, bool use_default_callbacks) |
Add event handlers for passed in event_callbacks. | |
RCLCPP_PUBLIC const char * | get_topic_name () const |
Get the topic that this subscription is subscribed on. | |
RCLCPP_PUBLIC std::shared_ptr< rcl_subscription_t > | get_subscription_handle () |
RCLCPP_PUBLIC std::shared_ptr< const rcl_subscription_t > | get_subscription_handle () const |
RCLCPP_PUBLIC const std::unordered_map< rcl_subscription_event_type_t, std::shared_ptr< rclcpp::EventHandlerBase > > & | get_event_handlers () const |
Get all the QoS event handlers associated with this subscription. More... | |
RCLCPP_PUBLIC rclcpp::QoS | get_actual_qos () const |
Get the actual QoS settings, after the defaults have been determined. More... | |
RCLCPP_PUBLIC 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... | |
RCLCPP_PUBLIC 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 RCLCPP_PUBLIC std::shared_ptr< void > | create_message ()=0 |
Borrow a new message. More... | |
virtual RCLCPP_PUBLIC std::shared_ptr< rclcpp::SerializedMessage > | create_serialized_message ()=0 |
Borrow a new serialized message. More... | |
virtual RCLCPP_PUBLIC 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 RCLCPP_PUBLIC void | handle_serialized_message (const std::shared_ptr< rclcpp::SerializedMessage > &serialized_message, const rclcpp::MessageInfo &message_info)=0 |
virtual RCLCPP_PUBLIC void | handle_loaned_message (void *loaned_message, const rclcpp::MessageInfo &message_info)=0 |
virtual RCLCPP_PUBLIC void | return_message (std::shared_ptr< void > &message)=0 |
Return the message borrowed in create_message. More... | |
virtual RCLCPP_PUBLIC void | return_serialized_message (std::shared_ptr< rclcpp::SerializedMessage > &message)=0 |
Return the message borrowed in create_serialized_message. More... | |
RCLCPP_PUBLIC const rosidl_message_type_support_t & | get_message_type_support_handle () const |
RCLCPP_PUBLIC bool | is_serialized () const |
Return if the subscription is serialized. More... | |
RCLCPP_PUBLIC DeliveredMessageKind | get_delivered_message_kind () const |
Return the delivered message kind. More... | |
RCLCPP_PUBLIC size_t | get_publisher_count () const |
Get matching publisher count. More... | |
RCLCPP_PUBLIC bool | can_loan_messages () const |
Check if subscription instance can loan messages. More... | |
RCLCPP_PUBLIC void | setup_intra_process (uint64_t intra_process_subscription_id, IntraProcessManagerWeakPtr weak_ipm) |
Implemenation detail. | |
RCLCPP_PUBLIC rclcpp::Waitable::SharedPtr | get_intra_process_waitable () const |
Return the waitable for intra-process. More... | |
RCLCPP_PUBLIC 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... | |
RCLCPP_PUBLIC std::vector< rclcpp::NetworkFlowEndpoint > | get_network_flow_endpoints () const |
Get network flow endpoints. More... | |
void | set_on_new_message_callback (std::function< void(size_t)> callback) |
Set a callback to be called when each new message is received. More... | |
void | clear_on_new_message_callback () |
Unset the callback registered for new messages, if any. | |
void | set_on_new_intra_process_message_callback (std::function< void(size_t)> callback) |
Set a callback to be called when each new intra-process message is received. More... | |
void | clear_on_new_intra_process_message_callback () |
Unset the callback registered for new intra-process messages, if any. | |
void | set_on_new_qos_event_callback (std::function< void(size_t)> callback, rcl_subscription_event_type_t event_type) |
Set a callback to be called when each new qos event instance occurs. More... | |
void | clear_on_new_qos_event_callback (rcl_subscription_event_type_t event_type) |
Unset the callback registered for new qos events, if any. | |
RCLCPP_PUBLIC bool | is_cft_enabled () const |
Check if content filtered topic feature of the subscription instance is enabled. More... | |
RCLCPP_PUBLIC void | set_content_filter (const std::string &filter_expression, const std::vector< std::string > &expression_parameters={}) |
Set the filter expression and expression parameters for the subscription. More... | |
RCLCPP_PUBLIC rclcpp::ContentFilterOptions | get_content_filter () const |
Get the filter expression and expression parameters for the subscription. More... | |
virtual RCLCPP_PUBLIC rclcpp::dynamic_typesupport::DynamicMessageType::SharedPtr | get_shared_dynamic_message_type ()=0 |
virtual RCLCPP_PUBLIC rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr | get_shared_dynamic_message ()=0 |
virtual RCLCPP_PUBLIC rclcpp::dynamic_typesupport::DynamicSerializationSupport::SharedPtr | get_shared_dynamic_serialization_support ()=0 |
virtual RCLCPP_PUBLIC rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr | create_dynamic_message ()=0 |
Borrow a new serialized message (this clones!) More... | |
virtual RCLCPP_PUBLIC void | return_dynamic_message (rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr &message)=0 |
virtual RCLCPP_PUBLIC void | handle_dynamic_message (const rclcpp::dynamic_typesupport::DynamicMessage::SharedPtr &message, const rclcpp::MessageInfo &message_info)=0 |
RCLCPP_PUBLIC bool | take_dynamic_message (rclcpp::dynamic_typesupport::DynamicMessage &message_out, rclcpp::MessageInfo &message_info_out) |
Protected Member Functions | |
template<typename EventCallbackT > | |
void | add_event_handler (const EventCallbackT &callback, const rcl_subscription_event_type_t event_type) |
RCLCPP_PUBLIC void | default_incompatible_qos_callback (QOSRequestedIncompatibleQoSInfo &info) const |
RCLCPP_PUBLIC void | default_incompatible_type_callback (IncompatibleTypeInfo &info) const |
RCLCPP_PUBLIC bool | matches_any_intra_process_publishers (const rmw_gid_t *sender_gid) const |
RCLCPP_PUBLIC void | set_on_new_message_callback (rcl_event_callback_t callback, const void *user_data) |
Protected Attributes | |
rclcpp::node_interfaces::NodeBaseInterface *const | node_base_ |
std::shared_ptr< rcl_node_t > | node_handle_ |
std::recursive_mutex | callback_mutex_ |
std::function< void(size_t)> | on_new_message_callback_ {nullptr} |
std::shared_ptr< rcl_subscription_t > | subscription_handle_ |
std::shared_ptr< rcl_subscription_t > | intra_process_subscription_handle_ |
rclcpp::Logger | node_logger_ |
std::unordered_map< rcl_subscription_event_type_t, std::shared_ptr< rclcpp::EventHandlerBase > > | event_handlers_ |
bool | use_intra_process_ |
IntraProcessManagerWeakPtr | weak_ipm_ |
uint64_t | intra_process_subscription_id_ |
std::shared_ptr< rclcpp::experimental::SubscriptionIntraProcessBase > | subscription_intra_process_ |
const SubscriptionEventCallbacks | event_callbacks_ |
Virtual base class for subscriptions. This pattern allows us to iterate over different template specializations of Subscription, among other things.
Definition at line 89 of file subscription_base.hpp.
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, | ||
const SubscriptionEventCallbacks & | event_callbacks, | ||
bool | use_default_callbacks, | ||
DeliveredMessageKind | delivered_message_kind = DeliveredMessageKind::ROS_MESSAGE |
||
) |
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] | delivered_message_kind | Enum flag to change how the message will be received and delivered |
Definition at line 40 of file subscription_base.cpp.
References bind_event_callbacks(), rclcpp::expand_topic_or_service_name(), rclcpp::Logger::get_child(), rclcpp::get_node_logger(), rcl_get_zero_initialized_subscription(), rcl_node_get_name(), rcl_node_get_namespace(), RCL_RET_OK, RCL_RET_TOPIC_NAME_INVALID, rcl_subscription_fini(), and rcl_subscription_init().
bool 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.
Definition at line 302 of file subscription_base.cpp.
References rcl_subscription_can_loan_messages().
|
pure virtual |
Borrow a new serialized message (this clones!)
Implemented in rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >, rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >, and rclcpp::GenericSubscription.
|
pure virtual |
Borrow a new message.
Implemented in rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >, rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >, and rclcpp::GenericSubscription.
|
pure virtual |
Borrow a new serialized message.
Implemented in rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >, rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >, and rclcpp::GenericSubscription.
bool 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. |
Definition at line 380 of file subscription_base.cpp.
References get_intra_process_waitable().
rclcpp::QoS 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 subscription, 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 |
Definition at line 200 of file subscription_base.cpp.
References rclcpp::QoSInitialization::from_rmw(), and rcl_subscription_get_actual_qos().
Referenced by rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >::Subscription().
rclcpp::ContentFilterOptions SubscriptionBase::get_content_filter | ( | ) | const |
Get the filter expression and expression parameters for the subscription.
RCLBadAlloc | if memory cannot be allocated |
RCLError | if an unexpect error occurs |
Definition at line 504 of file subscription_base.cpp.
References rclcpp::ContentFilterOptions::expression_parameters, rclcpp::ContentFilterOptions::filter_expression, rclcpp::get_logger(), rcl_get_zero_initialized_subscription_content_filter_options(), RCL_RET_OK, rcl_subscription_content_filter_options_fini(), and rcl_subscription_get_content_filter().
rclcpp::DeliveredMessageKind SubscriptionBase::get_delivered_message_kind | ( | ) | const |
Return the delivered message kind.
DeliveredMessageKind
, which adjusts how messages are received and delivered. Definition at line 271 of file subscription_base.cpp.
const std::unordered_map< rcl_subscription_event_type_t, std::shared_ptr< rclcpp::EventHandlerBase > > & SubscriptionBase::get_event_handlers | ( | ) | const |
Get all the QoS event handlers associated with this subscription.
Definition at line 194 of file subscription_base.cpp.
rclcpp::Waitable::SharedPtr SubscriptionBase::get_intra_process_waitable | ( | ) | const |
Return the waitable for intra-process.
std::runtime_error | if the intra process manager is destroyed |
Definition at line 321 of file subscription_base.cpp.
Referenced by exchange_in_use_by_wait_set_state().
std::vector< rclcpp::NetworkFlowEndpoint > SubscriptionBase::get_network_flow_endpoints | ( | ) | const |
Get network flow endpoints.
Describes network flow endpoints that this subscription is receiving messages on
Definition at line 403 of file subscription_base.cpp.
References RCL_RET_OK.
size_t SubscriptionBase::get_publisher_count | ( | ) | const |
Get matching publisher count.
Definition at line 277 of file subscription_base.cpp.
References RCL_RET_OK, and rcl_subscription_get_publisher_count().
|
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< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >, rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >, and rclcpp::GenericSubscription.
bool SubscriptionBase::is_cft_enabled | ( | ) | const |
Check if content filtered topic feature of the subscription instance is enabled.
Definition at line 457 of file subscription_base.cpp.
References rcl_subscription_is_cft_enabled().
bool SubscriptionBase::is_serialized | ( | ) | const |
Return if the subscription is serialized.
true
if the subscription is serialized, false
otherwise Definition at line 265 of file subscription_base.cpp.
|
pure virtual |
Return the message borrowed in create_message.
[in] | message | Shared pointer to the returned message. |
Implemented in rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, 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< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >, rclcpp::Subscription< rcl_interfaces::msg::ParameterEvent >, and rclcpp::GenericSubscription.
void SubscriptionBase::set_content_filter | ( | const std::string & | filter_expression, |
const std::vector< std::string > & | expression_parameters = {} |
||
) |
Set the filter expression and expression parameters for the subscription.
[in] | filter_expression | A filter expression to set. |
[in] | expression_parameters | Array of expression parameters to set. |
RCLBadAlloc | if memory cannot be allocated |
RCLError | if an unexpect error occurs |
Definition at line 463 of file subscription_base.cpp.
References rclcpp::get_c_string(), rclcpp::get_c_vector_string(), rclcpp::get_logger(), rcl_get_zero_initialized_subscription_content_filter_options(), RCL_RET_OK, rcl_subscription_content_filter_options_fini(), rcl_subscription_content_filter_options_init(), and rcl_subscription_set_content_filter().
|
inline |
Set a callback to be called when each new intra-process message is received.
The callback receives a size_t which is the number of messages received since the last time this callback was called. Normally this is 1, but can be > 1 if messages were received before any callback was set.
Calling it again will clear any previously set callback.
This function is thread-safe.
If you want more information available in the callback, like the subscription or other information, you may use a lambda with captures or std::bind.
[in] | callback | functor to be called when a new message is received |
Definition at line 436 of file subscription_base.hpp.
References rclcpp::get_logger().
|
inline |
Set a callback to be called when each new message is received.
The callback receives a size_t which is the number of messages received since the last time this callback was called. Normally this is 1, but can be > 1 if messages were received before any callback was set.
Since this callback is called from the middleware, you should aim to make it fast and not blocking. If you need to do a lot of work or wait for some other event, you should spin it off to another thread, otherwise you risk blocking the middleware.
Calling it again will clear any previously set callback.
This function is thread-safe.
If you want more information available in the callback, like the subscription or other information, you may use a lambda with captures or std::bind.
[in] | callback | functor to be called when a new message is received |
Definition at line 358 of file subscription_base.hpp.
Referenced by clear_on_new_message_callback().
|
inline |
Set a callback to be called when each new qos event instance occurs.
The callback receives a size_t which is the number of events that occurred since the last time this callback was called. Normally this is 1, but can be > 1 if events occurred before any callback was set.
Since this callback is called from the middleware, you should aim to make it fast and not blocking. If you need to do a lot of work or wait for some other event, you should spin it off to another thread, otherwise you risk blocking the middleware.
Calling it again will clear any previously set callback.
An exception will be thrown if the callback is not callable.
This function is thread-safe.
If you want more information available in the callback, like the qos event or other information, you may use a lambda with captures or std::bind.
[in] | callback | functor to be called when a new event occurs |
[in] | event_type | identifier for the qos event we want to attach the callback to |
Definition at line 499 of file subscription_base.hpp.
References rclcpp::get_logger().
bool 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, |
Definition at line 238 of file subscription_base.cpp.
References rclcpp::SerializedMessage::get_rcl_serialized_message(), rclcpp::MessageInfo::get_rmw_message_info(), RCL_RET_OK, RCL_RET_SUBSCRIPTION_TAKE_FAILED, and rcl_take_serialized_message().
bool 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, |
Definition at line 213 of file subscription_base.cpp.
References rclcpp::MessageInfo::get_rmw_message_info(), RCL_RET_OK, RCL_RET_SUBSCRIPTION_TAKE_FAILED, and rcl_take().
Referenced by rclcpp::Subscription< MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT >::take().