#include <subscriber.h>
Public Member Functions | |
virtual 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)=0 |
Subscribe to a topic. | |
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. | |
virtual | ~SubscriberBase () |
Definition at line 48 of file subscriber.h.
virtual message_filters::SubscriberBase::~SubscriberBase | ( | ) | [inline, virtual] |
Definition at line 51 of file subscriber.h.
virtual void message_filters::SubscriberBase::subscribe | ( | ros::NodeHandle & | nh, |
const std::string & | topic, | ||
uint32_t | queue_size, | ||
const ros::TransportHints & | transport_hints = ros::TransportHints() , |
||
ros::CallbackQueueInterface * | callback_queue = 0 |
||
) | [pure virtual] |
Subscribe to a topic.
If this Subscriber is already subscribed to a topic, this function will first unsubscribe.
nh | The ros::NodeHandle to use to subscribe. |
topic | The topic to subscribe to. |
queue_size | The subscription queue size |
transport_hints | The transport hints to pass along |
callback_queue | The callback queue to pass along |
Implemented in message_filters::Subscriber< M >.
virtual void message_filters::SubscriberBase::subscribe | ( | ) | [pure virtual] |
Re-subscribe to a topic. Only works if this subscriber has previously been subscribed to a topic.
Implemented in message_filters::Subscriber< M >.
virtual void message_filters::SubscriberBase::unsubscribe | ( | ) | [pure virtual] |
Force immediate unsubscription of this subscriber from its topic.
Implemented in message_filters::Subscriber< M >.