MIRA
Buffer.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2012 by
3  * MetraLabs GmbH (MLAB), GERMANY
4  * and
5  * Neuroinformatics and Cognitive Robotics Labs (NICR) at TU Ilmenau, GERMANY
6  * All rights reserved.
7  *
8  * Contact: info@mira-project.org
9  *
10  * Commercial Usage:
11  * Licensees holding valid commercial licenses may use this file in
12  * accordance with the commercial license agreement provided with the
13  * software or, alternatively, in accordance with the terms contained in
14  * a written agreement between you and MLAB or NICR.
15  *
16  * GNU General Public License Usage:
17  * Alternatively, this file may be used under the terms of the GNU
18  * General Public License version 3.0 as published by the Free Software
19  * Foundation and appearing in the file LICENSE.GPL3 included in the
20  * packaging of this file. Please review the following information to
21  * ensure the GNU General Public License version 3.0 requirements will be
22  * met: http://www.gnu.org/copyleft/gpl.html.
23  * Alternatively you may (at your option) use any later version of the GNU
24  * General Public License if such license has been publicly approved by
25  * MLAB and NICR (or its successors, if any).
26  *
27  * IN NO EVENT SHALL "MLAB" OR "NICR" BE LIABLE TO ANY PARTY FOR DIRECT,
28  * INDIRECT, SPECIAL, INCIDENTAL, OR CONSEQUENTIAL DAMAGES ARISING OUT OF
29  * THE USE OF THIS SOFTWARE AND ITS DOCUMENTATION, EVEN IF "MLAB" OR
30  * "NICR" HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31  *
32  * "MLAB" AND "NICR" SPECIFICALLY DISCLAIM ANY WARRANTIES, INCLUDING,
33  * BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
34  * FITNESS FOR A PARTICULAR PURPOSE. THE SOFTWARE PROVIDED HEREUNDER IS
35  * ON AN "AS IS" BASIS, AND "MLAB" AND "NICR" HAVE NO OBLIGATION TO
36  * PROVIDE MAINTENANCE, SUPPORT, UPDATES, ENHANCEMENTS OR MODIFICATIONS.
37  */
38 
47 #ifndef _MIRA_BUFFER_H_
48 #define _MIRA_BUFFER_H_
49 
50 #include <memory>
51 #include <stdexcept>
52 #include <vector>
53 
54 #include <platform/Types.h>
55 
56 #ifndef Q_MOC_RUN
57 #include <boost/type_traits.hpp>
58 #endif
59 
61 #include <serialization/Array.h>
64 
65 namespace mira {
66 
68 
83 template <typename T, typename Alloc = std::allocator<T> >
84 class Buffer
85 {
86  // the is_pod check is too hard here, since user defined constructors
87  // are allowed, as long there is a trivial default constructor,
88  // copy constructor and trivial destructor
89  static_assert(boost::has_trivial_destructor<T>::value,
90  "Can be used with types that have trivial destructor only");
91  static_assert(boost::has_trivial_default_constructor<T>::value,
92  "Can be used with types that have a trivial default constructor only");
93  static_assert(boost::has_trivial_copy_constructor<T>::value,
94  "Can be used with types that have a trivial copy constructor only");
95 
96  // TODO: The standard library has renamed all of the above has_trivial_XYZ to
97  // is_trivially_XYZable WITHOUT providing the old versions for
98  // backward compatibility. Therefore, the following code works on
99  // GCC >= 4.8 but fails on previous GCCs versions and MSVC. Therefore,
100  // we prefer to use the boost variants above, which seem to be more
101  // stable than the standard
102  //static_assert(std::is_trivially_destructible<T>::value,
103  // "Can be used with types that have trivial destructor only");
104  //static_assert(std:::is_trivially_default_constructible<T>::value,
105  // "Can be used with types that have a trivial default constructor only");
106  //static_assert(std::is_trivially_copy_constructible<T>::value,
107  // "Can be used with types that have a trivial copy constructor only");
108 
109 
110 public:
111 
112  // some STL conform typedefs
113  typedef T value_type;
114  typedef typename Alloc::pointer pointer;
115  typedef typename Alloc::const_pointer const_pointer;
116  typedef typename Alloc::reference reference;
117  typedef typename Alloc::const_reference const_reference;
118  typedef T* iterator;
119  typedef const T* const_iterator;
120  typedef std::size_t size_type;
121  typedef ptrdiff_t difference_type;
122  typedef Alloc allocator_type;
123 
124 private:
125 
126  void init() {
127  mBuffer = NULL;
128  mReserved = mSize = 0;
129  mBufferCreated = false;
130  mTakenVector = NULL;
131  }
132 
133 public:
134 
136  Buffer() {
137  init();
138  }
139 
140  /*
141  * Create a buffer and allocate memory of size size
142  */
144  init();
145  resize(size);
146  }
147 
153  Buffer(T* carray, size_type size) {
154  mBuffer = carray;
155  mReserved = mSize = size;
156  mBufferCreated = false;
157  mTakenVector = NULL;
158  }
159 
179  Buffer(std::vector<T>&& other)
180  {
181  mTakenVector = new std::vector<T>;
182  mTakenVector->swap(other);
183 
184  mBuffer = &(*mTakenVector)[0];
185  mReserved = mTakenVector->capacity();
186  mSize = mTakenVector->size();
187  mBufferCreated = false;
188  }
189 
192  setBuffer(NULL, 0);
193  }
194 
195 public:
196 
198  Buffer(const Buffer& other) {
199  init();
200  copy(other);
201  }
202 
204  Buffer& operator=(const Buffer& other) {
205  copy(other);
206  return *this;
207  }
208 
210  void copy(const Buffer& other) {
211  resize(other.size());
212  memcpy(mBuffer, other.data(), other.size()*sizeof(T));
213  }
214 
215 public:
216  // Move semantic
217 
219  Buffer(Buffer&& other) noexcept {
220  init();
221  swap(other);
222  }
223 
225  Buffer& operator=(Buffer&& other) noexcept {
226  swap(other);
227  return *this;
228  }
229 
231  void swap(Buffer& other) {
232  std::swap(mBuffer, other.mBuffer);
233  std::swap(mSize, other.mSize);
234  std::swap(mReserved, other.mReserved);
235  std::swap(mBufferCreated, other.mBufferCreated);
236  std::swap(mTakenVector, other.mTakenVector);
237  }
238 
239 public:
240 
242  bool operator==(const Buffer& other) const {
243  if(size()!=other.size())
244  return false;
245  assert(sizeInBytes()==other.sizeInBytes());
246  return memcmp(data(), other.data(), sizeInBytes()) == 0;
247  }
248 
250  bool operator!=(const Buffer& other) const {
251  return !operator==(other);
252  }
253 
254 public:
255 
260  iterator begin() { return mBuffer; }
261 
266  const_iterator begin() const { return mBuffer; }
267 
272  iterator end() { return mBuffer+mSize; } // also works if empty
273 
278  const_iterator end() const { return mBuffer+mSize; }
279 
280 public:
284  size_type max_size () const { return mAllocator.max_size(); }
285 
289  size_type size() const { return mSize; }
290 
294  size_type sizeInBytes() const { return mSize * sizeof(T); }
295 
299  bool empty () const { return mSize==0; }
300 
305  size_type capacity () const { return mReserved; }
306 
311 
312 public:
313 
320  {
321  if(reserve > mReserved)
322  {
323  std::size_t newSize = mReserved;
324  if(newSize==0)
325  newSize=1;
326  while(reserve > newSize)
327  newSize *= 2;
328 
329  T* newBuffer = mAllocator.allocate(newSize);
330  if(mBuffer!=NULL)
331  memcpy(newBuffer, mBuffer, mSize*sizeof(T));
332  setBuffer(newBuffer, newSize);
333  mBufferCreated = true;
334  }
335  }
336 
337 public:
338 
347  {
348  reserve(size); // make sure buffer is big enough
349  mSize = size;
350  }
351 
352 public:
353 
358  void push_back(const T& x) {
359  resize(mSize+1);
360  mBuffer[mSize-1] = x;
361  }
362 
369  }
370 
375  void push_back(const Buffer<T>& data) {
376  size_type oldSize = mSize;
377  resize(mSize + data.size());
378  memcpy(mBuffer+oldSize*sizeof(T), data.data(), data.sizeInBytes());
379  }
380 
386  void pop_back() {
387  pop_back(1);
388  }
389 
395  void pop_back(size_type elements) {
396  if (elements >= mSize)
397  {
398  this->clear();
399  return;
400  }
401  resize(mSize-elements);
402  }
403 
408  void pop_front() {
409  pop_front(1);
410  }
411 
416  void pop_front(size_type elements) {
417  if (elements >= mSize)
418  {
419  clear();
420  return;
421  }
422  // Move the memory
423  if (elements > 0)
424  {
425  memmove(mBuffer, mBuffer+elements*sizeof(T), (mSize-elements)*sizeof(T));
426  resize(mSize-elements);
427  }
428  }
429 
433  void clear() {
434  mSize = 0;
435  }
436 
437 public:
438 
443  assert(n<mSize);
444  return mBuffer[n];
445  }
446 
451  assert(n<mSize);
452  return mBuffer[n];
453  }
454 
461  rangeCheck(n);
462  return mBuffer[n];
463  }
464 
471  rangeCheck(n);
472  return mBuffer[n];
473  }
474 
479  assert(mSize>0);
480  return mBuffer[0];
481  }
482 
487  assert(mSize>0);
488  return mBuffer[0];
489  }
490 
495  assert(mSize>0);
496  return mBuffer[size()-1];
497  }
498 
503  assert(mSize>0);
504  return mBuffer[size()-1];
505  }
506 
510  pointer data() { return mBuffer; }
511 
515  const_pointer data() const { return mBuffer; }
516 
517 protected:
518 
520  void rangeCheck(size_type n) const
521  {
522  if (n >= size())
523  throw std::out_of_range("Buffer::range_check");
524  }
526 
527 private:
528 
530  void setBuffer(T* newBuffer, size_type size)
531  {
532  // delete old buffer, if any
533  if(mBufferCreated)
534  mAllocator.deallocate(mBuffer,mReserved);
535 
536  // data might have come from a taken over vector, which now is no longer needed
537  delete mTakenVector;
538  mTakenVector = NULL;
539 
540  mBuffer = newBuffer;
541  mReserved = size;
542  }
544 
545 protected:
546 
547  T* mBuffer;
551 
552  Alloc mAllocator;
553 
554  std::vector<T>* mTakenVector;
555 };
556 
558 
560 template<typename Reflector, typename T, typename Allocator>
561 void reflectRead(Reflector& r, Buffer<T, Allocator>& c)
562 {
563  // store the size first
564  uint32 count = c.size();
565  {
567  MIRA_REFLECT_CALL(Reflector, r, "Buffer ReflectCollectionCount",
569  }
570  // store the elements as array
571  serialization::PlainArray<T> array(c.data(), c.size());
572  r.delegate(array);
573 }
574 
576 template<typename Reflector, typename T, typename Allocator>
577 void reflectWrite(Reflector& r, Buffer<T, Allocator>& c)
578 {
579  // restore the size first
580  uint32 count;
581  {
583  MIRA_REFLECT_CALL(Reflector, r, "Buffer ReflectCollectionCount",
585  }
586  // reserve the space and create the elements
587  c.resize(count);
588  // restore the elements as array
589  serialization::PlainArray<T> array(c.data(), c.size());
590  r.delegate(array);
591 }
592 
594 template<typename Reflector, typename T, typename Allocator>
595 void reflect(Reflector& r, Buffer<T, Allocator>& c)
596 {
597  splitReflect(r, c);
598 }
599 
600 template<typename T, typename Allocator>
601 class IsObjectTrackable<Buffer<T, Allocator>> : public std::false_type {};
602 
603 template<typename T, typename Allocator>
604 class IsCollection<Buffer<T, Allocator>> : public std::true_type {};
605 
607 
608 }
609 
610 #endif
Type trait that indicates whether pointer tracking can be enabled for this type.
Definition: IsObjectTrackable.h:68
void reflectWrite(Reflector &r, Buffer< T, Allocator > &c)
Specialization of the non-intrusive reflect for Buffer.
Definition: Buffer.h:577
Alloc::const_pointer const_pointer
Definition: Buffer.h:115
reference back()
Returns a reference to the last element in the vector container.
Definition: Buffer.h:494
bool operator!=(const Buffer &other) const
Checks for inequality with other buffer.
Definition: Buffer.h:250
bool operator==(const Buffer &other) const
Checks for equality with other buffer.
Definition: Buffer.h:242
Macros for use with reflectors.
void pop_back()
Removes the last element in the vector, effectively reducing the vector size by one.
Definition: Buffer.h:386
std::size_t size_type
Definition: Buffer.h:120
specialize cv::DataType for our ImgPixel and inherit from cv::DataType<Vec>
Definition: IOService.h:67
Buffer(Buffer &&other) noexcept
Move constructor.
Definition: Buffer.h:219
bool mBufferCreated
Was the buffer created (is it owned) by us.
Definition: Buffer.h:550
Buffer & operator=(const Buffer &other)
Assignment.
Definition: Buffer.h:204
Buffer(T *carray, size_type size)
Use already allocated memory in carray with size size.
Definition: Buffer.h:153
Alloc mAllocator
The allocator used to allocate new memory.
Definition: Buffer.h:552
const T * const_iterator
Definition: Buffer.h:119
size_type mReserved
The real size of the buffer.
Definition: Buffer.h:549
uint32_t uint32
Definition: Types.h:64
ptrdiff_t difference_type
Definition: Buffer.h:121
T value_type
Definition: Buffer.h:90
Alloc::reference reference
Definition: Buffer.h:116
Provides type trait that indicates whether a type should be serialized "transparently".
allocator_type get_allocator() const
Returns the allocator.
Definition: Buffer.h:310
const_reference front() const
Returns a reference to the first element in the vector container.
Definition: Buffer.h:486
void reserve(size_type reserve)
Allocates new memory if reserved size < new reserved size.
Definition: Buffer.h:319
T * mBuffer
Pointer to the data buffer.
Definition: Buffer.h:547
size_type mSize
The used elements of the buffer.
Definition: Buffer.h:548
size_type sizeInBytes() const
Returns the used size in bytes.
Definition: Buffer.h:294
Buffer(const Buffer &other)
Copy constructor.
Definition: Buffer.h:198
void push_back(const T &x)
Adds a new element at the end of the vector, after its current last element.
Definition: Buffer.h:358
Buffer & operator=(Buffer &&other) noexcept
Move assignment.
Definition: Buffer.h:225
Wrapper class for reflecting arrays.
void pop_front(size_type elements)
Removes the first elements in the vector by copying all remaining data to the front invalidating all ...
Definition: Buffer.h:416
Alloc::pointer pointer
Definition: Buffer.h:114
void swap(Buffer &other)
Swaps the content of this buffer with the other buffer.
Definition: Buffer.h:231
Contains the base interface of all Reflectors, Serializers, etc.
const_pointer data() const
Returns a const pointer to the underlying data.
Definition: Buffer.h:515
T * iterator
Definition: Buffer.h:118
#define MIRA_REFLECT_CALL(ReflectorType, reflector, context, COMMAND)
Whenever a reflection function calls another function that is independently maintained, the call should be marked to the reflector.
Definition: ReflectorMacros.h:109
reference front()
Returns a reference to the first element in the vector container.
Definition: Buffer.h:478
size_type size() const
Returns the used size of the buffer set by resize()
Definition: Buffer.h:289
const_reference at(size_type n) const
The difference between this member function and member operator function operator[] is that vector::a...
Definition: Buffer.h:470
void push_back(const Buffer< T > &data)
Adds new elements to the end of the vector, after its current last element.
Definition: Buffer.h:375
bool empty() const
Checks if the buffer is empty (used size == 0).
Definition: Buffer.h:299
pointer data()
Returns a pointer to the underlying data.
Definition: Buffer.h:510
Buffer()
Default constructor constructing an empty buffer.
Definition: Buffer.h:136
reference at(size_type n)
The difference between this member function and member operator function operator[] is that vector::a...
Definition: Buffer.h:460
const_reference back() const
Returns a reference to the last element in the vector container.
Definition: Buffer.h:502
void reflect(Reflector &r, LogRecord &record)
Non-intrusive reflector for LogRecord.
Definition: LoggingCore.h:137
size_type max_size() const
Returns the maximum size of the buffer.
Definition: Buffer.h:284
Buffer(size_type size)
Definition: Buffer.h:143
Generic buffer class that can be used as a replacement for std::vector whenever copying and reallocat...
Definition: Buffer.h:84
~Buffer()
Destructor.
Definition: Buffer.h:191
std::vector< T > * mTakenVector
Used to take over the data from a vector without copying.
Definition: Buffer.h:554
void push_back(T *data, size_type size)
Adds new elements to the end of the vector, after its current last element.
Definition: Buffer.h:367
Can be specialized for a concrete derived RecursiveMemberReflector to reflect the size of collections...
Definition: ReflectCollection.h:69
void pop_back(size_type elements)
Removes the last elements in the vector, effectively reducing the vector size by elements.
Definition: Buffer.h:395
iterator begin()
Returns an iterator referring to the first element in the vector container.
Definition: Buffer.h:260
void reflectRead(Reflector &r, Buffer< T, Allocator > &c)
Specialization of the non-intrusive reflect for Buffer.
Definition: Buffer.h:561
void resize(size_type size)
Resizes the buffer.
Definition: Buffer.h:346
void clear()
All the elements of the vector are dropped.
Definition: Buffer.h:433
void pop_front()
Removes the first element in the vector by copying all remaining data to the front invalidating all i...
Definition: Buffer.h:408
iterator end()
Returns an iterator referring to the past-the-end element in the vector container.
Definition: Buffer.h:272
void copy(const Buffer &other)
Copies a buffer into this.
Definition: Buffer.h:210
Type trait that indicates whether a type is a collection.
Definition: IsCollection.h:63
const_iterator end() const
Returns an iterator referring to the past-the-end element in the vector container.
Definition: Buffer.h:278
Alloc::const_reference const_reference
Definition: Buffer.h:117
Alloc allocator_type
Definition: Buffer.h:122
Buffer(std::vector< T > &&other)
Constructs a buffer that TAKES OVER all data from the specified vector.
Definition: Buffer.h:179
const_iterator begin() const
Returns an iterator referring to the first element in the vector container.
Definition: Buffer.h:266
size_type capacity() const
Returns the reserved size/capacity of the buffer (Its real size) set by reserve() ...
Definition: Buffer.h:305
reference operator[](size_type n)
Returns a reference to the element at position n in the vector container.
Definition: Buffer.h:442