Go to the documentation of this file.
35 #ifndef MESSAGE_FILTERS_SUBSCRIBER_H
36 #define MESSAGE_FILTERS_SUBSCRIBER_H
40 #include <boost/thread/mutex.hpp>
95 class Subscriber :
public SubscriberBase,
public SimpleFilter<M>
114 subscribe(nh, topic, queue_size, transport_hints, callback_queue);
146 ops_.template initByFullCallbackType<const EventType&>(topic, queue_size, boost::bind(&
Subscriber<M>::cb,
this, boost::placeholders::_1));
void cb(const EventType &e)
virtual ~SubscriberBase()
TransportHints transport_hints
CallbackQueueInterface * callback_queue
void unsubscribe()
Force immediate unsubscription of this subscriber from its topic.
std::string getTopic() const
boost::shared_ptr< M const > MConstPtr
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
void subscribe()
Re-subscribe to a topic. Only works if this subscriber has previously been subscribed to a topic.
ros::SubscribeOptions ops_
void connectInput(F &f)
Does nothing. Provided so that Subscriber may be used in a message_filters::Chain.
virtual void subscribe()=0
Re-subscribe to a topic. Only works if this subscriber has previously been subscribed to a topic.
virtual void unsubscribe()=0
Force immediate unsubscription of this subscriber from its topic.
const ros::Subscriber & getSubscriber() const
Returns the internal ros::Subscriber object.
void signalMessage(const MConstPtr &msg)
Call all registered callbacks, passing them the specified message.
void add(const EventType &e)
Does nothing. Provided so that Subscriber may be used in a message_filters::Chain.
ros::MessageEvent< M const > EventType
Subscriber()
Empty constructor, use subscribe() to subscribe to a topic.
boost::shared_ptr< SubscriberBase > SubscriberBasePtr
message_filters
Author(s): Josh Faust, Vijay Pradeep, Dirk Thomas
, Jacob Perron
autogenerated on Sat Sep 14 2024 02:59:47