free_list.h
Go to the documentation of this file.
1 
2 /*********************************************************************
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2010, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *********************************************************************/
35 
36 #ifndef LOCKFREE_FREE_LIST_H
37 #define LOCKFREE_FREE_LIST_H
38 
39 #include <ros/assert.h>
40 #include <ros/atomic.h>
41 
42 #if FREE_LIST_DEBUG
43 #include <boost/thread.hpp>
44 #endif
45 
46 #define ROSRT_CACHELINE_SIZE 64 // TODO: actually determine this.
47 
48 #if FREE_LIST_DEBUG
49 #define FREELIST_DEBUG_YIELD() sched_yield()
50 #else
51 #define FREELIST_DEBUG_YIELD()
52 #endif
53 
54 namespace lockfree
55 {
56 
67 class FreeList
68 {
69 public:
73  FreeList();
79  FreeList(uint32_t block_size, uint32_t block_count);
80  ~FreeList();
81 
87  void initialize(uint32_t block_size, uint32_t block_count);
88 
93  void* allocate();
98  void free(void const* mem);
104  bool owns(void const* mem);
105 
110 
120  template<typename T>
121  void constructAll(const T& tmpl)
122  {
123  ROS_ASSERT(sizeof(T) <= block_size_);
124  for (uint32_t i = 0; i < block_count_; ++i)
125  {
126  new (blocks_ + (i * block_size_)) T(tmpl);
127  }
128  }
129 
137  template<typename T>
139  {
140  ROS_ASSERT(sizeof(T) <= block_size_);
141  for (uint32_t i = 0; i < block_count_; ++i)
142  {
143  new (blocks_ + (i * block_size_)) T();
144  }
145  }
146 
151  template<typename T>
152  void destructAll()
153  {
154  ROS_ASSERT(sizeof(T) <= block_size_);
155  for (uint32_t i = 0; i < block_count_; ++i)
156  {
157  reinterpret_cast<T*>(blocks_ + (i * block_size_))->~T();
158  }
159  }
160 
161 #if FREE_LIST_DEBUG
162  struct Debug;
163  Debug* getDebug()
164  {
165  return debug_.get();
166  }
167 #endif
168 
169 private:
170 
171  inline uint32_t getTag(uint64_t val)
172  {
173  return (uint32_t)(val >> 32);
174  }
175 
176  inline uint32_t getVal(uint64_t val)
177  {
178  return (uint32_t)val & 0xffffffff;
179  }
180 
181  inline void setTag(uint64_t& val, uint32_t tag)
182  {
183  val = getVal(val) | ((uint64_t)tag << 32);
184  }
185 
186  inline void setVal(uint64_t& val, uint32_t v)
187  {
188  val = ((uint64_t)getTag(val) << 32) | v;
189  }
190 
191  uint8_t* blocks_;
192  ros::atomic_uint32_t* next_;
193  ros::atomic_uint64_t head_;
194  ros::atomic_uint32_t alloc_count_;
195 
196  uint32_t block_size_;
197  uint32_t block_count_;
198 
199 #if FREE_LIST_DEBUG
200  struct Debug
201  {
202  enum
203  {
204  Alloc,
205  Free
206  };
207 
208  struct Item
209  {
210  Item()
211  : head(0xffffffff)
212  , new_head(0xffffffff)
213  , addr(0)
214  , op(0xff)
215  , success(0)
216  {}
217  ros::WallTime time;
218  uint64_t head;
219  uint64_t new_head;
220  uint8_t* addr;
221  uint8_t op;
222  uint8_t success;
223  };
224 
225  std::vector<Item> items;
226  std::string thread;
227  };
228 
229  void initDebug()
230  {
231  if (!debug_.get())
232  {
233  debug_.reset(new Debug);
234  std::stringstream ss;
235  ss << boost::this_thread::get_id();
236  debug_->thread = ss.str();
237  }
238  }
239 
240  boost::thread_specific_ptr<Debug> debug_;
241 #endif
242 };
243 
244 } // namespace lockfree
245 
246 #endif // LOCKFREE_FREE_LIST_H
lockfree::FreeList::blocks_
uint8_t * blocks_
Definition: free_list.h:191
lockfree::FreeList::free
void free(void const *mem)
Free a block of memory allocated from this FreeList.
Definition: free_list.cpp:170
lockfree::FreeList::getTag
uint32_t getTag(uint64_t val)
Definition: free_list.h:171
lockfree::FreeList::block_size_
uint32_t block_size_
Definition: free_list.h:196
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::FreeList::alloc_count_
ros::atomic_uint32_t alloc_count_
Definition: free_list.h:194
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::FreeList::destructAll
void destructAll()
Destruct all the objects in this FreeList. You must have called constructAll() first.
Definition: free_list.h:152
lockfree::FreeList::~FreeList
~FreeList()
Definition: free_list.cpp:61
lockfree::FreeList::constructAll
void constructAll(const T &tmpl)
Construct all the blocks with a specific template. If you call this you must call destructAll() prior...
Definition: free_list.h:121
lockfree::FreeList::block_count_
uint32_t block_count_
Definition: free_list.h:197
Debug
Debug
lockfree::FreeList::head_
ros::atomic_uint64_t head_
Definition: free_list.h:193
atomic.h
ros::WallTime
lockfree::FreeList::FreeList
FreeList()
Default constructor. You must call initialize() if you use this constructor.
Definition: free_list.cpp:44
lockfree::FreeList::allocate
void * allocate()
Allocate a single block from this FreeList.
Definition: free_list.cpp:108
lockfree::FreeList::setTag
void setTag(uint64_t &val, uint32_t tag)
Definition: free_list.h:181
lockfree::FreeList
A lock-free (not wait-free) statically-sized free-list implemented with CAS.
Definition: free_list.h:67
lockfree::FreeList::setVal
void setVal(uint64_t &val, uint32_t v)
Definition: free_list.h:186
lockfree::FreeList::hasOutstandingAllocations
bool hasOutstandingAllocations()
Returns whether or not this FreeList currently has any outstanding allocations.
Definition: free_list.cpp:103
assert.h
ROS_ASSERT
#define ROS_ASSERT(cond)
lockfree::FreeList::constructAll
void constructAll()
Construct all the blocks with a default constructor. If you call this you must call destructAll() pri...
Definition: free_list.h:138
lockfree::FreeList::getVal
uint32_t getVal(uint64_t val)
Definition: free_list.h:176
lockfree::FreeList::next_
ros::atomic_uint32_t * next_
Definition: free_list.h:192
lockfree
Definition: free_list.h:54


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