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. More... | |
template<typename F > | |
void | connectInput (F &f) |
Does nothing. Provided so that Subscriber may be used in a message_filters::Chain. More... | |
const ros::Subscriber & | getSubscriber () const |
Returns the internal ros::Subscriber object. More... | |
std::string | getTopic () const |
void | subscribe () |
Re-subscribe to a topic. Only works if this subscriber has previously been subscribed to a topic. More... | |
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. More... | |
Subscriber () | |
Empty constructor, use subscribe() to subscribe to a topic. More... | |
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. More... | |
void | unsubscribe () |
Force immediate unsubscription of this subscriber from its topic. More... | |
~Subscriber () | |
Private Member Functions | |
void | cb (const EventType &e) |
Private Attributes | |
ros::NodeHandle | nh_ |
ros::SubscribeOptions | ops_ |
ros::Subscriber | sub_ |
Additional Inherited Members |
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 127 of file subscriber.h.
typedef ros::MessageEvent<M const> message_filters::Subscriber< M >::EventType |
Definition at line 131 of file subscriber.h.
typedef boost::shared_ptr<M const> message_filters::Subscriber< M >::MConstPtr |
Definition at line 130 of file subscriber.h.
|
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 144 of file subscriber.h.
|
inline |
Empty constructor, use subscribe() to subscribe to a topic.
Definition at line 152 of file subscriber.h.
|
inline |
Definition at line 156 of file subscriber.h.
|
inline |
Does nothing. Provided so that Subscriber may be used in a message_filters::Chain.
Definition at line 229 of file subscriber.h.
|
inlineprivate |
Definition at line 236 of file subscriber.h.
|
inline |
Does nothing. Provided so that Subscriber may be used in a message_filters::Chain.
Definition at line 221 of file subscriber.h.
|
inline |
Returns the internal ros::Subscriber object.
Definition at line 215 of file subscriber.h.
|
inline |
Definition at line 207 of file subscriber.h.
|
inlinevirtual |
Re-subscribe to a topic. Only works if this subscriber has previously been subscribed to a topic.
Implements message_filters::SubscriberBase.
Definition at line 189 of file subscriber.h.
|
inlinevirtual |
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 172 of file subscriber.h.
|
inlinevirtual |
Force immediate unsubscription of this subscriber from its topic.
Implements message_filters::SubscriberBase.
Definition at line 202 of file subscriber.h.
|
private |
Definition at line 243 of file subscriber.h.
|
private |
Definition at line 242 of file subscriber.h.
|
private |
Definition at line 241 of file subscriber.h.