35 #ifndef IMAGE_TRANSPORT_PUBLISHER_H 36 #define IMAGE_TRANSPORT_PUBLISHER_H 39 #include <sensor_msgs/Image.h> 75 uint32_t getNumSubscribers()
const;
80 std::string getTopic()
const;
85 void publish(
const sensor_msgs::Image& message)
const;
90 void publish(
const sensor_msgs::ImageConstPtr& message)
const;
97 operator void*()
const;
115 static void weakSubscriberCb(
const ImplWPtr& impl_wptr,
Manages advertisements of multiple transport options on an Image topic.
bool operator==(const Publisher &rhs) const
boost::weak_ptr< Impl > ImplWPtr
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::shared_ptr< Impl > ImplPtr
Allows publication of an image to a single subscriber. Only available inside subscriber connection ca...
#define IMAGE_TRANSPORT_DECL
Advertise and subscribe to image topics.
bool operator!=(const Publisher &rhs) const