aligned.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 ALLOCATORS_ALIGNED_H
36 #define ALLOCATORS_ALIGNED_H
37 
38 #include <cstdlib>
39 #include <boost/cstdint.hpp>
40 
41 namespace allocators
42 {
43 
44 // alignedMalloc/alignedFree implementations found at
45 // http://www.gamasutra.com/view/feature/3942/data_alignment_part_1.php?page=2
46 
53 inline void* alignedMalloc(size_t size, size_t alignment)
54 {
55  const int pointerSize = sizeof(void*);
56  const int requestedSize = size + alignment - 1 + pointerSize;
57  void* raw = std::malloc(requestedSize);
58 
59  if (!raw)
60  {
61  return 0;
62  }
63 
64  void* start = (uint8_t*)raw + pointerSize;
65  void* aligned = (void*)(((uintptr_t)((uint8_t*)start+alignment-1)) & ~(alignment-1));
66  *(void**)((uint8_t*)aligned-pointerSize) = raw;
67  return aligned;
68 }
69 
74 inline void alignedFree(void* aligned)
75 {
76  if (!aligned)
77  {
78  return;
79  }
80 
81  void* raw = *(void**)((uint8_t*)aligned - sizeof(void*));
82  std::free(raw);
83 }
84 
85 template<class T, size_t align> class AlignedAllocator;
86 
87 // specialize for void:
88 template<size_t align>
89 class AlignedAllocator<void, align>
90 {
91 public:
92  typedef void* pointer;
93  typedef const void* const_pointer;
94  // reference to void members are impossible.
95  typedef void value_type;
96 
97  template<class U>
98  struct rebind
99  {
101  };
102 };
103 
109 template<class T, size_t align>
110 class AlignedAllocator
111 {
112 public:
113  typedef size_t size_type;
114  typedef ptrdiff_t difference_type;
115  typedef T* pointer;
116  typedef const T* const_pointer;
117  typedef T& reference;
118  typedef const T& const_reference;
119  typedef T value_type;
120 
121  template<class U>
122  struct rebind
123  {
125  };
126 
127  AlignedAllocator() throw ()
128  {
129  }
130 
131  ~AlignedAllocator() throw ()
132  {
133  }
134 
135  pointer address(reference r) const
136  {
137  return &r;
138  }
140  {
141  return &r;
142  }
143  size_type max_size() const throw ()
144  {
145  return ~size_type(0);
146  }
148  {
149  void* mem = alignedMalloc(n * sizeof(T), align);
150  if (!mem)
151  {
152  throw std::bad_alloc();
153  }
154 
155  return static_cast<pointer>(mem);
156  }
157  void deallocate(pointer p, size_type n)
158  {
160  }
161 
162  void construct(pointer p, const_reference val)
163  {
164  new (p) T(val);
165  }
166  void destroy(pointer p)
167  {
168  p->~T();
169  }
170 };
171 
172 } // namespace allocators
173 
174 #endif // ALLOCATORS_ALIGNED_H
175 
allocators::AlignedAllocator::const_reference
const typedef T & const_reference
Definition: aligned.h:150
allocators::AlignedAllocator::address
pointer address(reference r) const
Definition: aligned.h:167
allocators::alignedMalloc
void * alignedMalloc(size_t size, size_t alignment)
Allocate memory aligned at on a value. Memory allocated through alignedMalloc() must be freed through...
Definition: aligned.h:85
allocators::AlignedAllocator< void, align >::pointer
void * pointer
Definition: aligned.h:124
allocators::AlignedAllocator::~AlignedAllocator
~AlignedAllocator()
Definition: aligned.h:163
allocators::AlignedAllocator::const_pointer
const typedef T * const_pointer
Definition: aligned.h:148
allocators::AlignedAllocator::reference
T & reference
Definition: aligned.h:149
allocators::AlignedAllocator::destroy
void destroy(pointer p)
Definition: aligned.h:198
allocators::AlignedAllocator::pointer
T * pointer
Definition: aligned.h:147
allocators::AlignedAllocator::deallocate
void deallocate(pointer p, size_type n)
Definition: aligned.h:189
allocators::alignedFree
void alignedFree(void *aligned)
Free memory allocated through alignedMalloc()
Definition: aligned.h:106
allocators::AlignedAllocator::construct
void construct(pointer p, const_reference val)
Definition: aligned.h:194
allocators::AlignedAllocator::max_size
size_type max_size() const
Definition: aligned.h:175
allocators::AlignedAllocator
An stl-compatible aligned allocator.
Definition: aligned.h:117
allocators
Definition: aligned.h:41
allocators::AlignedAllocator::AlignedAllocator
AlignedAllocator()
Definition: aligned.h:159
allocators::AlignedAllocator::difference_type
ptrdiff_t difference_type
Definition: aligned.h:146
allocators::AlignedAllocator::size_type
size_t size_type
Definition: aligned.h:145
allocators::AlignedAllocator::allocate
pointer allocate(size_type n, typename AlignedAllocator< void, align >::const_pointer hint=0)
Definition: aligned.h:179
allocators::AlignedAllocator::rebind::other
AlignedAllocator< U, align > other
Definition: aligned.h:156
allocators::AlignedAllocator::value_type
T value_type
Definition: aligned.h:151


allocators
Author(s): Josh Faust
autogenerated on Wed Mar 2 2022 00:54:11