35 #ifndef IMAGE_TRANSPORT_PUBLISHER_H 36 #define IMAGE_TRANSPORT_PUBLISHER_H 39 #include <sensor_msgs/Image.h> 84 void publish(
const sensor_msgs::Image& message)
const;
89 void publish(
const sensor_msgs::ImageConstPtr& message)
const;
96 operator void*()
const;
Manages advertisements of multiple transport options on an Image topic.
bool operator==(const Publisher &rhs) const
static void weakSubscriberCb(const ImplWPtr &impl_wptr, const SingleSubscriberPublisher &plugin_pub, const SubscriberStatusCallback &user_cb)
SubscriberStatusCallback rebindCB(const SubscriberStatusCallback &user_cb)
boost::weak_ptr< Impl > ImplWPtr
bool operator<(const Publisher &rhs) const
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
uint32_t getNumSubscribers() const
Returns the number of subscribers that are currently connected to this Publisher. ...
void shutdown()
Shutdown the advertisements associated with this Publisher.
void publish(const sensor_msgs::Image &message) const
Publish an image on the topics associated with this Publisher.
boost::shared_ptr< Impl > ImplPtr
Allows publication of an image to a single subscriber. Only available inside subscriber connection ca...
Advertise and subscribe to image topics.
std::string getTopic() const
Returns the base topic of this Publisher.
bool operator!=(const Publisher &rhs) const