Skip to content

Commit 41447e0

Browse files
committed
add checks for size prior to new, include cerr
1 parent cf7e1b4 commit 41447e0

File tree

2 files changed

+114
-40
lines changed

2 files changed

+114
-40
lines changed

include/gmapping/grid/array2d.h

Lines changed: 65 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -54,16 +54,22 @@ Array2D<Cell,debug>::Array2D(int xsize, int ysize){
5454
}
5555
m_xsize=xsize;
5656
m_ysize=ysize;
57-
if (m_xsize>0 && m_ysize>0){
57+
if (m_xsize>0 && m_ysize>0)
58+
{
5859
m_cells=CellArray2d(new CellArray[m_xsize], [](auto ptr){ delete[] ptr; });
5960
for (int i=0; i<m_xsize; i++)
61+
{
6062
m_cells[i]=CellArray(new Cell[m_ysize], [](auto ptr){ delete[] ptr; });
63+
}
6164
}
62-
else{
65+
else
66+
{
67+
std::cerr << __func__ << "Invalid size: " << "m_xsize= " << m_xsize << " m_ysize= " << m_ysize << " - resetting " << std::endl;
6368
m_xsize=m_ysize=0;
64-
m_cells=0;
69+
m_cells.reset();
6570
}
66-
if (debug){
71+
if (debug)
72+
{
6773
std::cerr << __func__ << std::endl;
6874
std::cerr << "m_xsize= " << m_xsize<< std::endl;
6975
std::cerr << "m_ysize= " << m_ysize<< std::endl;
@@ -72,23 +78,40 @@ Array2D<Cell,debug>::Array2D(int xsize, int ysize){
7278

7379
template <class Cell, const bool debug>
7480
Array2D<Cell,debug> & Array2D<Cell,debug>::operator=(const Array2D<Cell,debug> & g){
75-
if (debug || m_xsize!=g.m_xsize || m_ysize!=g.m_ysize){
81+
if (debug || m_xsize!=g.m_xsize || m_ysize!=g.m_ysize)
82+
{
7683
// delete memory
7784
if (m_cells)
7885
{
7986
m_cells.reset();
8087
}
8188
m_xsize=g.m_xsize;
8289
m_ysize=g.m_ysize;
83-
m_cells=CellArray2d(new CellArray[m_xsize], [](auto ptr){ delete[] ptr; });
84-
for (int i=0; i<m_xsize; i++)
85-
m_cells[i]=CellArray(new Cell[m_ysize], [](auto ptr){ delete[] ptr; });
90+
if (m_xsize > 0 && m_ysize > 0)
91+
{
92+
m_cells = CellArray2d(new CellArray[m_xsize], [](auto ptr) { delete[] ptr; });
93+
for (int i = 0; i < m_xsize; i++)
94+
{
95+
m_cells[i] = CellArray(new Cell[m_ysize], [](auto ptr) { delete[] ptr; });
96+
}
97+
}
98+
else
99+
{
100+
std::cerr << __func__ << "Invalid size: " << "m_xsize= " << m_xsize << " m_ysize= " << m_ysize << " - resetting " << std::endl;
101+
m_xsize = m_ysize = 0;
102+
m_cells.reset();
103+
}
86104
}
87105
for (int x=0; x<m_xsize; x++)
88-
for (int y=0; y<m_ysize; y++)
89-
m_cells[x][y]=g.m_cells[x][y];
106+
{
107+
for (int y = 0; y < m_ysize; y++)
108+
{
109+
m_cells[x][y] = g.m_cells[x][y];
110+
}
111+
}
90112

91-
if (debug){
113+
if (debug)
114+
{
92115
std::cerr << __func__ << std::endl;
93116
std::cerr << "m_xsize= " << m_xsize<< std::endl;
94117
std::cerr << "m_ysize= " << m_ysize<< std::endl;
@@ -97,20 +120,33 @@ Array2D<Cell,debug> & Array2D<Cell,debug>::operator=(const Array2D<Cell,debug> &
97120
}
98121

99122
template <class Cell, const bool debug>
100-
Array2D<Cell,debug>::Array2D(const Array2D<Cell,debug> & g){
123+
Array2D<Cell,debug>::Array2D(const Array2D<Cell,debug> & g)
124+
{
101125
// delete memory
102126
if (m_cells)
103127
{
104128
m_cells.reset();
105129
}
106130
m_xsize=g.m_xsize;
107131
m_ysize=g.m_ysize;
108-
m_cells=CellArray2d(new CellArray[m_xsize], [](auto ptr){ delete[] ptr; });
109-
for (int x=0; x<m_xsize; x++){
110-
m_cells[x]=CellArray(new Cell[m_ysize], [](auto ptr){ delete[] ptr; });
111-
for (int y=0; y<m_ysize; y++)
112-
m_cells[x][y]=g.m_cells[x][y];
113-
}
132+
if (m_xsize > 0 && m_ysize > 0)
133+
{
134+
m_cells = CellArray2d(new CellArray[m_xsize], [](auto ptr) { delete[] ptr; });
135+
for (int x = 0; x < m_xsize; x++)
136+
{
137+
m_cells[x] = CellArray(new Cell[m_ysize], [](auto ptr) { delete[] ptr; });
138+
for (int y = 0; y < m_ysize; y++)
139+
{
140+
m_cells[x][y] = g.m_cells[x][y];
141+
}
142+
}
143+
}
144+
else
145+
{
146+
std::cerr << __func__ << "Invalid size: " << "m_xsize= " << m_xsize << " m_ysize= " << m_ysize << " - resetting " << std::endl;
147+
m_xsize=m_ysize=0;
148+
m_cells.reset();
149+
}
114150
if (debug){
115151
std::cerr << __func__ << std::endl;
116152
std::cerr << "m_xsize= " << m_xsize<< std::endl;
@@ -122,8 +158,8 @@ template <class Cell, const bool debug>
122158
Array2D<Cell,debug>::~Array2D(){
123159
if (debug){
124160
std::cerr << __func__ << std::endl;
125-
std::cerr << "m_xsize= " << m_xsize<< std::endl;
126-
std::cerr << "m_ysize= " << m_ysize<< std::endl;
161+
std::cerr << "m_xsize= " << m_xsize<< std::endl;
162+
std::cerr << "m_ysize= " << m_ysize<< std::endl;
127163
}
128164
// delete memory
129165
if (m_cells)
@@ -136,8 +172,8 @@ template <class Cell, const bool debug>
136172
void Array2D<Cell,debug>::clear(){
137173
if (debug){
138174
std::cerr << __func__ << std::endl;
139-
std::cerr << "m_xsize= " << m_xsize<< std::endl;
140-
std::cerr << "m_ysize= " << m_ysize<< std::endl;
175+
std::cerr << "m_xsize= " << m_xsize<< std::endl;
176+
std::cerr << "m_ysize= " << m_ysize<< std::endl;
141177
}
142178
// delete memory
143179
if (m_cells)
@@ -151,8 +187,13 @@ void Array2D<Cell,debug>::clear(){
151187

152188
template <class Cell, const bool debug>
153189
void Array2D<Cell,debug>::resize(int xmin, int ymin, int xmax, int ymax){
154-
int xsize=xmax-xmin;
155-
int ysize=ymax-ymin;
190+
int xsize = xmax-xmin;
191+
int ysize = ymax-ymin;
192+
if (xsize <= 0 || ysize <= 0)
193+
{
194+
std::cerr << __func__ << "Invalid reset size: " << "xsize= " << xsize << " ysize= " << ysize << " - no-op " << std::endl;
195+
return;
196+
}
156197
CellArray2d newcells=CellArray2d(new CellArray[xsize], [](auto ptr){ delete[] ptr; });
157198
for (int x=0; x<xsize; x++){
158199
newcells[x]=CellArray(new Cell[ysize], [](auto ptr){ delete[] ptr; });;

include/gmapping/grid/harray2d.h

Lines changed: 49 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -64,34 +64,55 @@ HierarchicalArray2D<Cell>::HierarchicalArray2D(const HierarchicalArray2D& hg)
6464
{
6565
this->m_cells.reset();
6666
}
67-
// the Array2D m_cells is a std::shared_ptr<std::shared_ptr<Cell[]>[]>, where Cell is std::shared_ptr< Array2D<Cell> >
68-
this->m_cells=HCellArray2d(new HCellArray[this->m_xsize], [](auto ptr){ delete[] ptr; });
69-
for (int x=0; x<this->m_xsize; x++){
70-
this->m_cells[x]=HCellArray(new HCell[this->m_ysize]);
71-
for (int y=0; y<this->m_ysize; y++)
72-
this->m_cells[x][y]=hg.m_cells[x][y];
73-
}
74-
this->m_patchMagnitude=hg.m_patchMagnitude;
75-
this->m_patchSize=hg.m_patchSize;
67+
if (this->m_xsize > 0 && this->m_ysize > 0)
68+
{
69+
// the Array2D m_cells is a std::shared_ptr<std::shared_ptr<Cell[]>[]>, where Cell is std::shared_ptr< Array2D<Cell> >
70+
this->m_cells = HCellArray2d(new HCellArray[this->m_xsize], [](auto ptr) { delete[] ptr; });
71+
for (int x = 0; x < this->m_xsize; x++)
72+
{
73+
this->m_cells[x] = HCellArray(new HCell[this->m_ysize]);
74+
for (int y = 0; y < this->m_ysize; y++)
75+
{
76+
this->m_cells[x][y] = hg.m_cells[x][y];
77+
}
78+
}
79+
this->m_patchMagnitude = hg.m_patchMagnitude;
80+
this->m_patchSize = hg.m_patchSize;
81+
}
82+
else
83+
{
84+
std::cerr << __func__ << "Invalid size: " << "m_xsize= " << this->m_xsize << " m_ysize= " << this->m_ysize << " - resetting " << std::endl;
85+
this->m_xsize = this->m_ysize=0;
86+
this->m_cells.reset();
87+
}
7688
}
7789

7890
template <class Cell>
7991
void HierarchicalArray2D<Cell>::resize(int xmin, int ymin, int xmax, int ymax){
8092
int xsize=xmax-xmin;
8193
int ysize=ymax-ymin;
94+
if (xsize <= 0 || ysize <= 0)
95+
{
96+
std::cerr << __func__ << "Invalid reset size: " << "xsize= " << xsize << " ysize= " << ysize << " - no-op " << std::endl;
97+
return;
98+
}
8299
HCellArray2d newcells=HCellArray2d(new HCellArray[xsize], [](auto ptr){ delete[] ptr; });
83-
for (int x=0; x<xsize; x++){
100+
for (int x=0; x<xsize; x++)
101+
{
84102
newcells[x]=HCellArray(new HCell[ysize], [](auto ptr){ delete[] ptr; });
85-
for (int y=0; y<ysize; y++){
103+
for (int y=0; y<ysize; y++)
104+
{
86105
newcells[x][y]=HCell();
87106
}
88107
}
89108
int dx= xmin < 0 ? 0 : xmin;
90109
int dy= ymin < 0 ? 0 : ymin;
91110
int Dx=xmax<this->m_xsize?xmax:this->m_xsize;
92111
int Dy=ymax<this->m_ysize?ymax:this->m_ysize;
93-
for (int x=dx; x<Dx; x++){
94-
for (int y=dy; y<Dy; y++){
112+
for (int x=dx; x<Dx; x++)
113+
{
114+
for (int y=dy; y<Dy; y++)
115+
{
95116
newcells[x-xmin][y-ymin]=this->m_cells[x][y];
96117
}
97118
}
@@ -107,9 +128,21 @@ HierarchicalArray2D<Cell>& HierarchicalArray2D<Cell>::operator=(const Hierarchic
107128
this->m_cells.reset();
108129
this->m_xsize=hg.m_xsize;
109130
this->m_ysize=hg.m_ysize;
110-
this->m_cells=HCellArray2d(new HCellArray[this->m_xsize], [](auto ptr){ delete[] ptr; });
111-
for (int i=0; i<this->m_xsize; i++)
112-
this->m_cells[i]=HCellArray(new HCell[this->m_ysize]);
131+
132+
if (this->m_xsize > 0 && this->m_ysize > 0)
133+
{
134+
this->m_cells = HCellArray2d(new HCellArray[this->m_xsize], [](auto ptr) { delete[] ptr; });
135+
for (int i = 0; i < this->m_xsize; i++)
136+
{
137+
this->m_cells[i] = HCellArray(new HCell[this->m_ysize]);
138+
}
139+
}
140+
else
141+
{
142+
std::cerr << __func__ << "Invalid size: " << "m_xsize= " << this->m_xsize << " m_ysize= " << this->m_ysize << " - resetting " << std::endl;
143+
this->m_xsize = this->m_ysize = 0;
144+
this->m_cells.reset();
145+
}
113146
}
114147
for (int x=0; x<this->m_xsize; x++)
115148
for (int y=0; y<this->m_ysize; y++)

0 commit comments

Comments
 (0)