20 #ifndef INCLUDE_FKIE_MESSAGE_FILTERS_CAMERA_PUBLISHER_H_ 21 #define INCLUDE_FKIE_MESSAGE_FILTERS_CAMERA_PUBLISHER_H_ 25 #include <sensor_msgs/Image.h> 26 #include <sensor_msgs/CameraInfo.h> 65 virtual bool is_active()
const noexcept
override;
70 virtual std::string
topic()
const noexcept
override;
104 void receive (
const sensor_msgs::ImageConstPtr&,
const sensor_msgs::CameraInfoConstPtr&) noexcept
override;
106 std::shared_ptr<image_transport::ImageTransport>
it_;
Base class for data consumers.
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
Publish consumed data to ROS camera topics.
Base class for ROS publishers in a filter pipeline.
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_
image_transport::CameraPublisher pub_
virtual bool is_active() const noexcept override
Check if the ROS publisher has at least one subscriber.
CameraPublisher() noexcept
Constructs an empty publisher.
virtual std::string topic() const noexcept override
Return the configured ROS topic.