ROS 2 rclcpp + rcl - humble
humble
ROS 2 C++ Client Library with ROS Client Library
|
A publisher publishes messages of any type to a topic. More...
#include <rclcpp/publisher.hpp>
Public Types | |
using | PublishedType = typename rclcpp::TypeAdapter< MessageT >::custom_type |
MessageT::custom_type if MessageT is a TypeAdapter, otherwise just MessageT. | |
using | ROSMessageType = typename rclcpp::TypeAdapter< MessageT >::ros_message_type |
using | PublishedTypeAllocatorTraits = allocator::AllocRebind< PublishedType, AllocatorT > |
using | PublishedTypeAllocator = typename PublishedTypeAllocatorTraits::allocator_type |
using | PublishedTypeDeleter = allocator::Deleter< PublishedTypeAllocator, PublishedType > |
using | ROSMessageTypeAllocatorTraits = allocator::AllocRebind< ROSMessageType, AllocatorT > |
using | ROSMessageTypeAllocator = typename ROSMessageTypeAllocatorTraits::allocator_type |
using | ROSMessageTypeDeleter = allocator::Deleter< ROSMessageTypeAllocator, ROSMessageType > |
using | MessageAllocatorTraits = PublishedTypeAllocatorTraits |
using | MessageAllocator = PublishedTypeAllocator |
using | MessageDeleter = PublishedTypeDeleter |
using | MessageUniquePtr = std::unique_ptr< PublishedType, PublishedTypeDeleter > |
using | MessageSharedPtr = std::shared_ptr< const PublishedType > |
![]() | |
using | IntraProcessManagerSharedPtr = std::shared_ptr< rclcpp::experimental::IntraProcessManager > |
Public Member Functions | |
Publisher (rclcpp::node_interfaces::NodeBaseInterface *node_base, const std::string &topic, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator< AllocatorT > &options) | |
Default constructor. More... | |
virtual void | post_init_setup (rclcpp::node_interfaces::NodeBaseInterface *node_base, const std::string &topic, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator< AllocatorT > &options) |
Called post construction, so that construction may continue after shared_from_this() works. | |
rclcpp::LoanedMessage< ROSMessageType, AllocatorT > | borrow_loaned_message () |
Borrow a loaned ROS message from the middleware. More... | |
template<typename T > | |
std::enable_if_t< rosidl_generator_traits::is_message< T >::value &&std::is_same< T, ROSMessageType >::value > | publish (std::unique_ptr< T, ROSMessageTypeDeleter > msg) |
Publish a message on the topic. More... | |
template<typename T > | |
std::enable_if_t< rosidl_generator_traits::is_message< T >::value &&std::is_same< T, ROSMessageType >::value > | publish (const T &msg) |
Publish a message on the topic. More... | |
template<typename T > | |
std::enable_if_t< rclcpp::TypeAdapter< MessageT >::is_specialized::value &&std::is_same< T, PublishedType >::value > | publish (std::unique_ptr< T, PublishedTypeDeleter > msg) |
Publish a message on the topic. More... | |
template<typename T > | |
std::enable_if_t< rclcpp::TypeAdapter< MessageT >::is_specialized::value &&std::is_same< T, PublishedType >::value > | publish (const T &msg) |
Publish a message on the topic. More... | |
void | publish (const rcl_serialized_message_t &serialized_msg) |
void | publish (const SerializedMessage &serialized_msg) |
void | publish (rclcpp::LoanedMessage< ROSMessageType, AllocatorT > &&loaned_msg) |
Publish an instance of a LoanedMessage. More... | |
std::shared_ptr< PublishedTypeAllocator > | get_allocator () const |
PublishedTypeAllocator | get_published_type_allocator () const |
ROSMessageTypeAllocator | get_ros_message_type_allocator () const |
![]() | |
RCLCPP_PUBLIC | PublisherBase (rclcpp::node_interfaces::NodeBaseInterface *node_base, const std::string &topic, const rosidl_message_type_support_t &type_support, const rcl_publisher_options_t &publisher_options) |
Default constructor. More... | |
RCLCPP_PUBLIC const char * | get_topic_name () const |
Get the topic that this publisher publishes on. More... | |
RCLCPP_PUBLIC size_t | get_queue_size () const |
Get the queue size for this publisher. More... | |
RCLCPP_PUBLIC const rmw_gid_t & | get_gid () const |
Get the global identifier for this publisher (used in rmw and by DDS). More... | |
RCLCPP_PUBLIC std::shared_ptr< rcl_publisher_t > | get_publisher_handle () |
Get the rcl publisher handle. More... | |
RCLCPP_PUBLIC std::shared_ptr< const rcl_publisher_t > | get_publisher_handle () const |
Get the rcl publisher handle. More... | |
RCLCPP_PUBLIC const std::unordered_map< rcl_publisher_event_type_t, std::shared_ptr< rclcpp::QOSEventHandlerBase > > & | get_event_handlers () const |
Get all the QoS event handlers associated with this publisher. More... | |
RCLCPP_PUBLIC size_t | get_subscription_count () const |
Get subscription count. More... | |
RCLCPP_PUBLIC size_t | get_intra_process_subscription_count () const |
Get intraprocess subscription count. More... | |
RCLCPP_PUBLIC RCUTILS_WARN_UNUSED bool | assert_liveliness () const |
Manually assert that this Publisher is alive (for RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC). More... | |
RCLCPP_PUBLIC rclcpp::QoS | get_actual_qos () const |
Get the actual QoS settings, after the defaults have been determined. More... | |
RCLCPP_PUBLIC bool | can_loan_messages () const |
Check if publisher instance can loan messages. More... | |
RCLCPP_PUBLIC bool | operator== (const rmw_gid_t &gid) const |
Compare this publisher to a gid. More... | |
RCLCPP_PUBLIC bool | operator== (const rmw_gid_t *gid) const |
Compare this publisher to a pointer gid. More... | |
RCLCPP_PUBLIC void | setup_intra_process (uint64_t intra_process_publisher_id, IntraProcessManagerSharedPtr ipm) |
Implementation utility function used to setup intra process publishing after creation. | |
RCLCPP_PUBLIC std::vector< rclcpp::NetworkFlowEndpoint > | get_network_flow_endpoints () const |
Get network flow endpoints. More... | |
template<typename DurationRepT = int64_t, typename DurationT = std::milli> | |
bool | wait_for_all_acked (std::chrono::duration< DurationRepT, DurationT > timeout=std::chrono::duration< DurationRepT, DurationT >(-1)) const |
Wait until all published messages are acknowledged or until the specified timeout elapses. More... | |
void | set_on_new_qos_event_callback (std::function< void(size_t)> callback, rcl_publisher_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_publisher_event_type_t event_type) |
Unset the callback registered for new qos events, if any. | |
Protected Member Functions | |
void | do_inter_process_publish (const ROSMessageType &msg) |
void | do_serialized_publish (const rcl_serialized_message_t *serialized_msg) |
void | do_loaned_message_publish (std::unique_ptr< ROSMessageType, std::function< void(ROSMessageType *)>> msg) |
void | do_intra_process_publish (std::unique_ptr< PublishedType, PublishedTypeDeleter > msg) |
void | do_intra_process_ros_message_publish (std::unique_ptr< ROSMessageType, ROSMessageTypeDeleter > msg) |
std::shared_ptr< const ROSMessageType > | do_intra_process_ros_message_publish_and_return_shared (std::unique_ptr< ROSMessageType, ROSMessageTypeDeleter > msg) |
std::unique_ptr< ROSMessageType, ROSMessageTypeDeleter > | create_ros_message_unique_ptr () |
Return a new unique_ptr using the ROSMessageType of the publisher. | |
std::unique_ptr< ROSMessageType, ROSMessageTypeDeleter > | duplicate_ros_message_as_unique_ptr (const ROSMessageType &msg) |
Duplicate a given ros message as a unique_ptr. | |
std::unique_ptr< PublishedType, PublishedTypeDeleter > | duplicate_type_adapt_message_as_unique_ptr (const PublishedType &msg) |
Duplicate a given type adapted message as a unique_ptr. | |
![]() | |
template<typename EventCallbackT > | |
void | add_event_handler (const EventCallbackT &callback, const rcl_publisher_event_type_t event_type) |
RCLCPP_PUBLIC void | default_incompatible_qos_callback (QOSOfferedIncompatibleQoSInfo &info) const |
Protected Attributes | |
const rclcpp::PublisherOptionsWithAllocator< AllocatorT > | options_ |
Copy of original options passed during construction. More... | |
PublishedTypeAllocator | published_type_allocator_ |
PublishedTypeDeleter | published_type_deleter_ |
ROSMessageTypeAllocator | ros_message_type_allocator_ |
ROSMessageTypeDeleter | ros_message_type_deleter_ |
![]() | |
std::shared_ptr< rcl_node_t > | rcl_node_handle_ |
std::shared_ptr< rcl_publisher_t > | publisher_handle_ |
std::unordered_map< rcl_publisher_event_type_t, std::shared_ptr< rclcpp::QOSEventHandlerBase > > | event_handlers_ |
bool | intra_process_is_enabled_ |
IntraProcessManagerWeakPtr | weak_ipm_ |
uint64_t | intra_process_publisher_id_ |
rmw_gid_t | rmw_gid_ |
const rosidl_message_type_support_t | type_support_ |
Additional Inherited Members | |
![]() | |
using | IntraProcessManagerWeakPtr = std::weak_ptr< rclcpp::experimental::IntraProcessManager > |
A publisher publishes messages of any type to a topic.
MessageT must be a:
In the case that MessageT is ROS message type (e.g. std_msgs::msg::String), both PublishedType and ROSMessageType will be that type. In the case that MessageT is a TypeAdapter<CustomType, ROSMessageType> type (e.g. TypeAdapter<std::string, std_msgs::msg::String>), PublishedType will be the custom type, and ROSMessageType will be the ros message type.
This is achieved because of the "identity specialization" for TypeAdapter, which returns itself if it is already a TypeAdapter, and the default specialization which allows ROSMessageType to be void.
Definition at line 77 of file publisher.hpp.
|
inline |
Default constructor.
The constructor for a Publisher is almost never called directly. Instead, subscriptions should be instantiated through the function rclcpp::create_publisher().
[in] | node_base | NodeBaseInterface pointer that is used in part of the setup. |
[in] | topic | Name of the topic to publish to. |
[in] | qos | QoS profile for Subcription. |
[in] | options | Options for the subscription. |
Definition at line 125 of file publisher.hpp.
References rclcpp::Publisher< MessageT, AllocatorT >::options_.
|
inline |
Borrow a loaned ROS message from the middleware.
If the middleware is capable of loaning memory for a ROS message instance, the loaned message will be directly allocated in the middleware. If not, the message allocator of this rclcpp::Publisher instance is being used.
With a call to
publish
the LoanedMessage instance is being returned to the middleware or free'd accordingly to the allocator. If the message is not being published but processed differently, the destructor of this class will either return the message to the middleware or deallocate it via the internal allocator. Definition at line 231 of file publisher.hpp.
|
inline |
Publish a message on the topic.
This signature is enabled if the object being published is a ROS message type, as opposed to the custom_type of a TypeAdapter, and that type matches the type given when creating the publisher.
This signature allows the user to give a reference to a message, which is copied onto the heap without modification so that a copy can be owned by rclcpp and ownership of the copy can be moved later if needed.
[in] | msg | A const reference to the message to send. |
Definition at line 295 of file publisher.hpp.
References rclcpp::Publisher< MessageT, AllocatorT >::duplicate_ros_message_as_unique_ptr(), and rclcpp::Publisher< MessageT, AllocatorT >::publish().
|
inline |
Publish a message on the topic.
This signature is enabled if this class was created with a TypeAdapter and the given type matches the custom_type of the TypeAdapter.
This signature allows the user to give a reference to a message, which is copied onto the heap without modification so that a copy can be owned by rclcpp and ownership of the copy can be moved later if needed.
[in] | msg | A const reference to the message to send. |
Definition at line 367 of file publisher.hpp.
References rclcpp::Publisher< MessageT, AllocatorT >::duplicate_type_adapt_message_as_unique_ptr(), and rclcpp::Publisher< MessageT, AllocatorT >::publish().
|
inline |
Publish an instance of a LoanedMessage.
When publishing a loaned message, the memory for this ROS message will be deallocated after being published. The instance of the loaned message is no longer valid after this call.
loaned_msg | The LoanedMessage instance to be published. |
Definition at line 406 of file publisher.hpp.
References rclcpp::PublisherBase::can_loan_messages().
|
inline |
Publish a message on the topic.
This signature is enabled if this class was created with a TypeAdapter and the element_type of the std::unique_ptr matches the custom_type for the TypeAdapter used with this class.
This signature allows the user to give ownership of the message to rclcpp, allowing for more efficient intra-process communication optimizations.
[in] | msg | A unique pointer to the message to send. |
Definition at line 325 of file publisher.hpp.
References rclcpp::PublisherBase::get_intra_process_subscription_count(), and rclcpp::PublisherBase::get_subscription_count().
|
inline |
Publish a message on the topic.
This signature is enabled if the element_type of the std::unique_ptr is a ROS message type, as opposed to the custom_type of a TypeAdapter, and that type matches the type given when creating the publisher.
This signature allows the user to give ownership of the message to rclcpp, allowing for more efficient intra-process communication optimizations.
[in] | msg | A unique pointer to the message to send. |
Definition at line 254 of file publisher.hpp.
References rclcpp::PublisherBase::get_intra_process_subscription_count(), and rclcpp::PublisherBase::get_subscription_count().
Referenced by rclcpp::Publisher< MessageT, AllocatorT >::publish(), rclcpp::topic_statistics::SubscriptionTopicStatistics< CallbackMessageT >::publish_message_and_reset_measurements(), and rclcpp::node_interfaces::NodeParameters::set_parameters_atomically().
|
protected |
Copy of original options passed during construction.
It is important to save a copy of this so that the rmw payload which it may contain is kept alive for the duration of the publisher.
Definition at line 596 of file publisher.hpp.
Referenced by rclcpp::Publisher< MessageT, AllocatorT >::post_init_setup(), and rclcpp::Publisher< MessageT, AllocatorT >::Publisher().