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