35 #ifndef IMAGE_TRANSPORT_SINGLE_SUBSCRIBER_PUBLISHER 36 #define IMAGE_TRANSPORT_SINGLE_SUBSCRIBER_PUBLISHER 38 #include <boost/noncopyable.hpp> 39 #include <boost/function.hpp> 40 #include <sensor_msgs/Image.h> 53 typedef boost::function<void(const sensor_msgs::Image&)>
PublishFn;
56 const GetNumSubscribersFn& num_subscribers_fn,
57 const PublishFn& publish_fn);
59 std::string getSubscriberName()
const;
61 std::string getTopic()
const;
63 uint32_t getNumSubscribers()
const;
65 void publish(
const sensor_msgs::Image& message)
const;
66 void publish(
const sensor_msgs::ImageConstPtr& message)
const;
Manages advertisements of multiple transport options on an Image topic.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::function< void(const sensor_msgs::Image &)> PublishFn
Allows publication of an image to a single subscriber. Only available inside subscriber connection ca...
#define IMAGE_TRANSPORT_DECL
GetNumSubscribersFn num_subscribers_fn_
boost::function< uint32_t()> GetNumSubscribersFn