allocator.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2009-2012, Willow Garage, Inc.
00006  *  Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho,
00007  *                      Johns Hopkins University
00008  *
00009  *  All rights reserved.
00010  *
00011  *  Redistribution and use in source and binary forms, with or without
00012  *  modification, are permitted provided that the following conditions
00013  *  are met:
00014  *
00015  *   * Redistributions of source code must retain the above copyright
00016  *     notice, this list of conditions and the following disclaimer.
00017  *   * Redistributions in binary form must reproduce the above
00018  *     copyright notice, this list of conditions and the following
00019  *     disclaimer in the documentation and/or other materials provided
00020  *     with the distribution.
00021  *   * Neither the name of Willow Garage, Inc. nor the names of its
00022  *     contributors may be used to endorse or promote products derived
00023  *     from this software without specific prior written permission.
00024  *
00025  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00026  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00027  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00028  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00029  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00030  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00031  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00032  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00033  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00034  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00035  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00036  *  POSSIBILITY OF SUCH DAMAGE.
00037  *
00038  * $Id: allocator.h 5036 2012-03-12 08:54:15Z rusu $
00039  *
00040  */
00041 
00042 
00043 #ifndef PCL_POISSON_ALLOCATOR_H_
00044 #define PCL_POISSON_ALLOCATOR_H_
00045 #include <vector>
00046 
00047 namespace pcl 
00048 {
00049   namespace poisson 
00050   {
00051     class AllocatorState
00052     {
00053       public:
00054         int index,remains;
00055     };
00056 
00065     template<class T>
00066     class Allocator
00067     {
00068       int blockSize;
00069       int index, remains;
00070       std::vector<T*> memory;
00071 
00072       public:
00073         Allocator () : blockSize (0), index (0), remains (0), memory ()
00074         {
00075         }
00076 
00077         ~Allocator ()
00078         {
00079           reset ();
00080         }
00081 
00085         void 
00086         reset ()
00087         {
00088           for (size_t i = 0; i < memory.size (); i++)
00089             delete[] memory[i];
00090 
00091           memory.clear ();
00092           blockSize = index = remains = 0;
00093         }
00094 
00096         AllocatorState 
00097         getState () const
00098         {
00099           AllocatorState s;
00100           s.index = index;
00101           s.remains = remains;
00102           return (s);
00103         }
00104 
00110         void 
00111         rollBack ()
00112         {
00113           if(memory.size ())
00114           {
00115             for (size_t i = 0; i < memory.size (); i++)
00116             {
00117               for (int j = 0; j < blockSize; j++)
00118               {
00119                 memory[i][j].~T();
00120                 new(&memory[i][j]) T();
00121               }
00122             }
00123             index = 0;
00124             remains = blockSize;
00125           }
00126         }
00127 
00133         void 
00134         rollBack (const AllocatorState& state)
00135         {
00136           if (state.index < index || (state.index == index && state.remains < remains))
00137           {
00138             if (state.index < index)
00139             {
00140               for (int j = state.remains; j < blockSize; j++)
00141               {
00142                 memory[state.index][j].~T ();
00143                 new (&memory[state.index][j]) T();
00144               }
00145 
00146               for (int i = state.index + 1; i < index - 1; i++)
00147               {
00148                 for (int j = 0; j < blockSize; j++)
00149                 {
00150                   memory[i][j].~T();
00151                   new(&memory[i][j]) T();
00152                 }
00153               }
00154               for (int j = 0; j < remains; j++)
00155               {
00156                 memory[index][j].~T();
00157                 new(&memory[index][j]) T();
00158               }
00159               index = state.index;
00160               remains = state.remains;
00161             }
00162             else
00163             {
00164               for (int j = 0; j < state.remains; j<remains)
00165               {
00166                 memory[index][j].~T();
00167                 new(&memory[index][j]) T();
00168               }
00169               remains = state.remains;
00170             }
00171           }
00172         }
00173 
00177         void 
00178         set (const int& blockSize)
00179         {
00180           reset ();
00181           this->blockSize = blockSize;
00182           index = -1;
00183           remains = 0;
00184         }
00185 
00191         T* 
00192         newElements (const int& elements = 1)
00193         {
00194           T* mem;
00195           if (!elements)
00196             return (NULL);
00197          
00198           if (elements>blockSize)
00199           {
00200             fprintf (stderr, "Allocator Error, elements bigger than block-size: %d>%d\n", elements,blockSize);
00201             return (NULL);
00202           }
00203           if (remains<elements)
00204           {
00205             if(index == static_cast<int>(memory.size() - 1))
00206             {
00207               mem = new T[blockSize];
00208 
00209               if (!mem)
00210                 throw "Failed to allocate memory";
00211               memory.push_back (mem);
00212             }
00213             index++;
00214             remains = blockSize;
00215           }
00216           mem = &(memory[index][blockSize-remains]);
00217           remains -= elements;
00218           return (mem);
00219         }
00220     };
00221   }
00222 }
00223 
00224 
00225 #endif /* PCL_POISSON_ALLOCATOR_H_ */


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:14:38