Go to the documentation of this file.00001 #ifndef IMAGE_TRANSPORT_PUBLISHER_PLUGIN_H
00002 #define IMAGE_TRANSPORT_PUBLISHER_PLUGIN_H
00003
00004 #include <ros/ros.h>
00005 #include <sensor_msgs/Image.h>
00006 #include "image_transport/single_subscriber_publisher.h"
00007
00008 namespace image_transport {
00009
00013 class PublisherPlugin : boost::noncopyable
00014 {
00015 public:
00016 virtual ~PublisherPlugin() {}
00017
00022 virtual std::string getTransportName() const = 0;
00023
00027 void advertise(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00028 bool latch = true)
00029 {
00030 advertiseImpl(nh, base_topic, queue_size, SubscriberStatusCallback(),
00031 SubscriberStatusCallback(), ros::VoidPtr(), latch);
00032 }
00033
00037 void advertise(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00038 const SubscriberStatusCallback& connect_cb,
00039 const SubscriberStatusCallback& disconnect_cb = SubscriberStatusCallback(),
00040 const ros::VoidPtr& tracked_object = ros::VoidPtr(), bool latch = true)
00041 {
00042 advertiseImpl(nh, base_topic, queue_size, connect_cb, disconnect_cb, tracked_object, latch);
00043 }
00044
00049 virtual uint32_t getNumSubscribers() const = 0;
00050
00054 virtual std::string getTopic() const = 0;
00055
00059 virtual void publish(const sensor_msgs::Image& message) const = 0;
00060
00064 virtual void publish(const sensor_msgs::ImageConstPtr& message) const
00065 {
00066 publish(*message);
00067 }
00068
00072 virtual void shutdown() = 0;
00073
00078 static std::string getLookupName(const std::string& transport_name)
00079 {
00080 return "image_transport/" + transport_name + "_pub";
00081 }
00082
00083 protected:
00087 virtual void advertiseImpl(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00088 const SubscriberStatusCallback& connect_cb,
00089 const SubscriberStatusCallback& disconnect_cb,
00090 const ros::VoidPtr& tracked_object, bool latch) = 0;
00091 };
00092
00093 }
00094
00095 #endif