Template Class SimplePublisherPlugin
Defined in File simple_publisher_plugin.hpp
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public image_transport::PublisherPlugin
(Class PublisherPlugin)
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:
publish() with an extra PublishFn argument
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
Returns the number of subscribers that are currently connected to this PublisherPlugin.
-
inline virtual std::string getTopic() const
Returns the communication topic that this PublisherPlugin will publish on.
-
inline virtual void publish(const sensor_msgs::msg::Image &message) const
Publish an image using the transport associated with this PublisherPlugin.
-
inline virtual void shutdown()
Shutdown any advertisements associated with this PublisherPlugin.
Protected Types
Protected Functions
-
inline virtual void advertiseImpl(rclcpp::Node *node, const std::string &base_topic, rmw_qos_profile_t custom_qos)
Advertise a topic. Must be implemented by the subclass.
-
virtual void publish(const sensor_msgs::msg::Image &message, const PublishFn &publish_fn) const = 0
Publish an image using the specified publish function. Must be implemented by the subclass.
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 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>.