28 set_subscribe_options(it, base_topic, queue_size, transport_hints);
34 it_ = std::make_shared<image_transport::ImageTransport>(it);
35 base_topic_ = base_topic;
36 queue_size_ = queue_size;
37 hints_ = transport_hints;
42 set_subscribe_options(it, base_topic, queue_size, transport_hints);
62 [
this](
const sensor_msgs::ImageConstPtr& img,
const sensor_msgs::CameraInfoConstPtr& info)
76 void CameraSubscriber::cb (
const sensor_msgs::ImageConstPtr& img,
const sensor_msgs::CameraInfoConstPtr& info)
image_transport::CameraSubscriber sub_
void cb(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)
virtual void unsubscribe_impl() noexcept override
Shut the ROS subscriber down.
virtual void subscribe()
Subscribe to the configured ROS topic.
image_transport::TransportHints hints_
virtual bool is_configured() const noexcept override
Check if the ROS subscriber is properly configured.
void set_subscribe_options(const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const image_transport::TransportHints &transport_hints=image_transport::TransportHints()) noexcept
Configure ROS topic that is to be subscribed.
CameraSubscriber() noexcept
Constructs an empty subscriber.
virtual std::string topic() const noexcept override
Return the configured ROS topic.
std::shared_ptr< image_transport::ImageTransport > it_
virtual void subscribe_impl() noexcept override
Create a ROS subscriber.
void send(const Outputs &... out)
Pass data to all connected sinks.
boost::shared_ptr< void > VoidPtr
std::string getTopic() const