35 #ifndef ROSRT_SUBSCRIBER_H    36 #define ROSRT_SUBSCRIBER_H    46 class CallbackQueueInterface;
   109     subscribe(nh, topic, transport_hints);
   114     M 
const* latest = latest_.exchange(0);
   149     return subscribe(nh, topic, transport_hints);
   162 #ifdef ROS_NEW_SERIALIZATION_API   165     ops.template init<M>(topic, 1, boost::bind(&Subscriber::callback, 
this, _1));
   184     M 
const* latest = latest_.exchange(0);
   206     if (!pool_->owns(msg.get()))
   208       M* copy = pool_->allocate();
   220       latest = pool_->removeShared(msg);
   223     M 
const* old = latest_.exchange(latest);
   238 #endif // ROSRT_SUBSCRIBER_H 
Subscriber()
Default constructor. You must call initialize() before doing anything else if you use this constructo...
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. 
lockfree::ObjectPool< M > * pool_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCONSOLE_DECL void initialize()
void callback(const boost::shared_ptr< M const  > &msg)
void initialize(uint32_t count, const T &tmpl)
ros::CallbackQueueInterface * getSubscriberCallbackQueue()
ros::atomic< M const * > latest_
void initialize(uint32_t message_pool_size)
Initialize this subscribe. Only use with the default constructor. 
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. 
bool subscribe(ros::NodeHandle &nh, const std::string &topic, const ros::TransportHints &transport_hints=ros::TransportHints())
Subscribe to a topic. 
A lock-free subscriber. Allows you to receive ROS messages inside a realtime thread. 
Subscriber(uint32_t message_pool_size)
Constructor with initialization. Call subscribe() to subscribe to a topic. 
boost::shared_ptr< M const  > poll()
Retrieve the newest message received. 
CallbackQueueInterface * callback_queue
void addPoolToGC(void *pool, PoolDeleteFunc deleter, PoolDeletableFunc deletable)