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

a realtime-safe ROS publisher More...

#include <publisher.h>

Inheritance diagram for rosrt::Publisher< M >:
Inheritance graph
[legend]

Public Member Functions

boost::shared_ptr< M > allocate ()
 Allocate a message. The message will have been constructed with the template provided to initialize() More...
 
const ros::PublishergetPublisher ()
 Returns the ros::Publisher object in use. More...
 
void initialize (const ros::Publisher &pub, uint32_t message_pool_size, const M &tmpl)
 initialization function. Only use with the default constructor More...
 
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. More...
 
bool publish (const MConstPtr &msg)
 Publish a message. More...
 
 Publisher ()
 Default constructor. You must call initialize() before you use this publisher for anything else. More...
 
 Publisher (const ros::Publisher &pub, uint32_t message_pool_size, const M &tmpl)
 Constructor with initialization. More...
 
 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. More...
 
 ~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 115 of file publisher.h.

Member Typedef Documentation

◆ MConstPtr

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

Definition at line 117 of file publisher.h.

Constructor & Destructor Documentation

◆ Publisher() [1/3]

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 124 of file publisher.h.

◆ Publisher() [2/3]

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
pubA ros::Publisher to use to actually publish any messages
message_pool_sizeThe size of the message pool to provide
tmplA template object to intialize all the messages in the message pool with

Definition at line 135 of file publisher.h.

◆ Publisher() [3/3]

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
nhThe NodeHandle to act on
topicThe topic to publish on
ros_publisher_queue_sizeThe queue size to pass to NodeHandle::advertise()
message_pool_sizeThe size of the message pool to provide
tmplA template object to intialize all the messages in the message pool with

Definition at line 148 of file publisher.h.

◆ ~Publisher()

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

Definition at line 153 of file publisher.h.

Member Function Documentation

◆ allocate()

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 197 of file publisher.h.

◆ getPublisher()

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

Returns the ros::Publisher object in use.

Definition at line 206 of file publisher.h.

◆ initialize() [1/2]

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
pubA ros::Publisher to use to actually publish any messages
message_pool_sizeThe size of the message pool to provide
tmplA template object to intialize all the messages in the message pool with

Definition at line 165 of file publisher.h.

◆ initialize() [2/2]

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
nhThe NodeHandle to act on
topicThe topic to publish on
ros_publisher_queue_sizeThe queue size to pass to NodeHandle::advertise()
message_pool_sizeThe size of the message pool to provide
tmplA template object to intialize all the messages in the message pool with

Definition at line 180 of file publisher.h.

◆ publish()

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

Publish a message.

Definition at line 188 of file publisher.h.

Member Data Documentation

◆ pool_

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

Definition at line 210 of file publisher.h.

◆ pub_

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

Definition at line 209 of file publisher.h.


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


rosrt
Author(s): Josh Faust
autogenerated on Wed Mar 2 2022 00:54:17