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;
98 bool operator< (
const Publisher& rhs)
const {
return impl_ < rhs.
impl_; }
99 bool operator!=(
const Publisher& rhs)
const {
return impl_ != rhs.
impl_; }
100 bool operator==(
const Publisher& rhs)
const {
return impl_ == rhs.impl_; }
103 Publisher(
ros::NodeHandle& nh,
const std::string& base_topic, uint32_t queue_size,
111 typedef boost::weak_ptr<Impl> ImplWPtr;
115 static void weakSubscriberCb(
const ImplWPtr& impl_wptr,
116 const SingleSubscriberPublisher& plugin_pub,
121 friend class ImageTransport;