A lock-free subscriber. Allows you to receive ROS messages inside a realtime thread. More...
#include <subscriber.h>
Public Member Functions | |
void | initialize (uint32_t message_pool_size) |
Initialize this subscribe. Only use with the default constructor. More... | |
bool | initialize (uint32_t message_pool_size, ros::NodeHandle &nh, const std::string &topic, const ros::TransportHints &transport_hints=ros::TransportHints()) |
Initialize this subscribe. Only use with the default constructor. More... | |
boost::shared_ptr< M const > | poll () |
Retrieve the newest message received. More... | |
bool | subscribe (ros::NodeHandle &nh, const std::string &topic, const ros::TransportHints &transport_hints=ros::TransportHints()) |
Subscribe to a topic. More... | |
Subscriber () | |
Default constructor. You must call initialize() before doing anything else if you use this constructor. More... | |
Subscriber (uint32_t message_pool_size) | |
Constructor with initialization. Call subscribe() to subscribe to a topic. More... | |
Subscriber (uint32_t message_pool_size, ros::NodeHandle &nh, const std::string &topic, const ros::TransportHints &transport_hints=ros::TransportHints()) | |
Constructor with initialization and subscription. More... | |
~Subscriber () | |
Private Member Functions | |
void | callback (const boost::shared_ptr< M const > &msg) |
Private Attributes | |
ros::atomic< M const * > | latest_ |
lockfree::ObjectPool< M > * | pool_ |
ros::Subscriber | sub_ |
A lock-free subscriber. Allows you to receive ROS messages inside a realtime thread.
This subscriber works in a polling manner rather than the usual callback-based mechanism, e.g.:
Subscriber<Msg> sub(2, nh, "my_topic"); while (true) { MsgConstPtr msg = sub.poll(); if (msg) { // do something with msg ... } }
Definition at line 75 of file subscriber.h.
|
inline |
Default constructor. You must call initialize() before doing anything else if you use this constructor.
Definition at line 81 of file subscriber.h.
|
inline |
Constructor with initialization. Call subscribe() to subscribe to a topic.
message_pool_size | The size of the message pool to use. If this pool fills up no more messages will be received until some messages are freed. |
Definition at line 91 of file subscriber.h.
|
inline |
Constructor with initialization and subscription.
message_pool_size | The size of the message pool to use. If this pool fills up no more messages will be received until some messages are freed. |
nh | The ros::NodeHandle to use to subscribe |
topic | The topic to subscribe on |
[optional] | transport_hints the transport hints to use |
Definition at line 105 of file subscriber.h.
|
inline |
Definition at line 112 of file subscriber.h.
|
inlineprivate |
Definition at line 201 of file subscriber.h.
|
inline |
Initialize this subscribe. Only use with the default constructor.
message_pool_size | The size of the message pool to use. If this pool fills up no more messages will be received until some messages are freed. |
Definition at line 128 of file subscriber.h.
|
inline |
Initialize this subscribe. Only use with the default constructor.
message_pool_size | The size of the message pool to use. If this pool fills up no more messages will be received until some messages are freed. |
nh | The ros::NodeHandle to use to subscribe |
topic | The topic to subscribe on |
[optional] | transport_hints the transport hints to use |
Definition at line 146 of file subscriber.h.
|
inline |
Retrieve the newest message received.
The same message will only be returned once, i.e:
<msg received> msg = poll(); // Returns a valid message msg = poll(); // Returns NULL
Definition at line 182 of file subscriber.h.
|
inline |
Subscribe to a topic.
nh | The ros::NodeHandle to use to subscribe |
topic | The topic to subscribe on |
[optional] | transport_hints the transport hints to use |
Definition at line 159 of file subscriber.h.
|
private |
Definition at line 230 of file subscriber.h.
|
private |
Definition at line 232 of file subscriber.h.
|
private |
Definition at line 233 of file subscriber.h.