35 #ifndef ROSRT_PUBLISHER_H    36 #define ROSRT_PUBLISHER_H    43 #include <boost/utility.hpp>    66   *clone = *boost::static_pointer_cast<M 
const>(msg);
    75   return publish(pub, msg, publishMessage<M>, cloneMessage<M>);
   116   Publisher(
ros::NodeHandle& nh, 
const std::string& topic, uint32_t ros_publisher_queue_size, uint32_t message_pool_size, 
const M& tmpl)
   118     initialize(nh, topic, ros_publisher_queue_size, message_pool_size, tmpl);
   148   void initialize(
ros::NodeHandle& nh, 
const std::string& topic, uint32_t ros_publisher_queue_size, uint32_t message_pool_size, 
const M& tmpl)
   158     return detail::publish<M>(pub_, msg);
   168     return pool_->allocateShared();
   183 #endif // ROSRT_PUBLISHER_H 
const ros::Publisher & getPublisher()
Returns the ros::Publisher object in use. 
void publish(const boost::shared_ptr< M > &message) const 
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. 
ROSCONSOLE_DECL void initialize()
boost::shared_ptr< void const  > VoidConstPtr
lockfree::ObjectPool< M > * pool_
void initialize(uint32_t count, const T &tmpl)
VoidConstPtr(* CloneFunc)(const VoidConstPtr &msg)
void publishMessage(const ros::Publisher &pub, const VoidConstPtr &msg)
a realtime-safe ROS publisher 
void(* PublishFunc)(const ros::Publisher &pub, const VoidConstPtr &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
VoidConstPtr cloneMessage(const VoidConstPtr &msg)
bool publish(const ros::Publisher &pub, const VoidConstPtr &msg, PublishFunc pub_func, CloneFunc clone_func)
Publisher(const ros::Publisher &pub, uint32_t message_pool_size, const M &tmpl)
Constructor with initialization. 
boost::shared_ptr< M const  > MConstPtr
void initialize(const ros::Publisher &pub, uint32_t message_pool_size, const M &tmpl)
initialization function. Only use with the default constructor 
Publisher()
Default constructor. You must call initialize() before you use this publisher for anything else...
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. 
boost::shared_ptr< M > allocate()
Allocate a message. The message will have been constructed with the template provided to initialize()...
bool publish(const MConstPtr &msg)
Publish a message. 
void addPoolToGC(void *pool, PoolDeleteFunc deleter, PoolDeletableFunc deletable)