publisher.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2010, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #ifndef ROSRT_PUBLISHER_H
36 #define ROSRT_PUBLISHER_H
37 
38 #include <lockfree/object_pool.h>
39 #include "detail/pool_gc.h"
40 
41 #include <ros/publisher.h>
42 #include <ros/node_handle.h>
43 #include <boost/utility.hpp>
44 
45 namespace rosrt
46 {
47 
49 
50 typedef void(*PublishFunc)(const ros::Publisher& pub, const VoidConstPtr& msg);
51 typedef VoidConstPtr(*CloneFunc)(const VoidConstPtr& msg);
52 
53 namespace detail
54 {
55 template<typename M>
56 void publishMessage(const ros::Publisher& pub, const VoidConstPtr& msg)
57 {
58  boost::shared_ptr<M const> m = boost::static_pointer_cast<M const>(msg);
59  pub.publish(m);
60 }
61 
62 template<typename M>
63 VoidConstPtr cloneMessage(const VoidConstPtr& msg)
64 {
65  boost::shared_ptr<M> clone(new M);
66  *clone = *boost::static_pointer_cast<M const>(msg);
67  return clone;
68 }
69 
70 bool publish(const ros::Publisher& pub, const VoidConstPtr& msg, PublishFunc pub_func, CloneFunc clone_func);
71 
72 template<typename M>
73 bool publish(const ros::Publisher& pub, const VoidConstPtr& msg)
74 {
75  return publish(pub, msg, publishMessage<M>, cloneMessage<M>);
76 }
77 } // namespace detail
78 
82 template<typename M>
83 class Publisher : public boost::noncopyable
84 {
86 
87 public:
93  : pool_(NULL)
94  {
95  }
96 
103  Publisher(const ros::Publisher& pub, uint32_t message_pool_size, const M& tmpl)
104  {
105  initialize(pub, message_pool_size, tmpl);
106  }
107 
116  Publisher(ros::NodeHandle& nh, const std::string& topic, uint32_t ros_publisher_queue_size, uint32_t message_pool_size, const M& tmpl)
117  {
118  initialize(nh, topic, ros_publisher_queue_size, message_pool_size, tmpl);
119  }
120 
122  {
123  if (pool_)
124  detail::addPoolToGC((void*)pool_, detail::deletePool<M>, detail::poolIsDeletable<M>);
125  }
126 
133  void initialize(const ros::Publisher& pub, uint32_t message_pool_size, const M& tmpl)
134  {
135  pub_ = pub;
136  pool_ = new lockfree::ObjectPool<M>();
137  pool_->initialize(message_pool_size, tmpl);
138  }
139 
148  void initialize(ros::NodeHandle& nh, const std::string& topic, uint32_t ros_publisher_queue_size, uint32_t message_pool_size, const M& tmpl)
149  {
150  initialize(nh.advertise<M>(topic, ros_publisher_queue_size), message_pool_size, tmpl);
151  }
152 
156  bool publish(const MConstPtr& msg)
157  {
158  return detail::publish<M>(pub_, msg);
159  }
160 
166  {
167  assert(pool_);
168  return pool_->allocateShared();
169  }
170 
174  const ros::Publisher& getPublisher() { return pub_; }
175 
176 private:
179 };
180 
181 } // namespace rosrt
182 
183 #endif // ROSRT_PUBLISHER_H
const ros::Publisher & getPublisher()
Returns the ros::Publisher object in use.
Definition: publisher.h:174
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.
Definition: publisher.h:116
ROSCONSOLE_DECL void initialize()
boost::shared_ptr< void const > VoidConstPtr
Definition: publisher.h:48
lockfree::ObjectPool< M > * pool_
Definition: publisher.h:178
void initialize(uint32_t count, const T &tmpl)
VoidConstPtr(* CloneFunc)(const VoidConstPtr &msg)
Definition: publisher.h:51
ros::Publisher pub_
Definition: publisher.h:177
void publishMessage(const ros::Publisher &pub, const VoidConstPtr &msg)
Definition: publisher.h:56
Definition: managers.h:38
a realtime-safe ROS publisher
Definition: publisher.h:83
void(* PublishFunc)(const ros::Publisher &pub, const VoidConstPtr &msg)
Definition: publisher.h:50
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
VoidConstPtr cloneMessage(const VoidConstPtr &msg)
Definition: publisher.h:63
bool publish(const ros::Publisher &pub, const VoidConstPtr &msg, PublishFunc pub_func, CloneFunc clone_func)
Definition: publisher.cpp:50
Publisher(const ros::Publisher &pub, uint32_t message_pool_size, const M &tmpl)
Constructor with initialization.
Definition: publisher.h:103
boost::shared_ptr< M const > MConstPtr
Definition: publisher.h:85
void initialize(const ros::Publisher &pub, uint32_t message_pool_size, const M &tmpl)
initialization function. Only use with the default constructor
Definition: publisher.h:133
Publisher()
Default constructor. You must call initialize() before you use this publisher for anything else...
Definition: publisher.h:92
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.
Definition: publisher.h:148
boost::shared_ptr< M > allocate()
Allocate a message. The message will have been constructed with the template provided to initialize()...
Definition: publisher.h:165
bool publish(const MConstPtr &msg)
Publish a message.
Definition: publisher.h:156
void addPoolToGC(void *pool, PoolDeleteFunc deleter, PoolDeletableFunc deletable)
Definition: simple_gc.cpp:59


rosrt
Author(s): Josh Faust
autogenerated on Fri Apr 5 2019 02:16:39