Go to the documentation of this file.
35 #ifndef IMAGE_TRANSPORT_SUBSCRIBER_FILTER_H
36 #define IMAGE_TRANSPORT_SUBSCRIBER_FILTER_H
77 SubscriberFilter(ImageTransport& it,
const std::string& base_topic, uint32_t queue_size,
78 const TransportHints& transport_hints = TransportHints())
80 subscribe(it, base_topic, queue_size, transport_hints);
105 void subscribe(ImageTransport& it,
const std::string& base_topic, uint32_t queue_size,
106 const TransportHints& transport_hints = TransportHints())
153 void cb(
const sensor_msgs::ImageConstPtr& m)
uint32_t getNumPublishers() const
Returns the number of publishers this subscriber is connected to.
uint32_t getNumPublishers() const
Returns the number of publishers this subscriber is connected to.
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
Subscribe to a topic.
std::string getTransport() const
Returns the name of the transport being used.
void cb(const sensor_msgs::ImageConstPtr &m)
std::string getTopic() const
Manages a subscription callback on a specific topic that can be interpreted as an Image topic.
SubscriberFilter()
Empty constructor, use subscribe() to subscribe to a topic.
std::string getTransport() const
Returns the name of the transport being used.
const Subscriber & getSubscriber() const
Returns the internal image_transport::Subscriber object.
void signalMessage(const MConstPtr &msg)
std::string getTopic() const
Returns the base image topic.
void unsubscribe()
Force immediate unsubscription of this subscriber from its topic.
void shutdown()
Unsubscribe the callback associated with this Subscriber.
image_transport
Author(s): Patrick Mihelich
autogenerated on Sat Jan 20 2024 03:14:50