ROS subscription filter. More...
#include <subscriber.h>
Public Types | |
typedef ros::MessageEvent< M const > | EventType |
typedef boost::shared_ptr< M const > | MConstPtr |
Public Member Functions | |
void | add (const EventType &e) |
Does nothing. Provided so that Subscriber may be used in a message_filters::Chain. | |
template<typename F > | |
void | connectInput (F &f) |
Does nothing. Provided so that Subscriber may be used in a message_filters::Chain. | |
const ros::Subscriber & | getSubscriber () const |
Returns the internal ros::Subscriber object. | |
std::string | getTopic () const |
void | subscribe () |
Re-subscribe to a topic. Only works if this subscriber has previously been subscribed to a topic. | |
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. | |
Subscriber () | |
Empty constructor, use subscribe() to subscribe to a topic. | |
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. | |
void | unsubscribe () |
Force immediate unsubscription of this subscriber from its topic. | |
~Subscriber () | |
Private Member Functions | |
void | cb (const EventType &e) |
Private Attributes | |
ros::NodeHandle | nh_ |
ros::SubscribeOptions | ops_ |
ros::Subscriber | sub_ |
ROS subscription filter.
This class acts as a highest-level filter, simply passing messages from a ROS subscription through to the filters which have connected to it.
When this object is destroyed it will unsubscribe from the ROS subscription.
The Subscriber object is templated on the type of message being subscribed to.
Subscriber has no input connection.
The output connection for the Subscriber object is the same signature as for roscpp subscription callbacks, ie.
void callback(const boost::shared_ptr<M const>&);
Definition at line 88 of file subscriber.h.
typedef ros::MessageEvent<M const> message_filters::Subscriber< M >::EventType |
Reimplemented from message_filters::SimpleFilter< M >.
Definition at line 92 of file subscriber.h.
typedef boost::shared_ptr<M const> message_filters::Subscriber< M >::MConstPtr |
Reimplemented from message_filters::SimpleFilter< M >.
Definition at line 91 of file subscriber.h.
message_filters::Subscriber< M >::Subscriber | ( | ros::NodeHandle & | nh, | |
const std::string & | topic, | |||
uint32_t | queue_size, | |||
const ros::TransportHints & | transport_hints = ros::TransportHints() , |
|||
ros::CallbackQueueInterface * | callback_queue = 0 | |||
) | [inline] |
Constructor.
See the ros::NodeHandle::subscribe() variants for more information on the parameters
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 |
Definition at line 105 of file subscriber.h.
message_filters::Subscriber< M >::Subscriber | ( | ) | [inline] |
Empty constructor, use subscribe() to subscribe to a topic.
Definition at line 113 of file subscriber.h.
message_filters::Subscriber< M >::~Subscriber | ( | ) | [inline] |
Definition at line 117 of file subscriber.h.
void message_filters::Subscriber< M >::add | ( | const EventType & | e | ) | [inline] |
Does nothing. Provided so that Subscriber may be used in a message_filters::Chain.
Definition at line 189 of file subscriber.h.
void message_filters::Subscriber< M >::cb | ( | const EventType & | e | ) | [inline, private] |
Definition at line 195 of file subscriber.h.
void message_filters::Subscriber< M >::connectInput | ( | F & | f | ) | [inline] |
Does nothing. Provided so that Subscriber may be used in a message_filters::Chain.
Definition at line 182 of file subscriber.h.
const ros::Subscriber& message_filters::Subscriber< M >::getSubscriber | ( | ) | const [inline] |
Returns the internal ros::Subscriber object.
Definition at line 176 of file subscriber.h.
std::string message_filters::Subscriber< M >::getTopic | ( | ) | const [inline] |
Definition at line 168 of file subscriber.h.
void message_filters::Subscriber< M >::subscribe | ( | ) | [inline, virtual] |
Re-subscribe to a topic. Only works if this subscriber has previously been subscribed to a topic.
Implements message_filters::SubscriberBase.
Definition at line 150 of file subscriber.h.
void message_filters::Subscriber< M >::subscribe | ( | ros::NodeHandle & | nh, | |
const std::string & | topic, | |||
uint32_t | queue_size, | |||
const ros::TransportHints & | transport_hints = ros::TransportHints() , |
|||
ros::CallbackQueueInterface * | callback_queue = 0 | |||
) | [inline, 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 |
Implements message_filters::SubscriberBase.
Definition at line 133 of file subscriber.h.
void message_filters::Subscriber< M >::unsubscribe | ( | ) | [inline, virtual] |
Force immediate unsubscription of this subscriber from its topic.
Implements message_filters::SubscriberBase.
Definition at line 163 of file subscriber.h.
ros::NodeHandle message_filters::Subscriber< M >::nh_ [private] |
Definition at line 202 of file subscriber.h.
ros::SubscribeOptions message_filters::Subscriber< M >::ops_ [private] |
Definition at line 201 of file subscriber.h.
ros::Subscriber message_filters::Subscriber< M >::sub_ [private] |
Definition at line 200 of file subscriber.h.