Go to the documentation of this file.
35 #ifndef ROSRT_SUBSCRIBER_H
36 #define ROSRT_SUBSCRIBER_H
46 class CallbackQueueInterface;
114 M
const* latest =
latest_.exchange(0);
149 return subscribe(nh, topic, transport_hints);
162 #ifdef ROS_NEW_SERIALIZATION_API
184 M
const* latest =
latest_.exchange(0);
223 M
const* old =
latest_.exchange(latest);
238 #endif // ROSRT_SUBSCRIBER_H
void callback(const boost::shared_ptr< M const > &msg)
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.
ros::CallbackQueueInterface * getSubscriberCallbackQueue()
T * removeShared(const boost::shared_ptr< T > &t)
CallbackQueueInterface * callback_queue
lockfree::ObjectPool< M > * pool_
Subscriber()
Default constructor. You must call initialize() before doing anything else if you use this constructo...
ros::atomic< M const * > latest_
bool owns(const boost::shared_ptr< T const > &t)
boost::shared_ptr< M const > poll()
void addPoolToGC(void *pool, PoolDeleteFunc deleter, PoolDeletableFunc deletable)
Subscriber(uint32_t message_pool_size)
Constructor with initialization. Call subscribe() to subscribe to a topic.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
boost::shared_ptr< T > makeShared(T *t)
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.
void initialize(uint32_t message_pool_size)
Initialize this subscribe. Only use with the default constructor.
void initialize(uint32_t count, const T &tmpl)
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.
rosrt
Author(s): Josh Faust
autogenerated on Wed Mar 2 2022 00:54:17