Template Class SimplePublisherPlugin

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

template<class M>
class SimplePublisherPlugin : public image_transport::PublisherPlugin

Base class to simplify implementing most plugins to Publisher.

This base class vastly simplifies implementing a PublisherPlugin in the common case that all communication with the matching SubscriberPlugin happens over a single ROS topic using a transport-specific message type. SimplePublisherPlugin is templated on the transport-specific message type.

A subclass need implement only two methods:

For access to the parameter server and name remappings, use nh().

getTopicToAdvertise() controls the name of the internal communication topic. It defaults to <base topic>/<transport name>.

Public Functions

inline virtual ~SimplePublisherPlugin()
inline virtual size_t getNumSubscribers() const override

Returns the number of subscribers that are currently connected to this PublisherPlugin.

inline virtual std::string getTopic() const override

Returns the communication topic that this PublisherPlugin will publish on.

inline virtual void publish(const sensor_msgs::msg::Image &message) const override

Publish an image using the transport associated with this PublisherPlugin.

inline virtual void publishUniquePtr(sensor_msgs::msg::Image::UniquePtr message) const override

Publish an image using the transport associated with this PublisherPlugin. This version of the function can be used to optimize cases where the Plugin can avoid doing copies of the data when having the ownership to the image message. Plugins that can take advantage of message ownership should overwrite this method along with supportsUniquePtrPub().

inline virtual void shutdown() override

Shutdown any advertisements associated with this PublisherPlugin.

Protected Types

typedef rclcpp::Publisher<M>::SharedPtr PublisherT
typedef std::function<void(const M&)> PublishFn

Generic function for publishing the internal message type.

Protected Functions

inline virtual void advertiseImpl(rclcpp::Node *node, const std::string &base_topic, rmw_qos_profile_t custom_qos, rclcpp::PublisherOptions options) override

Advertise a topic. Must be implemented by the subclass.

inline virtual void publish(const sensor_msgs::msg::Image&, const PublishFn&) const

Publish an image using the specified publish function.

Deprecated:

Use publish(const sensor_msgs::msg::Image&, const PublisherT&) instead.

The PublishFn publishes the transport-specific message type. This indirection allows SimpleSubscriberPlugin to use this function for both normal broadcast publishing and single subscriber publishing (in subscription callbacks).

inline virtual void publish(const sensor_msgs::msg::Image &message, const PublisherT &publisher) const

Publish an image using the specified publisher.

inline virtual void publish(sensor_msgs::msg::Image::UniquePtr, const PublisherT&) const

Publish an image using the specified publisher.

This version of the function can be used to optimize cases where the Plugin can avoid doing copies of the data when having the ownership to the image message. Plugins that can take advantage of message ownership should overwrite this method along with supportsUniquePtrPub().

inline virtual std::string getTopicToAdvertise(const std::string &base_topic) const

Return the communication topic name for a given base topic.

Defaults to <base topic>/<transport name>.