$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 #ifndef LOCKFREE_OBJECT_POOL_H 00036 #define LOCKFREE_OBJECT_POOL_H 00037 00038 #include "free_list.h" 00039 00040 #include <ros/assert.h> 00041 00042 #include <boost/shared_ptr.hpp> 00043 00044 namespace lockfree 00045 { 00046 00047 template<typename T> 00048 class ObjectPool; 00049 00050 namespace detail 00051 { 00052 00053 struct SPStorage 00054 { 00055 uint8_t data[72]; 00056 }; 00057 00058 template<class T> class SPAllocator; 00059 00060 // specialize for void: 00061 template<> 00062 class SPAllocator<void> 00063 { 00064 public: 00065 typedef void* pointer; 00066 typedef const void* const_pointer; 00067 // reference to void members are impossible. 00068 typedef void value_type; 00069 00070 template<class U> 00071 struct rebind 00072 { 00073 typedef SPAllocator<U> other; 00074 }; 00075 00076 SPAllocator(FreeList* pool, SPStorage* block) throw () 00077 : block_(block) 00078 , used_(0) 00079 , pool_(pool) 00080 { 00081 } 00082 00083 template<class U> 00084 SPAllocator(const SPAllocator<U>& u) throw () 00085 { 00086 block_ = u.get_block(); 00087 used_ = u.get_used(); 00088 pool_ = u.get_pool(); 00089 } 00090 00091 SPStorage* get_block() const { return block_; } 00092 uint32_t get_used() const { return used_; } 00093 FreeList* get_pool() const { return pool_; } 00094 00095 private: 00096 SPStorage* block_; 00097 uint32_t used_; 00098 FreeList* pool_; 00099 }; 00100 00101 template<class T> 00102 class SPAllocator 00103 { 00104 public: 00105 typedef size_t size_type; 00106 typedef ptrdiff_t difference_type; 00107 typedef T* pointer; 00108 typedef const T* const_pointer; 00109 typedef T& reference; 00110 typedef const T& const_reference; 00111 typedef T value_type; 00112 00113 template<class U> 00114 struct rebind 00115 { 00116 typedef SPAllocator<U> other; 00117 }; 00118 00119 SPAllocator(FreeList* pool, SPStorage* block) throw () 00120 : block_(block) 00121 , used_(0) 00122 , pool_(pool) 00123 { 00124 } 00125 00126 template<class U> 00127 SPAllocator(const SPAllocator<U>& u) throw () 00128 { 00129 block_ = u.get_block(); 00130 used_ = u.get_used(); 00131 pool_ = u.get_pool(); 00132 } 00133 00134 ~SPAllocator() throw () 00135 { 00136 } 00137 00138 pointer address(reference r) const 00139 { 00140 return &r; 00141 } 00142 const_pointer address(const_reference r) const 00143 { 00144 return &r; 00145 } 00146 size_type max_size() const throw () 00147 { 00148 return ~size_type(0); 00149 } 00150 pointer allocate(size_type n, SPAllocator<void>::const_pointer hint = 0) 00151 { 00152 uint32_t to_alloc = n * sizeof(T); 00153 ROS_ASSERT_MSG(to_alloc <= (sizeof(SPStorage) - used_), "to_alloc=%d, size=%u, used=%d", to_alloc, (uint32_t)sizeof(SPStorage), used_); 00154 00155 pointer p = reinterpret_cast<pointer>(block_->data + used_); 00156 used_ += to_alloc; 00157 return p; 00158 } 00159 void deallocate(pointer p, size_type n) 00160 { 00161 uint32_t to_free = n * sizeof(T); 00162 used_ -= to_free; 00163 ROS_ASSERT_MSG(used_ >= -(int32_t)sizeof(SPStorage), "to_free=%d, size=%u, used=%d", to_free, (uint32_t)sizeof(SPStorage), used_); 00164 00165 if (used_ == 0 || used_ < 0) 00166 { 00167 pool_->free(block_); 00168 } 00169 } 00170 00171 void construct(pointer p, const_reference val) 00172 { 00173 new (p) T(val); 00174 } 00175 void destroy(pointer p) 00176 { 00177 p->~T(); 00178 } 00179 00180 SPStorage* get_block() const { return block_; } 00181 int32_t get_used() const { return used_; } 00182 FreeList* get_pool() const { return pool_; } 00183 00184 private: 00185 SPStorage* block_; 00186 int32_t used_; 00187 FreeList* pool_; 00188 }; 00189 00190 } // namespace detail 00191 00197 template<typename T> 00198 class ObjectPool 00199 { 00200 struct Deleter 00201 { 00202 Deleter(ObjectPool* pool, detail::SPStorage* storage) 00203 : pool_(pool) 00204 , sp_(storage) 00205 , free_(true) 00206 { 00207 } 00208 00209 void operator()(T const* t) 00210 { 00211 if (free_) 00212 { 00213 pool_->free(t); 00214 } 00215 } 00216 00217 ObjectPool* pool_; 00218 detail::SPStorage* sp_; 00219 bool free_; 00220 }; 00221 00222 00223 00224 public: 00228 ObjectPool() 00229 : initialized_(false) 00230 { 00231 } 00232 00238 ObjectPool(uint32_t count, const T& tmpl) 00239 : initialized_(false) 00240 { 00241 initialize(count, tmpl); 00242 } 00243 00244 ~ObjectPool() 00245 { 00246 freelist_.template destructAll<T>(); 00247 sp_storage_freelist_.template destructAll<detail::SPStorage>(); 00248 } 00249 00253 bool hasOutstandingAllocations() 00254 { 00255 return freelist_.hasOutstandingAllocations() || sp_storage_freelist_.hasOutstandingAllocations(); 00256 } 00257 00263 void initialize(uint32_t count, const T& tmpl) 00264 { 00265 ROS_ASSERT(!initialized_); 00266 freelist_.initialize(sizeof(T), count); 00267 freelist_.template constructAll<T>(tmpl); 00268 sp_storage_freelist_.initialize(sizeof(detail::SPStorage), count); 00269 sp_storage_freelist_.template constructAll<detail::SPStorage>(); 00270 initialized_ = true; 00271 } 00272 00278 boost::shared_ptr<T> allocateShared() 00279 { 00280 ROS_ASSERT(initialized_); 00281 00282 T* item = static_cast<T*>(freelist_.allocate()); 00283 if (!item) 00284 { 00285 return boost::shared_ptr<T>(); 00286 } 00287 00288 boost::shared_ptr<T> ptr = makeShared(item); 00289 if (!ptr) 00290 { 00291 freelist_.free(item); 00292 return boost::shared_ptr<T>(); 00293 } 00294 00295 return ptr; 00296 } 00297 00301 boost::shared_ptr<T> makeShared(T* t) 00302 { 00303 return makeSharedImpl(t); 00304 } 00305 00309 boost::shared_ptr<T const> makeShared(T const* t) 00310 { 00311 return makeSharedImpl<T const>(t); 00312 } 00313 00319 T* removeShared(const boost::shared_ptr<T>& t) 00320 { 00321 ROS_ASSERT(freelist_.owns(t.get())); 00322 00323 Deleter* d = boost::get_deleter<Deleter>(t); 00324 d->free_ = false; 00325 return t.get(); 00326 } 00327 00333 T const* removeShared(const boost::shared_ptr<T const>& t) 00334 { 00335 ROS_ASSERT(freelist_.owns(t.get())); 00336 00337 Deleter* d = boost::get_deleter<Deleter>(t); 00338 d->free_ = false; 00339 return t.get(); 00340 } 00341 00347 T* allocate() 00348 { 00349 return static_cast<T*>(freelist_.allocate()); 00350 } 00351 00356 void free(T const* t) 00357 { 00358 freelist_.free(t); 00359 } 00360 00364 bool owns(T const* t) 00365 { 00366 return freelist_.owns(t); 00367 } 00368 00372 bool owns(const boost::shared_ptr<T const>& t) 00373 { 00374 return owns(t.get()); 00375 } 00376 00377 private: 00378 00379 template<typename T2> 00380 boost::shared_ptr<T2> makeSharedImpl(T2* t) 00381 { 00382 ROS_ASSERT(freelist_.owns(t)); 00383 00384 detail::SPStorage* sp_storage = static_cast<detail::SPStorage*>(sp_storage_freelist_.allocate()); 00385 00386 if (!sp_storage) 00387 { 00388 return boost::shared_ptr<T2>(); 00389 } 00390 00391 boost::shared_ptr<T2> ptr(t, Deleter(this, sp_storage), detail::SPAllocator<void>(&sp_storage_freelist_, sp_storage)); 00392 return ptr; 00393 } 00394 00395 bool initialized_; 00396 00397 FreeList freelist_; 00398 FreeList sp_storage_freelist_; 00399 }; 00400 00401 } // namespace lockfree 00402 00403 #endif // LOCKFREE_OBJECT_POOL_H