a realtime-safe ROS publisher More...
#include <publisher.h>
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::Publisher & | getPublisher () |
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_ |
a realtime-safe ROS publisher
Definition at line 83 of file publisher.h.
|
private |
Definition at line 85 of file publisher.h.
|
inline |
Default constructor. You must call initialize() before you use this publisher for anything else.
Definition at line 92 of file publisher.h.
|
inline |
Constructor with initialization.
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 103 of file publisher.h.
|
inline |
Constructor with initialization, simple version.
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 116 of file publisher.h.
|
inline |
Definition at line 121 of file publisher.h.
|
inline |
Allocate a message. The message will have been constructed with the template provided to initialize()
Definition at line 165 of file publisher.h.
|
inline |
Returns the ros::Publisher object in use.
Definition at line 174 of file publisher.h.
|
inline |
initialization function. Only use with the default constructor
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 133 of file publisher.h.
|
inline |
Constructor with initialization, simple version.
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 148 of file publisher.h.
|
inline |
Publish a message.
Definition at line 156 of file publisher.h.
|
private |
Definition at line 178 of file publisher.h.
|
private |
Definition at line 177 of file publisher.h.