managed_list.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, 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 ACTIONLIB__MANAGED_LIST_H_
36 #define ACTIONLIB__MANAGED_LIST_H_
37 
39 #include <boost/thread.hpp>
40 #include <boost/shared_ptr.hpp>
41 #include <boost/weak_ptr.hpp>
42 
43 #include <list>
44 
45 #include "ros/console.h"
46 
47 namespace actionlib
48 {
49 
55 template<class T>
57 {
58 private:
59  struct TrackedElem
60  {
61  T elem;
62  boost::weak_ptr<void> handle_tracker_;
63  };
64 
65 public:
66  class Handle;
67 
68  class iterator
69  {
70 public:
71  iterator() {}
72  T & operator*() {return it_->elem; }
73  T & operator->() {return it_->elem; }
74  const T & operator*() const {return it_->elem; }
75  const T & operator->() const {return it_->elem; }
76  bool operator==(const iterator & rhs) const {return it_ == rhs.it_; }
77  bool operator!=(const iterator & rhs) const {return !(*this == rhs); }
78  void operator++() {it_++; }
79  Handle createHandle();
80  friend class ManagedList;
81 
82 private:
83  iterator(typename std::list<TrackedElem>::iterator it)
84  : it_(it) {}
85  typename std::list<TrackedElem>::iterator it_;
86  };
87 
88  typedef typename boost::function<void (iterator)> CustomDeleter;
89 
90 private:
92  {
93 public:
94  ElemDeleter(iterator it, CustomDeleter deleter,
96  : it_(it), deleter_(deleter), guard_(guard)
97  {}
98 
99  void operator()(void *)
100  {
101  DestructionGuard::ScopedProtector protector(*guard_);
102  if (!protector.isProtected()) {
103  ROS_ERROR_NAMED("actionlib",
104  "ManagedList: The DestructionGuard associated with this list has already been destructed. You must delete all list handles before deleting the ManagedList");
105  return;
106  }
107 
108  ROS_DEBUG_NAMED("actionlib", "IN DELETER");
109  if (deleter_) {
110  deleter_(it_);
111  }
112  }
113 
114 private:
116  CustomDeleter deleter_;
118  };
119 
120 public:
121  class Handle
122  {
123 public:
128  : it_(iterator()), handle_tracker_(boost::shared_ptr<void>()), valid_(false) {}
129 
130  Handle & operator=(const Handle & rhs)
131  {
132  if (rhs.valid_) {
133  it_ = rhs.it_;
134  }
136  valid_ = rhs.valid_;
137  return *this;
138  }
139 
144  void reset()
145  {
146  valid_ = false;
147 #ifndef _MSC_VER
148  // this prevents a crash on MSVC, but I bet the problem is elsewhere.
149  // it puts the lotion in the basket.
150  it_ = iterator();
151 #endif
152  handle_tracker_.reset();
153  }
154 
160  T & getElem()
161  {
162  assert(valid_);
163  if (!valid_) {
164  ROS_ERROR_NAMED("actionlib","getElem() should not see invalid handles");
165  }
166  return *it_;
167  }
168 
169  const T & getElem() const
170  {
171  assert(valid_);
172  if (!valid_) {
173  ROS_ERROR_NAMED("actionlib","getElem() should not see invalid handles");
174  }
175  return *it_;
176  }
177 
181  bool operator==(const Handle & rhs) const
182  {
183  assert(valid_);
184  if (!valid_) {
185  ROS_ERROR_NAMED("actionlib", "operator== should not see invalid handles");
186  }
187  assert(rhs.valid_);
188  if (!rhs.valid_) {
189  ROS_ERROR_NAMED("actionlib", "operator== should not see invalid RHS handles");
190  }
191  return it_ == rhs.it_;
192  }
193 
194  friend class ManagedList;
195  // Need this friend declaration so that iterator::createHandle() can
196  // call the private Handle::Handle() declared below.
197  friend class iterator;
198 
199 private:
200  Handle(const boost::shared_ptr<void> & handle_tracker, iterator it)
201  : it_(it), handle_tracker_(handle_tracker), valid_(true)
202  {}
203 
206  bool valid_;
207  };
208 
210 
214  Handle add(const T & elem)
215  {
216  return add(elem, boost::bind(&ManagedList<T>::defaultDeleter, this, _1) );
217  }
218 
224  Handle add(const T & elem, CustomDeleter custom_deleter,
226  {
227  TrackedElem tracked_t;
228  tracked_t.elem = elem;
229 
230  typename std::list<TrackedElem>::iterator list_it = list_.insert(list_.end(), tracked_t);
231  iterator managed_it = iterator(list_it);
232 
233  ElemDeleter deleter(managed_it, custom_deleter, guard);
234  boost::shared_ptr<void> tracker( (void *) NULL, deleter);
235 
236  list_it->handle_tracker_ = tracker;
237 
238  return Handle(tracker, managed_it);
239  }
240 
244  void erase(iterator it)
245  {
246  list_.erase(it.it_);
247  }
248 
249  iterator end() {return iterator(list_.end()); }
250  iterator begin() {return iterator(list_.begin()); }
251 
252 private:
253  void defaultDeleter(iterator it)
254  {
255  erase(it);
256  }
257  std::list<TrackedElem> list_;
258 };
259 
260 
261 template<class T>
263  if (it_->handle_tracker_.expired()) {
264  ROS_ERROR_NAMED("actionlib", "Tried to create a handle to a list elem with refcount 0");
265  }
266 
267  boost::shared_ptr<void> tracker = it_->handle_tracker_.lock();
268 
269  return Handle(tracker, *this);
270 }
271 
272 } // namespace actionlib
273 
274 #endif // ACTIONLIB__MANAGED_LIST_H_
Handle createHandle()
Creates a refcounted Handle from an iterator.
Definition: managed_list.h:262
Handle & operator=(const Handle &rhs)
Definition: managed_list.h:130
iterator(typename std::list< TrackedElem >::iterator it)
Definition: managed_list.h:83
std::list< TrackedElem > list_
Definition: managed_list.h:257
std::list< TrackedElem >::iterator it_
Definition: managed_list.h:85
T & getElem()
get the list element that this handle points to fails/asserts if this is an empty handle ...
Definition: managed_list.h:160
bool isProtected()
Checks if the ScopedProtector successfully protected the DestructionGuard.
Handle add(const T &elem)
Add an element to the back of the ManagedList.
Definition: managed_list.h:214
boost::function< void(iterator)> CustomDeleter
Definition: managed_list.h:88
Handle()
Construct an empty handle.
Definition: managed_list.h:127
void erase(iterator it)
Removes an element from the ManagedList.
Definition: managed_list.h:244
boost::shared_ptr< DestructionGuard > guard_
Definition: managed_list.h:117
void defaultDeleter(iterator it)
Definition: managed_list.h:253
#define ROS_DEBUG_NAMED(name,...)
wrapper around an STL list to help with reference counting Provides handles elements in an STL list...
Definition: managed_list.h:56
bool operator==(const iterator &rhs) const
Definition: managed_list.h:76
void reset()
stop tracking the list element with this handle, even though the Handle hasn&#39;t gone out of scope ...
Definition: managed_list.h:144
bool operator!=(const iterator &rhs) const
Definition: managed_list.h:77
boost::shared_ptr< void > handle_tracker_
Definition: managed_list.h:205
boost::weak_ptr< void > handle_tracker_
Definition: managed_list.h:62
Handle(const boost::shared_ptr< void > &handle_tracker, iterator it)
Definition: managed_list.h:200
#define ROS_ERROR_NAMED(name,...)
ElemDeleter(iterator it, CustomDeleter deleter, const boost::shared_ptr< DestructionGuard > &guard)
Definition: managed_list.h:94
Protects a DestructionGuard until this object goes out of scope.
bool operator==(const Handle &rhs) const
Checks if two handles point to the same list elem.
Definition: managed_list.h:181
Handle add(const T &elem, CustomDeleter custom_deleter, const boost::shared_ptr< DestructionGuard > &guard)
Add an element to the back of the ManagedList, along with a Custom deleter.
Definition: managed_list.h:224


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Feb 28 2022 21:34:38