The default PublisherPlugin. More...
#include <raw_publisher.h>
Public Member Functions | |
virtual std::string | getTransportName () const |
Get a string identifier for the transport provided by this plugin. | |
virtual void | publish (const sensor_msgs::ImageConstPtr &message) const |
Publish an image using the transport associated with this PublisherPlugin. | |
virtual | ~RawPublisher () |
Protected Member Functions | |
virtual std::string | getTopicToAdvertise (const std::string &base_topic) const |
Return the communication topic name for a given base topic. | |
virtual void | publish (const sensor_msgs::Image &message, const PublishFn &publish_fn) const |
Publish an image using the specified publish function. Must be implemented by the subclass. |
The default PublisherPlugin.
RawPublisher is a simple wrapper for ros::Publisher, publishing unaltered Image messages on the base topic.
Definition at line 48 of file raw_publisher.h.
virtual image_transport::RawPublisher::~RawPublisher | ( | ) | [inline, virtual] |
Definition at line 51 of file raw_publisher.h.
virtual std::string image_transport::RawPublisher::getTopicToAdvertise | ( | const std::string & | base_topic | ) | const [inline, protected, virtual] |
Return the communication topic name for a given base topic.
Defaults to <base topic>/<transport name>.
Reimplemented from image_transport::SimplePublisherPlugin< sensor_msgs::Image >.
Definition at line 71 of file raw_publisher.h.
virtual std::string image_transport::RawPublisher::getTransportName | ( | ) | const [inline, virtual] |
Get a string identifier for the transport provided by this plugin.
Implements image_transport::PublisherPlugin.
Definition at line 53 of file raw_publisher.h.
virtual void image_transport::RawPublisher::publish | ( | const sensor_msgs::ImageConstPtr & | message | ) | const [inline, virtual] |
Publish an image using the transport associated with this PublisherPlugin.
Reimplemented from image_transport::PublisherPlugin.
Definition at line 60 of file raw_publisher.h.
virtual void image_transport::RawPublisher::publish | ( | const sensor_msgs::Image & | message, |
const PublishFn & | publish_fn | ||
) | const [inline, protected, virtual] |
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).
Implements image_transport::SimplePublisherPlugin< sensor_msgs::Image >.
Definition at line 66 of file raw_publisher.h.