rosrt::Publisher< M > Class Template Reference

a realtime-safe ROS publisher More...

#include <publisher.h>

List of all members.

Public Member Functions

boost::shared_ptr< M > allocate ()
 Allocate a message. The message will have been constructed with the template provided to initialize().
const ros::Publisher & getPublisher ()
 Returns the ros::Publisher object in use.
void initialize (ros::NodeHandle &nh, const std::string &topic, uint32_t ros_publisher_queue_size, uint32_t message_pool_size, const M &tmpl)
 Constructor with initialization, simple version.
void initialize (const ros::Publisher &pub, uint32_t message_pool_size, const M &tmpl)
 initialization function. Only use with the default constructor
bool publish (const MConstPtr &msg)
 Publish a message.
 Publisher (ros::NodeHandle &nh, const std::string &topic, uint32_t ros_publisher_queue_size, uint32_t message_pool_size, const M &tmpl)
 Constructor with initialization, simple version.
 Publisher (const ros::Publisher &pub, uint32_t message_pool_size, const M &tmpl)
 Constructor with initialization.
 Publisher ()
 Default constructor. You must call initialize() before you use this publisher for anything else.
 ~Publisher ()

Private Types

typedef boost::shared_ptr< M
const > 
MConstPtr

Private Attributes

lockfree::ObjectPool< M > * pool_
ros::Publisher pub_

Detailed Description

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

a realtime-safe ROS publisher

Definition at line 77 of file publisher.h.


Member Typedef Documentation

template<typename M>
typedef boost::shared_ptr<M const> rosrt::Publisher< M >::MConstPtr [private]

Definition at line 79 of file publisher.h.


Constructor & Destructor Documentation

template<typename M>
rosrt::Publisher< M >::Publisher (  )  [inline]

Default constructor. You must call initialize() before you use this publisher for anything else.

Definition at line 86 of file publisher.h.

template<typename M>
rosrt::Publisher< M >::Publisher ( const ros::Publisher< M > &  pub,
uint32_t  message_pool_size,
const M &  tmpl 
) [inline]

Constructor with initialization.

Parameters:
pub A ros::Publisher to use to actually publish any messages
message_pool_size The size of the message pool to provide
tmpl A template object to intialize all the messages in the message pool with

Definition at line 97 of file publisher.h.

template<typename M>
rosrt::Publisher< M >::Publisher ( ros::NodeHandle &  nh,
const std::string &  topic,
uint32_t  ros_publisher_queue_size,
uint32_t  message_pool_size,
const M &  tmpl 
) [inline]

Constructor with initialization, simple version.

Parameters:
nh The NodeHandle to act on
topic The topic to publish on
ros_publisher_queue_size The queue size to pass to NodeHandle::advertise()
message_pool_size The size of the message pool to provide
tmpl A template object to intialize all the messages in the message pool with

Definition at line 110 of file publisher.h.

template<typename M>
rosrt::Publisher< M >::~Publisher (  )  [inline]

Definition at line 115 of file publisher.h.


Member Function Documentation

template<typename M>
boost::shared_ptr<M> rosrt::Publisher< M >::allocate (  )  [inline]

Allocate a message. The message will have been constructed with the template provided to initialize().

Definition at line 159 of file publisher.h.

template<typename M>
const ros::Publisher& rosrt::Publisher< M >::getPublisher (  )  [inline]

Returns the ros::Publisher object in use.

Definition at line 168 of file publisher.h.

template<typename M>
void rosrt::Publisher< M >::initialize ( ros::NodeHandle &  nh,
const std::string &  topic,
uint32_t  ros_publisher_queue_size,
uint32_t  message_pool_size,
const M &  tmpl 
) [inline]

Constructor with initialization, simple version.

Parameters:
nh The NodeHandle to act on
topic The topic to publish on
ros_publisher_queue_size The queue size to pass to NodeHandle::advertise()
message_pool_size The size of the message pool to provide
tmpl A template object to intialize all the messages in the message pool with

Definition at line 142 of file publisher.h.

template<typename M>
void rosrt::Publisher< M >::initialize ( const ros::Publisher< M > &  pub,
uint32_t  message_pool_size,
const M &  tmpl 
) [inline]

initialization function. Only use with the default constructor

Parameters:
pub A ros::Publisher to use to actually publish any messages
message_pool_size The size of the message pool to provide
tmpl A template object to intialize all the messages in the message pool with

Definition at line 127 of file publisher.h.

template<typename M>
bool rosrt::Publisher< M >::publish ( const MConstPtr msg  )  [inline]

Publish a message.

Definition at line 150 of file publisher.h.


Member Data Documentation

template<typename M>
lockfree::ObjectPool<M>* rosrt::Publisher< M >::pool_ [private]

Definition at line 172 of file publisher.h.

template<typename M>
ros::Publisher rosrt::Publisher< M >::pub_ [private]

Definition at line 171 of file publisher.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Defines


rosrt
Author(s): Josh Faust
autogenerated on Fri Jan 11 10:07:46 2013