diff --git a/include/gmapping/grid/array2d.h b/include/gmapping/grid/array2d.h index aebf4a5..c48e48e 100644 --- a/include/gmapping/grid/array2d.h +++ b/include/gmapping/grid/array2d.h @@ -54,16 +54,22 @@ Array2D::Array2D(int xsize, int ysize){ } m_xsize=xsize; m_ysize=ysize; - if (m_xsize>0 && m_ysize>0){ + if (m_xsize>0 && m_ysize>0) + { m_cells=CellArray2d(new CellArray[m_xsize], [](auto ptr){ delete[] ptr; }); for (int i=0; i::HierarchicalArray2D(const HierarchicalArray2D& hg) { this->m_cells.reset(); } - // the Array2D m_cells is a std::shared_ptr[]>, where Cell is std::shared_ptr< Array2D > - this->m_cells=HCellArray2d(new HCellArray[this->m_xsize], [](auto ptr){ delete[] ptr; }); - for (int x=0; xm_xsize; x++){ - this->m_cells[x]=HCellArray(new HCell[this->m_ysize]); - for (int y=0; ym_ysize; y++) - this->m_cells[x][y]=hg.m_cells[x][y]; - } - this->m_patchMagnitude=hg.m_patchMagnitude; - this->m_patchSize=hg.m_patchSize; + if (this->m_xsize > 0 && this->m_ysize > 0) + { + // the Array2D m_cells is a std::shared_ptr[]>, where Cell is std::shared_ptr< Array2D > + this->m_cells = HCellArray2d(new HCellArray[this->m_xsize], [](auto ptr) { delete[] ptr; }); + for (int x = 0; x < this->m_xsize; x++) + { + this->m_cells[x] = HCellArray(new HCell[this->m_ysize]); + for (int y = 0; y < this->m_ysize; y++) + { + this->m_cells[x][y] = hg.m_cells[x][y]; + } + } + this->m_patchMagnitude = hg.m_patchMagnitude; + this->m_patchSize = hg.m_patchSize; + } + else + { + std::cerr << __func__ << "Invalid size: " << "m_xsize= " << this->m_xsize << " m_ysize= " << this->m_ysize << " - resetting " << std::endl; + this->m_xsize = this->m_ysize=0; + this->m_cells.reset(); + } } template void HierarchicalArray2D::resize(int xmin, int ymin, int xmax, int ymax){ int xsize=xmax-xmin; int ysize=ymax-ymin; + if (xsize <= 0 || ysize <= 0) + { + std::cerr << __func__ << "Invalid reset size: " << "xsize= " << xsize << " ysize= " << ysize << " - no-op " << std::endl; + return; + } HCellArray2d newcells=HCellArray2d(new HCellArray[xsize], [](auto ptr){ delete[] ptr; }); - for (int x=0; x::resize(int xmin, int ymin, int xmax, int ymax){ int dy= ymin < 0 ? 0 : ymin; int Dx=xmaxm_xsize?xmax:this->m_xsize; int Dy=ymaxm_ysize?ymax:this->m_ysize; - for (int x=dx; xm_cells[x][y]; } } @@ -107,9 +128,21 @@ HierarchicalArray2D& HierarchicalArray2D::operator=(const Hierarchic this->m_cells.reset(); this->m_xsize=hg.m_xsize; this->m_ysize=hg.m_ysize; - this->m_cells=HCellArray2d(new HCellArray[this->m_xsize], [](auto ptr){ delete[] ptr; }); - for (int i=0; im_xsize; i++) - this->m_cells[i]=HCellArray(new HCell[this->m_ysize]); + + if (this->m_xsize > 0 && this->m_ysize > 0) + { + this->m_cells = HCellArray2d(new HCellArray[this->m_xsize], [](auto ptr) { delete[] ptr; }); + for (int i = 0; i < this->m_xsize; i++) + { + this->m_cells[i] = HCellArray(new HCell[this->m_ysize]); + } + } + else + { + std::cerr << __func__ << "Invalid size: " << "m_xsize= " << this->m_xsize << " m_ysize= " << this->m_ysize << " - resetting " << std::endl; + this->m_xsize = this->m_ysize = 0; + this->m_cells.reset(); + } } for (int x=0; xm_xsize; x++) for (int y=0; ym_ysize; y++)