single_subscriber_publisher.h
Go to the documentation of this file.
00001 #ifndef IMAGE_TRANSPORT_SINGLE_SUBSCRIBER_PUBLISHER
00002 #define IMAGE_TRANSPORT_SINGLE_SUBSCRIBER_PUBLISHER
00003 
00004 #include <boost/noncopyable.hpp>
00005 #include <boost/function.hpp>
00006 #include <sensor_msgs/Image.h>
00007 
00008 namespace image_transport {
00009 
00014 class SingleSubscriberPublisher : boost::noncopyable
00015 {
00016 public:
00017   typedef boost::function<uint32_t()> GetNumSubscribersFn;
00018   typedef boost::function<void(const sensor_msgs::Image&)> PublishFn;
00019   
00020   SingleSubscriberPublisher(const std::string& caller_id, const std::string& topic,
00021                             const GetNumSubscribersFn& num_subscribers_fn,
00022                             const PublishFn& publish_fn);
00023   
00024   std::string getSubscriberName() const;
00025 
00026   std::string getTopic() const;
00027 
00028   uint32_t getNumSubscribers() const;
00029 
00030   void publish(const sensor_msgs::Image& message) const;
00031   void publish(const sensor_msgs::ImageConstPtr& message) const;
00032 
00033 private:
00034   std::string caller_id_;
00035   std::string topic_;
00036   GetNumSubscribersFn num_subscribers_fn_;
00037   PublishFn publish_fn_;
00038 
00039   friend class Publisher; // to get publish_fn_ directly
00040 };
00041 
00042 typedef boost::function<void(const SingleSubscriberPublisher&)> SubscriberStatusCallback;
00043 
00044 } //namespace image_transport
00045 
00046 #endif


image_transport
Author(s): Patrick Mihelich
autogenerated on Fri Jan 3 2014 11:24:08