28 advertise(it, base_topic, queue_size, latch);
43 it_ = std::make_shared<image_transport::ImageTransport>(it);
45 base_topic, queue_size,
62 it_ = std::make_shared<image_transport::ImageTransport>(it);
64 base_topic, queue_size,
68 if (connect_cb) connect_cb(ssp);
73 if (disconnect_cb) disconnect_cb(ssp);
std::shared_ptr< image_transport::ImageTransport > it_
uint32_t getNumSubscribers() const
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ImagePublisher() noexcept
Constructs an empty publisher.
void update_subscriber_state()
Cause all linked subscribers to subscribe or unsubscribe to their ROS topics.
virtual bool is_active() const noexcept override
Check if the ROS publisher has at least one subscriber.
void publish(const sensor_msgs::Image &message) const
virtual std::string topic() const noexcept override
Return the configured ROS topic.
void advertise(const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, bool latch=false) noexcept
Advertise ROS image topic.
void receive(const sensor_msgs::ImageConstPtr &) noexcept override
image_transport::Publisher pub_
boost::shared_ptr< void > VoidPtr
std::string getTopic() const