Class GenericPublisher

Inheritance Relationships

Base Type

Class Documentation

class GenericPublisher : public rclcpp::PublisherBase

Publisher for serialized messages whose type is not known at compile time.

Since the type is not known at compile time, this is not a template, and the dynamic library containing type support information has to be identified and loaded based on the type name.

It does not support intra-process handling.

Public Functions

template<typename AllocatorT = std::allocator<void>>
inline GenericPublisher(rclcpp::node_interfaces::NodeBaseInterface *node_base, std::shared_ptr<rcpputils::SharedLibrary> ts_lib, const std::string &topic_name, const std::string &topic_type, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator<AllocatorT> &options)

Constructor.

In order to properly publish to a topic, this publisher needs to be added to the node_topic_interface of the node passed into this constructor.

See also

rclcpp::Node::create_generic_publisher() or rclcpp::create_generic_publisher() for creating an instance of this class and adding it to the node_topic_interface.

Parameters:
  • node_base – Pointer to parent node’s NodeBaseInterface

  • ts_lib – Type support library, needs to correspond to topic_type

  • topic_name – Topic name

  • topic_type – Topic type

  • qos – QoS settings

  • options – Publisher options. Not all publisher options are currently respected, the only relevant options for this publisher are event_callbacks, use_default_callbacks, and callback_group.

virtual ~GenericPublisher() = default
void publish(const rclcpp::SerializedMessage &message)

Publish a rclcpp::SerializedMessage.

void publish_as_loaned_msg(const rclcpp::SerializedMessage &message)

Publish a rclcpp::SerializedMessage via loaned message after de-serialization.

Parameters:

message – a serialized message

Throws:

anythingrclcpp::exceptions::throw_from_rcl_error can show