object_pool.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 LOCKFREE_OBJECT_POOL_H
36 #define LOCKFREE_OBJECT_POOL_H
37 
38 #include "free_list.h"
39 
40 #include <ros/assert.h>
41 
42 #include <boost/shared_ptr.hpp>
43 
44 namespace lockfree
45 {
46 
47 template<typename T>
48 class ObjectPool;
49 
50 namespace detail
51 {
52 
53 struct SPStorage
54 {
55  uint8_t data[72];
56 };
57 
58 template<class T> class SPAllocator;
59 
60 // specialize for void:
61 template<>
62 class SPAllocator<void>
63 {
64 public:
65  typedef void* pointer;
66  typedef const void* const_pointer;
67  // reference to void members are impossible.
68  typedef void value_type;
69 
70  template<class U>
71  struct rebind
72  {
73  typedef SPAllocator<U> other;
74  };
75 
76  SPAllocator(FreeList* pool, SPStorage* block) throw ()
77  : block_(block)
78  , used_(0)
79  , pool_(pool)
80  {
81  }
82 
83  template<class U>
84  SPAllocator(const SPAllocator<U>& u) throw ()
85  {
86  block_ = u.get_block();
87  used_ = u.get_used();
88  pool_ = u.get_pool();
89  }
90 
91  SPStorage* get_block() const { return block_; }
92  uint32_t get_used() const { return used_; }
93  FreeList* get_pool() const { return pool_; }
94 
95 private:
97  uint32_t used_;
99 };
100 
101 template<class T>
102 class SPAllocator
103 {
104 public:
105  typedef size_t size_type;
106  typedef ptrdiff_t difference_type;
107  typedef T* pointer;
108  typedef const T* const_pointer;
109  typedef T& reference;
110  typedef const T& const_reference;
111  typedef T value_type;
112 
113  template<class U>
114  struct rebind
115  {
117  };
118 
119  SPAllocator(FreeList* pool, SPStorage* block) throw ()
120  : block_(block)
121  , used_(0)
122  , pool_(pool)
123  {
124  }
125 
126  template<class U>
127  SPAllocator(const SPAllocator<U>& u) throw ()
128  {
129  block_ = u.get_block();
130  used_ = u.get_used();
131  pool_ = u.get_pool();
132  }
133 
134  ~SPAllocator() throw ()
135  {
136  }
137 
139  {
140  return &r;
141  }
143  {
144  return &r;
145  }
146  size_type max_size() const throw ()
147  {
148  return ~size_type(0);
149  }
151  {
152  uint32_t to_alloc = n * sizeof(T);
153  ROS_ASSERT_MSG(to_alloc <= (sizeof(SPStorage) - used_), "to_alloc=%d, size=%u, used=%d", to_alloc, (uint32_t)sizeof(SPStorage), used_);
154 
155  pointer p = reinterpret_cast<pointer>(block_->data + used_);
156  used_ += to_alloc;
157  return p;
158  }
160  {
161  uint32_t to_free = n * sizeof(T);
162  used_ -= to_free;
163  ROS_ASSERT_MSG(used_ >= -(int32_t)sizeof(SPStorage), "to_free=%d, size=%u, used=%d", to_free, (uint32_t)sizeof(SPStorage), used_);
164 
165  if (used_ == 0 || used_ < 0)
166  {
167  pool_->free(block_);
168  }
169  }
170 
171  void construct(pointer p, const_reference val)
172  {
173  new (p) T(val);
174  }
175  void destroy(pointer p)
176  {
177  p->~T();
178  }
179 
180  SPStorage* get_block() const { return block_; }
181  int32_t get_used() const { return used_; }
182  FreeList* get_pool() const { return pool_; }
183 
184 private:
185  SPStorage* block_;
186  int32_t used_;
187  FreeList* pool_;
188 };
189 
190 } // namespace detail
191 
197 template<typename T>
198 class ObjectPool
199 {
200  struct Deleter
201  {
202  Deleter(ObjectPool* pool, detail::SPStorage* storage)
203  : pool_(pool)
204  , sp_(storage)
205  , free_(true)
206  {
207  }
208 
209  void operator()(T const* t)
210  {
211  if (free_)
212  {
213  pool_->free(t);
214  }
215  }
216 
219  bool free_;
220  };
221 
222 
223 
224 public:
228  ObjectPool()
229  : initialized_(false)
230  {
231  }
232 
238  ObjectPool(uint32_t count, const T& tmpl)
239  : initialized_(false)
240  {
241  initialize(count, tmpl);
242  }
243 
244  ~ObjectPool()
245  {
246  freelist_.template destructAll<T>();
247  sp_storage_freelist_.template destructAll<detail::SPStorage>();
248  }
249 
254  {
256  }
257 
263  void initialize(uint32_t count, const T& tmpl)
264  {
266  freelist_.initialize(sizeof(T), count);
267  freelist_.template constructAll<T>(tmpl);
269  sp_storage_freelist_.template constructAll<detail::SPStorage>();
270  initialized_ = true;
271  }
272 
279  {
281 
282  T* item = static_cast<T*>(freelist_.allocate());
283  if (!item)
284  {
286  }
287 
288  boost::shared_ptr<T> ptr = makeShared(item);
289  if (!ptr)
290  {
291  freelist_.free(item);
292  return boost::shared_ptr<T>();
293  }
294 
295  return ptr;
296  }
297 
302  {
303  return makeSharedImpl(t);
304  }
305 
310  {
311  return makeSharedImpl<T const>(t);
312  }
313 
320  {
321  ROS_ASSERT(freelist_.owns(t.get()));
322 
323  Deleter* d = boost::get_deleter<Deleter>(t);
324  d->free_ = false;
325  return t.get();
326  }
327 
334  {
335  ROS_ASSERT(freelist_.owns(t.get()));
336 
337  Deleter* d = boost::get_deleter<Deleter>(t);
338  d->free_ = false;
339  return t.get();
340  }
341 
347  T* allocate()
348  {
349  return static_cast<T*>(freelist_.allocate());
350  }
351 
356  void free(T const* t)
357  {
358  freelist_.free(t);
359  }
360 
364  bool owns(T const* t)
365  {
366  return freelist_.owns(t);
367  }
368 
372  bool owns(const boost::shared_ptr<T const>& t)
373  {
374  return owns(t.get());
375  }
376 
377 private:
378 
379  template<typename T2>
381  {
383 
384  detail::SPStorage* sp_storage = static_cast<detail::SPStorage*>(sp_storage_freelist_.allocate());
385 
386  if (!sp_storage)
387  {
389  }
390 
391  boost::shared_ptr<T2> ptr(t, Deleter(this, sp_storage), detail::SPAllocator<void>(&sp_storage_freelist_, sp_storage));
392  return ptr;
393  }
394 
395  bool initialized_;
396 
399 };
400 
401 } // namespace lockfree
402 
403 #endif // LOCKFREE_OBJECT_POOL_H
lockfree::detail::SPAllocator::get_pool
FreeList * get_pool() const
Definition: object_pool.h:214
lockfree::ObjectPool::Deleter::Deleter
Deleter(ObjectPool *pool, detail::SPStorage *storage)
Definition: object_pool.h:234
lockfree::FreeList::free
void free(void const *mem)
Free a block of memory allocated from this FreeList.
Definition: free_list.cpp:170
lockfree::detail::SPAllocator::difference_type
ptrdiff_t difference_type
Definition: object_pool.h:138
lockfree::detail::SPStorage::data
uint8_t data[72]
Definition: object_pool.h:87
boost::shared_ptr
lockfree::ObjectPool::makeSharedImpl
boost::shared_ptr< T2 > makeSharedImpl(T2 *t)
Definition: object_pool.h:412
lockfree::detail::SPAllocator::reference
T & reference
Definition: object_pool.h:141
lockfree::detail::SPAllocator::pool_
FreeList * pool_
Definition: object_pool.h:219
lockfree::detail::SPAllocator::construct
void construct(pointer p, const_reference val)
Definition: object_pool.h:203
lockfree::ObjectPool
A fixed-count lock-free pool of the same type of object. Supports both bare- and shared-pointer alloc...
Definition: object_pool.h:80
lockfree::ObjectPool::sp_storage_freelist_
FreeList sp_storage_freelist_
Definition: object_pool.h:430
lockfree::FreeList::owns
bool owns(void const *mem)
Returns whether or not this FreeList owns a block of memory.
Definition: free_list.cpp:239
lockfree::detail::SPAllocator::allocate
pointer allocate(size_type n, SPAllocator< void >::const_pointer hint=0)
Definition: object_pool.h:182
lockfree::detail::SPAllocator::destroy
void destroy(pointer p)
Definition: object_pool.h:207
lockfree::ObjectPool::removeShared
T * removeShared(const boost::shared_ptr< T > &t)
"Remove" a shared pointer allocated by this pool, turning it into a bare pointer. shared_ptrs held to...
Definition: object_pool.h:351
lockfree::FreeList::initialize
void initialize(uint32_t block_size, uint32_t block_count)
Initialize this FreeList. Only use if you used to default constructor.
Definition: free_list.cpp:72
lockfree::ObjectPool::hasOutstandingAllocations
bool hasOutstandingAllocations()
Returns whether or not this ObjectPool has any outstanding allocations.
Definition: object_pool.h:285
lockfree::detail::SPAllocator::~SPAllocator
~SPAllocator()
Definition: object_pool.h:166
lockfree::ObjectPool::allocate
T * allocate()
Allocate a single object from the pool, returning a bare pointer.
Definition: object_pool.h:379
lockfree::ObjectPool::Deleter::pool_
ObjectPool * pool_
Definition: object_pool.h:249
lockfree::detail::SPAllocator::get_used
int32_t get_used() const
Definition: object_pool.h:213
lockfree::detail::SPAllocator::const_reference
const typedef T & const_reference
Definition: object_pool.h:142
lockfree::detail::SPAllocator::max_size
size_type max_size() const
Definition: object_pool.h:178
lockfree::ObjectPool::Deleter::free_
bool free_
Definition: object_pool.h:251
lockfree::detail::SPAllocator
Definition: object_pool.h:90
lockfree::ObjectPool::Deleter::operator()
void operator()(T const *t)
Definition: object_pool.h:241
lockfree::detail::SPAllocator::size_type
size_t size_type
Definition: object_pool.h:137
ROS_ASSERT_MSG
#define ROS_ASSERT_MSG(cond,...)
lockfree::detail::SPAllocator< void >
Definition: object_pool.h:94
lockfree::detail::SPAllocator::deallocate
void deallocate(pointer p, size_type n)
Definition: object_pool.h:191
d
d
lockfree::ObjectPool::freelist_
FreeList freelist_
Definition: object_pool.h:429
lockfree::ObjectPool::allocateShared
boost::shared_ptr< T > allocateShared()
Allocate a single object from the pool, returning a shared pointer.
Definition: object_pool.h:310
free_list.h
lockfree::detail::SPStorage
Definition: object_pool.h:85
lockfree::ObjectPool::Deleter
Definition: object_pool.h:232
lockfree::detail::SPAllocator::get_block
SPStorage * get_block() const
Definition: object_pool.h:212
lockfree::ObjectPool::owns
bool owns(T const *t)
Returns whether or not this pool owns the provided object.
Definition: object_pool.h:396
lockfree::detail::SPAllocator::const_pointer
const typedef T * const_pointer
Definition: object_pool.h:140
lockfree::ObjectPool::makeShared
boost::shared_ptr< T > makeShared(T *t)
Make a shared_ptr out of a bare pointer allocated by this pool.
Definition: object_pool.h:333
lockfree::ObjectPool::free
void free(T const *t)
Return an object allocated through allocateBare() to the pool.
Definition: object_pool.h:388
lockfree::FreeList::allocate
void * allocate()
Allocate a single block from this FreeList.
Definition: free_list.cpp:108
lockfree::detail::SPAllocator::block_
SPStorage * block_
Definition: object_pool.h:217
lockfree::ObjectPool::initialize
void initialize(uint32_t count, const T &tmpl)
initialize the pool. Only use with the default constructor
Definition: object_pool.h:295
lockfree::FreeList
A lock-free (not wait-free) statically-sized free-list implemented with CAS.
Definition: free_list.h:67
lockfree::detail::SPAllocator::value_type
T value_type
Definition: object_pool.h:143
lockfree::detail::SPAllocator::pointer
T * pointer
Definition: object_pool.h:139
lockfree::ObjectPool::Deleter::sp_
detail::SPStorage * sp_
Definition: object_pool.h:250
lockfree::detail::SPAllocator::rebind::other
SPAllocator< U > other
Definition: object_pool.h:148
lockfree::detail::SPAllocator::SPAllocator
SPAllocator(FreeList *pool, SPStorage *block)
Definition: object_pool.h:151
lockfree::detail::SPAllocator::address
pointer address(reference r) const
Definition: object_pool.h:170
lockfree::FreeList::hasOutstandingAllocations
bool hasOutstandingAllocations()
Returns whether or not this FreeList currently has any outstanding allocations.
Definition: free_list.cpp:103
lockfree::ObjectPool::ObjectPool
ObjectPool()
Default constructor. Must call initialize() before calling allocate()
Definition: object_pool.h:260
assert.h
ROS_ASSERT
#define ROS_ASSERT(cond)
lockfree::ObjectPool::initialized_
bool initialized_
Definition: object_pool.h:427
lockfree::ObjectPool::~ObjectPool
~ObjectPool()
Definition: object_pool.h:276
lockfree::detail::SPAllocator::used_
int32_t used_
Definition: object_pool.h:218
lockfree
Definition: free_list.h:54


lockfree
Author(s): Josh Faust
autogenerated on Wed Mar 2 2022 00:54:15