28 advertise(it, base_topic, queue_size, latch);
43 it_ = std::make_shared<image_transport::ImageTransport>(it);
45 base_topic, queue_size,
70 it_ = std::make_shared<image_transport::ImageTransport>(it);
72 base_topic, queue_size,
76 if (image_connect_cb) image_connect_cb(ssp);
81 if (image_disconnect_cb) image_disconnect_cb(ssp);
86 if (info_connect_cb) info_connect_cb(ssp);
91 if (info_disconnect_cb) info_disconnect_cb(ssp);
void advertise(const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, bool latch=false) noexcept
Advertise ROS camera topic.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void receive(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &) noexcept override
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
std::shared_ptr< image_transport::ImageTransport > it_
std::string getTopic() const
uint32_t getNumSubscribers() const
void update_subscriber_state()
Cause all linked subscribers to subscribe or unsubscribe to their ROS topics.
image_transport::CameraPublisher pub_
virtual bool is_active() const noexcept override
Check if the ROS publisher has at least one subscriber.
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
CameraPublisher() noexcept
Constructs an empty publisher.
boost::shared_ptr< void > VoidPtr
virtual std::string topic() const noexcept override
Return the configured ROS topic.