Class PublisherPlugin
Defined in File publisher_plugin.hpp
Inheritance Relationships
Derived Types
public image_transport::SimplePublisherPlugin< sensor_msgs::msg::Image >
(Template Class SimplePublisherPlugin)public image_transport::SimplePublisherPlugin< M >
(Template Class SimplePublisherPlugin)
Class Documentation
-
class PublisherPlugin
Base class for plugins to Publisher.
Subclassed by image_transport::SimplePublisherPlugin< sensor_msgs::msg::Image >, image_transport::SimplePublisherPlugin< M >
Public Functions
-
PublisherPlugin() = default
-
PublisherPlugin(const PublisherPlugin&) = delete
-
PublisherPlugin &operator=(const PublisherPlugin&) = delete
-
inline virtual ~PublisherPlugin()
-
virtual std::string getTransportName() const = 0
Get a string identifier for the transport provided by this plugin.
-
inline virtual bool supportsUniquePtrPub() const
Check whether this plugin supports publishing using UniquePtr.
-
inline void advertise(rclcpp::Node *nh, const std::string &base_topic, rmw_qos_profile_t custom_qos = rmw_qos_profile_default, rclcpp::PublisherOptions options = rclcpp::PublisherOptions())
Advertise a topic, simple version.
-
virtual size_t getNumSubscribers() const = 0
Returns the number of subscribers that are currently connected to this PublisherPlugin.
-
virtual std::string getTopic() const = 0
Returns the communication topic that this PublisherPlugin will publish on.
-
virtual void publish(const sensor_msgs::msg::Image &message) const = 0
Publish an image using the transport associated with this PublisherPlugin.
Publish an image using the transport associated with this PublisherPlugin.
-
inline virtual void publishUniquePtr(sensor_msgs::msg::Image::UniquePtr) const
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 publishData(const sensor_msgs::msg::Image &message, const uint8_t *data) const
Publish an image using the transport associated with this PublisherPlugin. This version of the function can be used to optimize cases where you don’t want to fill a ROS message first to avoid useless copies.
- Parameters:
message – an image message to use information from (but not data)
data – a pointer to the image data to use to fill the Image message
-
virtual void shutdown() = 0
Shutdown any advertisements associated with this PublisherPlugin.
Public Static Functions
-
static inline std::string getLookupName(const std::string &transport_name)
Return the lookup name of the PublisherPlugin associated with a specific transport identifier.
Protected Functions
-
virtual void advertiseImpl(rclcpp::Node *node, const std::string &base_topic, rmw_qos_profile_t custom_qos, rclcpp::PublisherOptions options) = 0
Advertise a topic. Must be implemented by the subclass.
-
PublisherPlugin() = default