35 #ifndef IMAGE_TRANSPORT_SUBSCRIBER_FILTER_H 36 #define IMAGE_TRANSPORT_SUBSCRIBER_FILTER_H 80 subscribe(it, base_topic, queue_size, transport_hints);
153 void cb(
const sensor_msgs::ImageConstPtr& m)
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for arbitrary boost::function object.
Image subscription filter.
SubscriberFilter(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
Constructor.
void signalMessage(const MConstPtr &msg)
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.
std::string getTransport() const
Returns the name of the transport being used.
std::string getTopic() const
Returns the base image topic.
const Subscriber & getSubscriber() const
Returns the internal image_transport::Subscriber object.
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
Subscribe to a topic.
uint32_t getNumPublishers() const
Returns the number of publishers this subscriber is connected to.
void shutdown()
Unsubscribe the callback associated with this Subscriber.
Stores transport settings for an image topic subscription.
void unsubscribe()
Force immediate unsubscription of this subscriber from its topic.
Advertise and subscribe to image topics.
uint32_t getNumPublishers() const
Returns the number of publishers this subscriber is connected to.
void cb(const sensor_msgs::ImageConstPtr &m)
std::string getTopic() const