35 #ifndef MESSAGE_FILTERS_SUBSCRIBER_H 36 #define MESSAGE_FILTERS_SUBSCRIBER_H 40 #include <boost/thread/mutex.hpp> 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, _1));
147 ops_.callback_queue = callback_queue;
148 ops_.transport_hints = transport_hints;
161 if (!ops_.topic.empty())
163 sub_ = nh_.subscribe(ops_);
197 void add(
const EventType& e)
204 void cb(
const EventType& e)
206 this->signalMessage(e);
std::string getTopic() const
void connectInput(F &f)
Does nothing. Provided so that Subscriber may be used in a message_filters::Chain.
ros::MessageEvent< M const > EventType
virtual void unsubscribe()=0
Force immediate unsubscription of this subscriber from its topic.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual void subscribe()=0
Re-subscribe to a topic. Only works if this subscriber has previously been subscribed to a topic...
const ros::Subscriber & getSubscriber() const
Returns the internal ros::Subscriber object.
Subscriber(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
Constructor.
Subscriber()
Empty constructor, use subscribe() to subscribe to a topic.
boost::shared_ptr< SubscriberBase > SubscriberBasePtr
void cb(const EventType &e)
ros::SubscribeOptions ops_
boost::shared_ptr< M const > MConstPtr
virtual ~SubscriberBase()
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
Subscribe to a topic.
Convenience base-class for simple filters which output a single message.
void unsubscribe()
Force immediate unsubscription of this subscriber from its topic.
void subscribe()
Re-subscribe to a topic. Only works if this subscriber has previously been subscribed to a topic...
void add(const EventType &e)
Does nothing. Provided so that Subscriber may be used in a message_filters::Chain.