Public Member Functions | Private Member Functions | Private Attributes | List of all members
rosrt::Subscriber< M > Class Template Reference

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_
 

Detailed Description

template<typename M>
class rosrt::Subscriber< M >

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.

Constructor & Destructor Documentation

template<typename M>
rosrt::Subscriber< M >::Subscriber ( )
inline

Default constructor. You must call initialize() before doing anything else if you use this constructor.

Definition at line 81 of file subscriber.h.

template<typename M>
rosrt::Subscriber< M >::Subscriber ( uint32_t  message_pool_size)
inline

Constructor with initialization. Call subscribe() to subscribe to a topic.

Parameters
message_pool_sizeThe 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.

template<typename M>
rosrt::Subscriber< M >::Subscriber ( uint32_t  message_pool_size,
ros::NodeHandle nh,
const std::string &  topic,
const ros::TransportHints transport_hints = ros::TransportHints() 
)
inline

Constructor with initialization and subscription.

Parameters
message_pool_sizeThe size of the message pool to use. If this pool fills up no more messages will be received until some messages are freed.
nhThe ros::NodeHandle to use to subscribe
topicThe topic to subscribe on
[optional]transport_hints the transport hints to use

Definition at line 105 of file subscriber.h.

template<typename M>
rosrt::Subscriber< M >::~Subscriber ( )
inline

Definition at line 112 of file subscriber.h.

Member Function Documentation

template<typename M>
void rosrt::Subscriber< M >::callback ( const boost::shared_ptr< M const > &  msg)
inlineprivate

Definition at line 201 of file subscriber.h.

template<typename M>
void rosrt::Subscriber< M >::initialize ( uint32_t  message_pool_size)
inline

Initialize this subscribe. Only use with the default constructor.

Parameters
message_pool_sizeThe 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.

template<typename M>
bool rosrt::Subscriber< M >::initialize ( uint32_t  message_pool_size,
ros::NodeHandle nh,
const std::string &  topic,
const ros::TransportHints transport_hints = ros::TransportHints() 
)
inline

Initialize this subscribe. Only use with the default constructor.

Parameters
message_pool_sizeThe size of the message pool to use. If this pool fills up no more messages will be received until some messages are freed.
nhThe ros::NodeHandle to use to subscribe
topicThe topic to subscribe on
[optional]transport_hints the transport hints to use
Returns
Whether or not we successfully subscribed

Definition at line 146 of file subscriber.h.

template<typename M>
boost::shared_ptr<M const> rosrt::Subscriber< M >::poll ( )
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.

template<typename M>
bool rosrt::Subscriber< M >::subscribe ( ros::NodeHandle nh,
const std::string &  topic,
const ros::TransportHints transport_hints = ros::TransportHints() 
)
inline

Subscribe to a topic.

Parameters
nhThe ros::NodeHandle to use to subscribe
topicThe topic to subscribe on
[optional]transport_hints the transport hints to use
Returns
Whether or not we successfully subscribed

Definition at line 159 of file subscriber.h.

Member Data Documentation

template<typename M>
ros::atomic<M const*> rosrt::Subscriber< M >::latest_
private

Definition at line 230 of file subscriber.h.

template<typename M>
lockfree::ObjectPool<M>* rosrt::Subscriber< M >::pool_
private

Definition at line 232 of file subscriber.h.

template<typename M>
ros::Subscriber rosrt::Subscriber< M >::sub_
private

Definition at line 233 of file subscriber.h.


The documentation for this class was generated from the following file:


rosrt
Author(s): Josh Faust
autogenerated on Mon Jun 10 2019 14:44:46