35 #ifndef IMAGE_TRANSPORT_RAW_PUBLISHER_H 36 #define IMAGE_TRANSPORT_RAW_PUBLISHER_H 60 virtual void publish(
const sensor_msgs::ImageConstPtr& message)
const 66 virtual void publish(
const sensor_msgs::Image& message,
const uint8_t* data)
const;
69 virtual void publish(
const sensor_msgs::Image& message,
const PublishFn& publish_fn)
const virtual std::string getTopicToAdvertise(const std::string &base_topic) const
Return the communication topic name for a given base topic.
void publish(const boost::shared_ptr< M > &message) const
const ros::Publisher & getPublisher() const
Returns the internal ros::Publisher.
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...
boost::function< void(const sensor_msgs::Image &)> PublishFn
Generic function for publishing the internal message type.
The default PublisherPlugin.
Base class to simplify implementing most plugins to Publisher.
virtual void publish(const sensor_msgs::ImageConstPtr &message) const
Publish an image using the transport associated with this PublisherPlugin.
virtual std::string getTransportName() const
Get a string identifier for the transport provided by this plugin.