Class RawPublisher
Defined in File raw_publisher.hpp
Inheritance Relationships
Base Type
public image_transport::SimplePublisherPlugin< sensor_msgs::msg::Image >
(Template Class SimplePublisherPlugin)
Class Documentation
-
class RawPublisher : public image_transport::SimplePublisherPlugin<sensor_msgs::msg::Image>
The default PublisherPlugin.
RawPublisher is a simple wrapper for ros::Publisher, publishing unaltered Image messages on the base topic.
Public Functions
-
inline virtual ~RawPublisher()
-
inline virtual std::string getTransportName() const
Get a string identifier for the transport provided by this plugin.
-
inline virtual bool supportsUniquePtrPub() const
Check whether this plugin supports publishing using UniquePtr.
Protected Functions
-
inline virtual void publish(const sensor_msgs::msg::Image &message, const PublishFn &publish_fn) 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 message, const PublisherT &publisher) 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>.
-
inline virtual ~RawPublisher()