20 #ifndef INCLUDE_FKIE_MESSAGE_FILTERS_CAMERA_SUBSCRIBER_H_ 21 #define INCLUDE_FKIE_MESSAGE_FILTERS_CAMERA_SUBSCRIBER_H_ 25 #include <sensor_msgs/Image.h> 26 #include <sensor_msgs/CameraInfo.h> 97 virtual std::string
topic()
const noexcept
override;
115 void cb(
const sensor_msgs::ImageConstPtr&,
const sensor_msgs::CameraInfoConstPtr&);
116 std::shared_ptr<image_transport::ImageTransport>
it_;
image_transport::CameraSubscriber sub_
void cb(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)
Base class for data providers.
virtual void unsubscribe_impl() noexcept override
Shut the ROS subscriber down.
virtual void subscribe_on_demand(PublisherBase &pub)
Subscribe to the configured ROS topic whenever the given publisher is active.
virtual void subscribe()
Subscribe to the configured ROS topic.
Subscribe to ROS camera topics as data provider.
image_transport::TransportHints hints_
Base class for ROS subscribers in a filter pipeline.
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 unsubscribe()
Unsubscribe from the configured ROS topic.
virtual void subscribe_impl() noexcept override
Create a ROS subscriber.