array2d.h
Go to the documentation of this file.
00001 #ifndef ARRAY2D_H
00002 #define ARRAY2D_H
00003 
00004 #include <assert.h>
00005 #include <gmapping/utils/point.h>
00006 #include "accessstate.h"
00007 
00008 #include <iostream>
00009 
00010 namespace GMapping {
00011 
00012 template<class Cell, const bool debug=false> class Array2D{
00013         public:
00014                 Array2D(int xsize=0, int ysize=0);
00015                 Array2D& operator=(const Array2D &);
00016                 Array2D(const Array2D<Cell,debug> &);
00017                 ~Array2D();
00018                 void clear();
00019                 void resize(int xmin, int ymin, int xmax, int ymax);
00020                 
00021                 
00022                 inline bool isInside(int x, int y) const;
00023                 inline const Cell& cell(int x, int y) const;
00024                 inline Cell& cell(int x, int y);
00025                 inline AccessibilityState cellState(int x, int y) const { return (AccessibilityState) (isInside(x,y)?(Inside|Allocated):Outside);}
00026                 
00027                 inline bool isInside(const IntPoint& p) const { return isInside(p.x, p.y);}
00028                 inline const Cell& cell(const IntPoint& p) const {return cell(p.x,p.y);}
00029                 inline Cell& cell(const IntPoint& p) {return cell(p.x,p.y);}
00030                 inline AccessibilityState cellState(const IntPoint& p) const { return cellState(p.x, p.y);}
00031                 
00032                 inline int getPatchSize() const{return 0;}
00033                 inline int getPatchMagnitude() const{return 0;}
00034                 inline int getXSize() const {return m_xsize;}
00035                 inline int getYSize() const {return m_ysize;}
00036                 inline Cell** cells() {return m_cells;}
00037                 Cell ** m_cells;
00038         protected:
00039                 int m_xsize, m_ysize;
00040 };
00041 
00042 
00043 template <class Cell, const bool debug>
00044 Array2D<Cell,debug>::Array2D(int xsize, int ysize){
00045 //      assert(xsize>0);
00046 //      assert(ysize>0);
00047         m_xsize=xsize;
00048         m_ysize=ysize;
00049         if (m_xsize>0 && m_ysize>0){
00050                 m_cells=new Cell*[m_xsize];
00051                 for (int i=0; i<m_xsize; i++)
00052                         m_cells[i]=new Cell[m_ysize];
00053         }
00054         else{
00055                 m_xsize=m_ysize=0;
00056                 m_cells=0;
00057         }
00058         if (debug){
00059                 std::cerr << __PRETTY_FUNCTION__ << std::endl;
00060                 std::cerr << "m_xsize= " << m_xsize<< std::endl;
00061                 std::cerr << "m_ysize= " << m_ysize<< std::endl;
00062         }
00063 }
00064 
00065 template <class Cell, const bool debug>
00066 Array2D<Cell,debug> & Array2D<Cell,debug>::operator=(const Array2D<Cell,debug> & g){
00067         if (debug || m_xsize!=g.m_xsize || m_ysize!=g.m_ysize){
00068                 for (int i=0; i<m_xsize; i++)
00069                         delete [] m_cells[i];
00070                 delete [] m_cells;
00071                 m_xsize=g.m_xsize;
00072                 m_ysize=g.m_ysize;
00073                 m_cells=new Cell*[m_xsize];
00074                 for (int i=0; i<m_xsize; i++)
00075                         m_cells[i]=new Cell[m_ysize];
00076         }
00077         for (int x=0; x<m_xsize; x++)
00078                 for (int y=0; y<m_ysize; y++)
00079                         m_cells[x][y]=g.m_cells[x][y];
00080         
00081         if (debug){
00082                 std::cerr << __PRETTY_FUNCTION__ << std::endl;
00083                 std::cerr << "m_xsize= " << m_xsize<< std::endl;
00084                 std::cerr << "m_ysize= " << m_ysize<< std::endl;
00085         }
00086         return *this;
00087 }
00088 
00089 template <class Cell, const bool debug>
00090 Array2D<Cell,debug>::Array2D(const Array2D<Cell,debug> & g){
00091         m_xsize=g.m_xsize;
00092         m_ysize=g.m_ysize;
00093         m_cells=new Cell*[m_xsize];
00094         for (int x=0; x<m_xsize; x++){
00095                 m_cells[x]=new Cell[m_ysize];
00096                 for (int y=0; y<m_ysize; y++)
00097                         m_cells[x][y]=g.m_cells[x][y];
00098         }
00099         if (debug){
00100                 std::cerr << __PRETTY_FUNCTION__ << std::endl;
00101                 std::cerr << "m_xsize= " << m_xsize<< std::endl;
00102                 std::cerr << "m_ysize= " << m_ysize<< std::endl;
00103         }
00104 }
00105 
00106 template <class Cell, const bool debug>
00107 Array2D<Cell,debug>::~Array2D(){
00108   if (debug){
00109         std::cerr << __PRETTY_FUNCTION__ << std::endl;
00110         std::cerr << "m_xsize= " << m_xsize<< std::endl;
00111         std::cerr << "m_ysize= " << m_ysize<< std::endl;
00112   }
00113   for (int i=0; i<m_xsize; i++){
00114     delete [] m_cells[i];
00115     m_cells[i]=0;
00116   }
00117   delete [] m_cells;
00118   m_cells=0;
00119 }
00120 
00121 template <class Cell, const bool debug>
00122 void Array2D<Cell,debug>::clear(){
00123   if (debug){
00124         std::cerr << __PRETTY_FUNCTION__ << std::endl;
00125         std::cerr << "m_xsize= " << m_xsize<< std::endl;
00126         std::cerr << "m_ysize= " << m_ysize<< std::endl;
00127   }
00128   for (int i=0; i<m_xsize; i++){
00129     delete [] m_cells[i];
00130     m_cells[i]=0;
00131   }
00132   delete [] m_cells;
00133   m_cells=0;
00134   m_xsize=0;
00135   m_ysize=0;
00136 }
00137 
00138 
00139 template <class Cell, const bool debug>
00140 void Array2D<Cell,debug>::resize(int xmin, int ymin, int xmax, int ymax){
00141         int xsize=xmax-xmin;
00142         int ysize=ymax-ymin;
00143         Cell ** newcells=new Cell *[xsize];
00144         for (int x=0; x<xsize; x++){
00145                 newcells[x]=new Cell[ysize];
00146         }
00147         int dx= xmin < 0 ? 0 : xmin;
00148         int dy= ymin < 0 ? 0 : ymin;
00149         int Dx=xmax<this->m_xsize?xmax:this->m_xsize;
00150         int Dy=ymax<this->m_ysize?ymax:this->m_ysize;
00151         for (int x=dx; x<Dx; x++){
00152                 for (int y=dy; y<Dy; y++){
00153                         newcells[x-xmin][y-ymin]=this->m_cells[x][y];
00154                 }
00155                 delete [] this->m_cells[x];
00156         }
00157         delete [] this->m_cells;
00158         this->m_cells=newcells;
00159         this->m_xsize=xsize;
00160         this->m_ysize=ysize; 
00161 }
00162 
00163 template <class Cell, const bool debug>
00164 inline bool Array2D<Cell,debug>::isInside(int x, int y) const{
00165         return x>=0 && y>=0 && x<m_xsize && y<m_ysize; 
00166 }
00167 
00168 template <class Cell, const bool debug>
00169 inline const Cell& Array2D<Cell,debug>::cell(int x, int y) const{
00170         assert(isInside(x,y));
00171         return m_cells[x][y];
00172 }
00173 
00174 
00175 template <class Cell, const bool debug>
00176 inline Cell& Array2D<Cell,debug>::cell(int x, int y){
00177         assert(isInside(x,y));
00178         return m_cells[x][y];
00179 }
00180 
00181 };
00182 
00183 #endif
00184 


openslam_gmapping
Author(s): Giorgio Grisetti, Cyrill Stachniss, Wolfram Burgard
autogenerated on Fri Aug 28 2015 11:56:21