free_list.h
Go to the documentation of this file.
00001 
00002 /*********************************************************************
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2010, Willow Garage, Inc.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the Willow Garage nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *********************************************************************/
00035 
00036 #ifndef LOCKFREE_FREE_LIST_H
00037 #define LOCKFREE_FREE_LIST_H
00038 
00039 #include <ros/assert.h>
00040 #include <ros/atomic.h>
00041 
00042 #if FREE_LIST_DEBUG
00043 #include <boost/thread.hpp>
00044 #endif
00045 
00046 #define ROSRT_CACHELINE_SIZE 64 // TODO: actually determine this.
00047 
00048 #if FREE_LIST_DEBUG
00049 #define FREELIST_DEBUG_YIELD() sched_yield()
00050 #else
00051 #define FREELIST_DEBUG_YIELD()
00052 #endif
00053 
00054 namespace lockfree
00055 {
00056 
00067 class FreeList
00068 {
00069 public:
00073   FreeList();
00079   FreeList(uint32_t block_size, uint32_t block_count);
00080   ~FreeList();
00081 
00087   void initialize(uint32_t block_size, uint32_t block_count);
00088 
00093   void* allocate();
00098   void free(void const* mem);
00104   bool owns(void const* mem);
00105 
00109   bool hasOutstandingAllocations();
00110 
00120   template<typename T>
00121   void constructAll(const T& tmpl)
00122   {
00123     ROS_ASSERT(sizeof(T) <= block_size_);
00124     for (uint32_t i = 0; i < block_count_; ++i)
00125     {
00126       new (blocks_ + (i * block_size_)) T(tmpl);
00127     }
00128   }
00129 
00137   template<typename T>
00138   void constructAll()
00139   {
00140     ROS_ASSERT(sizeof(T) <= block_size_);
00141     for (uint32_t i = 0; i < block_count_; ++i)
00142     {
00143       new (blocks_ + (i * block_size_)) T();
00144     }
00145   }
00146 
00151   template<typename T>
00152   void destructAll()
00153   {
00154     ROS_ASSERT(sizeof(T) <= block_size_);
00155     for (uint32_t i = 0; i < block_count_; ++i)
00156     {
00157       reinterpret_cast<T*>(blocks_ + (i * block_size_))->~T();
00158     }
00159   }
00160 
00161 #if FREE_LIST_DEBUG
00162   struct Debug;
00163   Debug* getDebug()
00164   {
00165     return debug_.get();
00166   }
00167 #endif
00168 
00169 private:
00170 
00171   inline uint32_t getTag(uint64_t val)
00172   {
00173     return (uint32_t)(val >> 32);
00174   }
00175 
00176   inline uint32_t getVal(uint64_t val)
00177   {
00178     return (uint32_t)val & 0xffffffff;
00179   }
00180 
00181   inline void setTag(uint64_t& val, uint32_t tag)
00182   {
00183     val = getVal(val) | ((uint64_t)tag << 32);
00184   }
00185 
00186   inline void setVal(uint64_t& val, uint32_t v)
00187   {
00188     val = ((uint64_t)getTag(val) << 32) | v;
00189   }
00190 
00191   uint8_t* blocks_;
00192   ros::atomic_uint32_t* next_;
00193   ros::atomic_uint64_t head_;
00194   ros::atomic_uint32_t alloc_count_;
00195 
00196   uint32_t block_size_;
00197   uint32_t block_count_;
00198 
00199 #if FREE_LIST_DEBUG
00200   struct Debug
00201   {
00202     enum
00203     {
00204       Alloc,
00205       Free
00206     };
00207 
00208     struct Item
00209     {
00210       Item()
00211       : head(0xffffffff)
00212       , new_head(0xffffffff)
00213       , addr(0)
00214       , op(0xff)
00215       , success(0)
00216       {}
00217       ros::WallTime time;
00218       uint64_t head;
00219       uint64_t new_head;
00220       uint8_t* addr;
00221       uint8_t op;
00222       uint8_t success;
00223     };
00224 
00225     std::vector<Item> items;
00226     std::string thread;
00227   };
00228 
00229   void initDebug()
00230   {
00231     if (!debug_.get())
00232     {
00233       debug_.reset(new Debug);
00234       std::stringstream ss;
00235       ss << boost::this_thread::get_id();
00236       debug_->thread = ss.str();
00237     }
00238   }
00239 
00240   boost::thread_specific_ptr<Debug> debug_;
00241 #endif
00242 };
00243 
00244 } // namespace lockfree
00245 
00246 #endif // LOCKFREE_FREE_LIST_H


lockfree
Author(s): Josh Faust
autogenerated on Wed Aug 26 2015 16:00:00