callback_queue.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, 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 Willow Garage, Inc. 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 ROSCPP_CALLBACK_QUEUE_H
36 #define ROSCPP_CALLBACK_QUEUE_H
37 
38 // check if we might need to include our own backported version boost::condition_variable
39 // in order to use CLOCK_MONOTONIC for the condition variable
40 // the include order here is important!
41 #ifdef BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC
42 #include <boost/version.hpp>
43 #if BOOST_VERSION < 106100
44 // use backported version of boost condition variable, see https://svn.boost.org/trac/boost/ticket/6377
46 #else // Boost version is 1.61 or greater and has the steady clock fixes
47 #include <boost/thread/condition_variable.hpp>
48 #endif
49 #else // !BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC
50 #include <boost/thread/condition_variable.hpp>
51 #endif // BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC
52 
54 #include "ros/time.h"
55 #include "common.h"
56 
57 #include <boost/shared_ptr.hpp>
58 #include <boost/thread/mutex.hpp>
59 #include <boost/thread/shared_mutex.hpp>
60 #include <boost/thread/tss.hpp>
61 
62 #include <list>
63 #include <deque>
64 
65 namespace ros
66 {
67 
71 class ROSCPP_DECL CallbackQueue : public CallbackQueueInterface
72 {
73 public:
74  CallbackQueue(bool enabled = true);
75  virtual ~CallbackQueue();
76 
77  virtual void addCallback(const CallbackInterfacePtr& callback, uint64_t removal_id = 0);
78  virtual void removeByID(uint64_t removal_id);
79 
81  {
86  };
87 
93  {
94  return callOne(ros::WallDuration());
95  }
96 
105  CallOneResult callOne(ros::WallDuration timeout);
106 
111  {
112  callAvailable(ros::WallDuration());
113  }
121  void callAvailable(ros::WallDuration timeout);
122 
126  bool empty() { return isEmpty(); }
130  bool isEmpty();
134  void clear();
135 
139  void enable();
143  void disable();
147  bool isEnabled();
148 
149 protected:
150  void setupTLS();
151 
152  struct TLS;
153  CallOneResult callOneCB(TLS* tls);
154 
155  struct IDInfo
156  {
157  uint64_t id;
158  boost::shared_mutex calling_rw_mutex;
159  };
161  typedef std::map<uint64_t, IDInfoPtr> M_IDInfo;
162 
163  IDInfoPtr getIDInfo(uint64_t id);
164 
166  {
168  : removal_id(0)
169  , marked_for_removal(false)
170  {}
172  uint64_t removal_id;
174  };
175  typedef std::list<CallbackInfo> L_CallbackInfo;
176  typedef std::deque<CallbackInfo> D_CallbackInfo;
177  D_CallbackInfo callbacks_;
178  size_t calling_;
179  boost::mutex mutex_;
181 
182  boost::mutex id_info_mutex_;
183  M_IDInfo id_info_;
184 
185  struct TLS
186  {
187  TLS()
188  : calling_in_this_thread(0xffffffffffffffffULL)
189  , cb_it(callbacks.end())
190  {}
192  D_CallbackInfo callbacks;
193  D_CallbackInfo::iterator cb_it;
194  };
195  boost::thread_specific_ptr<TLS> tls_;
196 
197  bool enabled_;
198 };
200 
201 }
202 
203 #endif
boost::mutex mutex_
boost::thread_specific_ptr< TLS > tls_
D_CallbackInfo::iterator cb_it
bool empty()
returns whether or not the queue is empty
This is the default implementation of the ros::CallbackQueueInterface.
boost::shared_mutex calling_rw_mutex
CallOneResult callOne()
Pop a single callback off the front of the queue and invoke it. If the callback was not ready to be c...
Abstract interface for a queue used to handle all callbacks within roscpp.
std::map< uint64_t, IDInfoPtr > M_IDInfo
D_CallbackInfo callbacks_
boost::shared_ptr< IDInfo > IDInfoPtr
boost::shared_ptr< CallbackQueue > CallbackQueuePtr
void callAvailable()
Invoke all callbacks currently in the queue. If a callback was not ready to be called, pushes it back onto the queue.
D_CallbackInfo callbacks
boost::mutex id_info_mutex_
std::list< CallbackInfo > L_CallbackInfo
boost::condition_variable condition_
std::deque< CallbackInfo > D_CallbackInfo


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Sun Feb 3 2019 03:29:54