Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Issue 42 - changes for slow memory leak #43

Open
wants to merge 3 commits into
base: melodic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,9 +1,11 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.0.2)
project(openslam_gmapping)

## Find catkin macros and libraries
find_package(catkin REQUIRED)

add_compile_options(-std=c++17)

include(GenerateExportHeader)
set(EXPORT_HEADER_DIR "${CATKIN_DEVEL_PREFIX}/include")
file(MAKE_DIRECTORY "${EXPORT_HEADER_DIR}")
Expand Down
26 changes: 26 additions & 0 deletions LICENSE
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
Copyright (c) 2019 Cyrill Stachniss, Udo Frese, Giorgio Grisetti, Wolfram Burgard
All rights reserved.

Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:

* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
* Neither the name of the Willow Garage, Inc. nor the names of its
contributors may be used to endorse or promote products derived from
this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
7 changes: 1 addition & 6 deletions gridfastslam/gfs2log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,11 @@ using namespace GMapping::GFSReader;

int main (int argc, const char * const * argv){
if (argc<3){
cout << "usage gfs2log [-err] [-neff] [-part] [-odom] <infilename> <outfilename>" << endl;
cout << "usage gfs2log [-err] [-part] [-odom] <infilename> <outfilename>" << endl;
cout << " -odom : dump raw odometry in ODOM message instead of inpolated corrected one" << endl;
return -1;
}
bool err=0;
bool neff=0;
bool part=0;
bool odom=0;
// int particle_num;
Expand All @@ -29,10 +28,6 @@ int main (int argc, const char * const * argv){
err=true;
c++;
}
if (!strcmp(argv[c],"-neff")){
neff=true;
c++;
}
if (!strcmp(argv[c],"-part")){
part=true;
c++;
Expand Down
5 changes: 0 additions & 5 deletions gridfastslam/gfs2rec.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -375,16 +375,11 @@ int main (int argc, const char * const * argv){
return -1;
}
bool err=0;
bool neff=0;
unsigned int c=1;
if (!strcmp(argv[c],"-err")){
err=true;
c++;
}
if (!strcmp(argv[c],"-neff")){
neff=true;
c++;
}
ifstream is(argv[c]);
if (!is){
cout << "could read file "<< endl;
Expand Down
7 changes: 4 additions & 3 deletions gridfastslam/gridslamprocessor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -409,8 +409,8 @@ void GridSlamProcessor::setMotionModelParameters
}
m_infoStream << "m_count " << m_count << endl;

RangeReading* reading_copy =
new RangeReading(reading.size(),
std::shared_ptr<RangeReading> reading_copy =
std::make_shared<RangeReading>(reading.size(),
&(reading[0]),
static_cast<const RangeSensor*>(reading.getSensor()),
reading.getTime());
Expand Down Expand Up @@ -466,7 +466,8 @@ void GridSlamProcessor::setMotionModelParameters
updateTreeWeights(false);
// cerr << ".done!" <<endl;

delete [] plainReading;
delete[] plainReading;
plainReading=0;
m_lastPartPose=m_odoPose; //update the past pose for the next iteration
m_linearDistance=0;
m_angularDistance=0;
Expand Down
148 changes: 100 additions & 48 deletions include/gmapping/grid/array2d.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#ifndef ARRAY2D_H
#define ARRAY2D_H

#include <memory>
#include <assert.h>
#include <gmapping/utils/point.h>
#include "gmapping/grid/accessstate.h"
Expand All @@ -11,6 +12,8 @@ namespace GMapping {

template<class Cell, const bool debug=false> class Array2D{
public:
using CellArray = std::shared_ptr<Cell[]>;
using CellArray2d = std::shared_ptr<CellArray[]>;
Array2D(int xsize=0, int ysize=0);
Array2D& operator=(const Array2D &);
Array2D(const Array2D<Cell,debug> &);
Expand All @@ -33,29 +36,40 @@ template<class Cell, const bool debug=false> class Array2D{
inline int getPatchMagnitude() const{return 0;}
inline int getXSize() const {return m_xsize;}
inline int getYSize() const {return m_ysize;}
inline Cell** cells() {return m_cells;}
Cell ** m_cells;
inline CellArray2d cells() {return m_cells;}
CellArray2d m_cells;
protected:
int m_xsize, m_ysize;
int m_xsize = 0, m_ysize = 0;
};


template <class Cell, const bool debug>
Array2D<Cell,debug>::Array2D(int xsize, int ysize){
// assert(xsize>0);
// assert(ysize>0);
m_xsize=xsize;
m_ysize=ysize;
if (m_xsize>0 && m_ysize>0){
m_cells=new Cell*[m_xsize];
// delete memory
if (m_cells)
{
m_cells.reset();
}
m_xsize=xsize;
m_ysize=ysize;
if (m_xsize>0 && m_ysize>0)
{
m_cells=CellArray2d(new CellArray[m_xsize], [](auto ptr){ delete[] ptr; });
for (int i=0; i<m_xsize; i++)
m_cells[i]=new Cell[m_ysize];
{
m_cells[i]=CellArray(new Cell[m_ysize], [](auto ptr){ delete[] ptr; });
}
}
else{
else
{
std::cerr << __func__ << "Invalid size: " << "m_xsize= " << m_xsize << " m_ysize= " << m_ysize << " - resetting " << std::endl;
m_xsize=m_ysize=0;
m_cells=0;
m_cells.reset();
}
if (debug){
if (debug)
{
std::cerr << __func__ << std::endl;
std::cerr << "m_xsize= " << m_xsize<< std::endl;
std::cerr << "m_ysize= " << m_ysize<< std::endl;
Expand All @@ -64,21 +78,40 @@ Array2D<Cell,debug>::Array2D(int xsize, int ysize){

template <class Cell, const bool debug>
Array2D<Cell,debug> & Array2D<Cell,debug>::operator=(const Array2D<Cell,debug> & g){
if (debug || m_xsize!=g.m_xsize || m_ysize!=g.m_ysize){
for (int i=0; i<m_xsize; i++)
delete [] m_cells[i];
delete [] m_cells;
if (debug || m_xsize!=g.m_xsize || m_ysize!=g.m_ysize)
{
// delete memory
if (m_cells)
{
m_cells.reset();
}
m_xsize=g.m_xsize;
m_ysize=g.m_ysize;
m_cells=new Cell*[m_xsize];
for (int i=0; i<m_xsize; i++)
m_cells[i]=new Cell[m_ysize];
if (m_xsize > 0 && m_ysize > 0)
{
m_cells = CellArray2d(new CellArray[m_xsize], [](auto ptr) { delete[] ptr; });
for (int i = 0; i < m_xsize; i++)
{
m_cells[i] = CellArray(new Cell[m_ysize], [](auto ptr) { delete[] ptr; });
}
}
else
{
std::cerr << __func__ << "Invalid size: " << "m_xsize= " << m_xsize << " m_ysize= " << m_ysize << " - resetting " << std::endl;
m_xsize = m_ysize = 0;
m_cells.reset();
}
}
for (int x=0; x<m_xsize; x++)
for (int y=0; y<m_ysize; y++)
m_cells[x][y]=g.m_cells[x][y];
{
for (int y = 0; y < m_ysize; y++)
{
m_cells[x][y] = g.m_cells[x][y];
}
}

if (debug){
if (debug)
{
std::cerr << __func__ << std::endl;
std::cerr << "m_xsize= " << m_xsize<< std::endl;
std::cerr << "m_ysize= " << m_ysize<< std::endl;
Expand All @@ -87,15 +120,33 @@ Array2D<Cell,debug> & Array2D<Cell,debug>::operator=(const Array2D<Cell,debug> &
}

template <class Cell, const bool debug>
Array2D<Cell,debug>::Array2D(const Array2D<Cell,debug> & g){
Array2D<Cell,debug>::Array2D(const Array2D<Cell,debug> & g)
{
// delete memory
if (m_cells)
{
m_cells.reset();
}
m_xsize=g.m_xsize;
m_ysize=g.m_ysize;
m_cells=new Cell*[m_xsize];
for (int x=0; x<m_xsize; x++){
m_cells[x]=new Cell[m_ysize];
for (int y=0; y<m_ysize; y++)
m_cells[x][y]=g.m_cells[x][y];
}
if (m_xsize > 0 && m_ysize > 0)
{
m_cells = CellArray2d(new CellArray[m_xsize], [](auto ptr) { delete[] ptr; });
for (int x = 0; x < m_xsize; x++)
{
m_cells[x] = CellArray(new Cell[m_ysize], [](auto ptr) { delete[] ptr; });
for (int y = 0; y < m_ysize; y++)
{
m_cells[x][y] = g.m_cells[x][y];
}
}
}
else
{
std::cerr << __func__ << "Invalid size: " << "m_xsize= " << m_xsize << " m_ysize= " << m_ysize << " - resetting " << std::endl;
m_xsize=m_ysize=0;
m_cells.reset();
}
if (debug){
std::cerr << __func__ << std::endl;
std::cerr << "m_xsize= " << m_xsize<< std::endl;
Expand All @@ -107,42 +158,45 @@ template <class Cell, const bool debug>
Array2D<Cell,debug>::~Array2D(){
if (debug){
std::cerr << __func__ << std::endl;
std::cerr << "m_xsize= " << m_xsize<< std::endl;
std::cerr << "m_ysize= " << m_ysize<< std::endl;
std::cerr << "m_xsize= " << m_xsize<< std::endl;
std::cerr << "m_ysize= " << m_ysize<< std::endl;
}
for (int i=0; i<m_xsize; i++){
delete [] m_cells[i];
m_cells[i]=0;
// delete memory
if (m_cells)
{
m_cells.reset();
}
delete [] m_cells;
m_cells=0;
}

template <class Cell, const bool debug>
void Array2D<Cell,debug>::clear(){
if (debug){
std::cerr << __func__ << std::endl;
std::cerr << "m_xsize= " << m_xsize<< std::endl;
std::cerr << "m_ysize= " << m_ysize<< std::endl;
std::cerr << "m_xsize= " << m_xsize<< std::endl;
std::cerr << "m_ysize= " << m_ysize<< std::endl;
}
for (int i=0; i<m_xsize; i++){
delete [] m_cells[i];
m_cells[i]=0;
// delete memory
if (m_cells)
{
m_cells.reset();
}
delete [] m_cells;
m_cells=0;
m_xsize=0;
m_ysize=0;
}


template <class Cell, const bool debug>
void Array2D<Cell,debug>::resize(int xmin, int ymin, int xmax, int ymax){
int xsize=xmax-xmin;
int ysize=ymax-ymin;
Cell ** newcells=new Cell *[xsize];
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;
}
CellArray2d newcells=CellArray2d(new CellArray[xsize], [](auto ptr){ delete[] ptr; });
for (int x=0; x<xsize; x++){
newcells[x]=new Cell[ysize];
newcells[x]=CellArray(new Cell[ysize], [](auto ptr){ delete[] ptr; });;
}
int dx= xmin < 0 ? 0 : xmin;
int dy= ymin < 0 ? 0 : ymin;
Expand All @@ -152,9 +206,7 @@ void Array2D<Cell,debug>::resize(int xmin, int ymin, int xmax, int ymax){
for (int y=dy; y<Dy; y++){
newcells[x-xmin][y-ymin]=this->m_cells[x][y];
}
delete [] this->m_cells[x];
}
delete [] this->m_cells;
this->m_cells=newcells;
this->m_xsize=xsize;
this->m_ysize=ysize;
Expand Down
Loading