Template Class Publisher

Inheritance Relationships

Base Type

Class Documentation

template<typename MessageT, typename AllocatorT = std::allocator<void>>
class Publisher : public rclcpp::PublisherBase

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.

See also

rclcpp::TypeAdapter for more details.

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>

Public Functions

inline Publisher(rclcpp::node_interfaces::NodeBaseInterface *node_base, const std::string &topic, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator<AllocatorT> &options)

Default constructor.

The constructor for a Publisher is almost never called directly. Instead, subscriptions should be instantiated through the function rclcpp::create_publisher().

Parameters:
  • node_base[in] NodeBaseInterface pointer that is used in part of the setup.

  • topic[in] Name of the topic to publish to.

  • qos[in] QoS profile for Subcription.

  • options[in] Options for the subscription.

inline 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.

inline virtual ~Publisher()
inline rclcpp::LoanedMessage<ROSMessageType, AllocatorT> borrow_loaned_message()

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

See also

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.

See also

rclcpp::LoanedMessage for details of the LoanedMessage class.

Returns:

LoanedMessage containing memory for a ROS message of type ROSMessageType

template<typename T>
inline 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.

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.

Parameters:

msg[in] A unique pointer to the message to send.

template<typename T>
inline 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.

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.

Parameters:

msg[in] A const reference to the message to send.

template<typename T>
inline 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.

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.

Parameters:

msg[in] A unique pointer to the message to send.

template<typename T>
inline 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.

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.

Parameters:

msg[in] A const reference to the message to send.

inline void publish(const rcl_serialized_message_t &serialized_msg)
inline void publish(const SerializedMessage &serialized_msg)
inline void publish(rclcpp::LoanedMessage<ROSMessageType, AllocatorT> &&loaned_msg)

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.

Parameters:

loaned_msg – The LoanedMessage instance to be published.

inline std::shared_ptr<PublishedTypeAllocator> get_allocator() const
inline PublishedTypeAllocator get_published_type_allocator() const
inline ROSMessageTypeAllocator get_ros_message_type_allocator() const

Protected Functions

inline void do_inter_process_publish(const ROSMessageType &msg)
inline void do_serialized_publish(const rcl_serialized_message_t *serialized_msg)
inline void do_loaned_message_publish(std::unique_ptr<ROSMessageType, std::function<void(ROSMessageType*)>> msg)
inline void do_intra_process_publish(std::unique_ptr<PublishedType, PublishedTypeDeleter> msg)
inline void do_intra_process_ros_message_publish(std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> msg)
inline std::shared_ptr<const ROSMessageType> do_intra_process_ros_message_publish_and_return_shared(std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> msg)
inline std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> create_ros_message_unique_ptr()

Return a new unique_ptr using the ROSMessageType of the publisher.

inline std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> duplicate_ros_message_as_unique_ptr(const ROSMessageType &msg)

Duplicate a given ros message as a unique_ptr.

inline 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.

Protected Attributes

const rclcpp::PublisherOptionsWithAllocator<AllocatorT> options_

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.

PublishedTypeAllocator published_type_allocator_
PublishedTypeDeleter published_type_deleter_
ROSMessageTypeAllocator ros_message_type_allocator_
ROSMessageTypeDeleter ros_message_type_deleter_