RainerKuemmerle / g2o

g2o: A General Framework for Graph Optimization

Geek Repo:Geek Repo

Github PK Tool:Github PK Tool

How to clear g2o optimizer after optimization to avoid memory leak

nkuwenjian opened this issue · comments

Hi, I have a following simple code, which is used to study the usage of g2o solver. This code works normally after compilation. However, when I use the tool of valgrind to check the code, I encounter the following error prompt about memory leak. So my question is how to properly clear g2o optimizer after optimization to avoid memory leak.

The version of g2o I used is the release version of 20200410.

The command of valgrind I used is valgrind --tool=memcheck --leak-check=full ./g2o_tutorial

Best,

Jian Wen

#include "g2o/core/block_solver.h"
#include "g2o/core/factory.h"
#include "g2o/core/optimization_algorithm_factory.h"
#include "g2o/core/optimization_algorithm_gauss_newton.h"
#include "g2o/solvers/cholmod/linear_solver_cholmod.h"
#include "g2o/types/slam3d/types_slam3d.h"

using BlockSolver = g2o::BlockSolver<g2o::BlockSolverTraits<-1, -1>>;
using LinearSolver = g2o::LinearSolverCholmod<BlockSolver::PoseMatrixType>;

int main() {
  // Initialize the SparseOptimizer
  g2o::SparseOptimizer optimizer;
  auto linear_solver = std::make_unique<LinearSolver>();
  linear_solver->setBlockOrdering(false);
  auto block_solver = std::make_unique<BlockSolver>(std::move(linear_solver));
  g2o::OptimizationAlgorithmGaussNewton* solver =
      new g2o::OptimizationAlgorithmGaussNewton(std::move(block_solver));
  optimizer.setAlgorithm(solver);

  // Add vertices
  g2o::VertexSE3* v0 = new g2o::VertexSE3();
  v0->setEstimate(
      Eigen::Transform<double, 3, 1>(Eigen::Translation<double, 3>(0, 0, 0)));
  v0->setId(0);
  optimizer.addVertex(v0);

  g2o::VertexSE3* v1 = new g2o::VertexSE3();
  v1->setEstimate(
      Eigen::Transform<double, 3, 1>(Eigen::Translation<double, 3>(0, 0, 0)));
  v1->setId(1);
  optimizer.addVertex(v1);

  g2o::VertexSE3* v2 = new g2o::VertexSE3();
  v2->setEstimate(
      Eigen::Transform<double, 3, 1>(Eigen::Translation<double, 3>(0, 0, 0)));
  v2->setId(2);
  optimizer.addVertex(v2);

  // Add edges
  g2o::EdgeSE3* e1 = new g2o::EdgeSE3();
  e1->vertices()[0] = optimizer.vertex(0);
  e1->vertices()[1] = optimizer.vertex(1);
  e1->setMeasurement(Eigen::Isometry3d(Eigen::Translation<double, 3>(1, 0, 0)));
  e1->setInformation(Eigen::Matrix<double, 6, 6>::Identity());
  optimizer.addEdge(e1);

  g2o::EdgeSE3* e2 = new g2o::EdgeSE3();
  e2->vertices()[0] = optimizer.vertex(1);
  e2->vertices()[1] = optimizer.vertex(2);
  e2->setMeasurement(Eigen::Isometry3d(Eigen::Translation<double, 3>(0, 1, 0)));
  e2->setInformation(Eigen::Matrix<double, 6, 6>::Identity());
  optimizer.addEdge(e2);

  g2o::EdgeSE3* e3 = new g2o::EdgeSE3();
  e3->vertices()[0] = optimizer.vertex(2);
  e3->vertices()[1] = optimizer.vertex(0);
  e3->setMeasurement(
      Eigen::Isometry3d(Eigen::Translation<double, 3>(-0.8, -0.7, 0.1)));
  e3->setInformation(Eigen::Matrix<double, 6, 6>::Identity());
  optimizer.addEdge(e3);

  v0->setFixed(true);

  optimizer.setVerbose(false);
  optimizer.initializeOptimization();
  int iter = optimizer.optimize(50);
  if (iter <= 0) {
    std::cout << "Optimization failed!" << std::endl;
  } else {
    std::cout << "Optimization finished after " << iter << " iterations."
              << std::endl;
  }

  optimizer.clear();

  return 0;
}
==139659== Memcheck, a memory error detector
==139659== Copyright (C) 2002-2017, and GNU GPL'd, by Julian Seward et al.
==139659== Using Valgrind-3.15.0 and LibVEX; rerun with -h for copyright info
==139659== Command: ./g2o_tutorial
==139659== 
Optimization finished after 50 iterations.
==139659== 
==139659== HEAP SUMMARY:
==139659==     in use at exit: 712 bytes in 23 blocks
==139659==   total heap usage: 1,028 allocs, 1,005 frees, 295,539 bytes allocated
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 2 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F0242: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 3 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F0379: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 4 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F04B0: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 5 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F05E7: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 6 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F071E: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 7 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F0855: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 8 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F098C: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 9 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F0AC3: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 10 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F0BFA: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 11 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F0D31: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 12 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F0E68: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 13 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F0F9F: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 14 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F10D6: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 15 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F120D: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 16 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F1344: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 17 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F147B: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 16 bytes in 1 blocks are definitely lost in loss record 18 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x488A567: g2o::Factory::registerType(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, g2o::AbstractHyperGraphElementCreator*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F15B2: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 120 bytes in 1 blocks are definitely lost in loss record 22 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x486C629: g2o::HyperGraphActionLibrary::registerAction(g2o::HyperGraphElementAction*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F160F: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== 120 bytes in 1 blocks are definitely lost in loss record 23 of 23
==139659==    at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==139659==    by 0x486C629: g2o::HyperGraphActionLibrary::registerAction(g2o::HyperGraphElementAction*) (in /usr/local/lib/libg2o_core.so)
==139659==    by 0x48F16ED: __static_initialization_and_destruction_0(int, int) [clone .constprop.955] (in /usr/local/lib/libg2o_types_slam3d.so)
==139659==    by 0x4011B99: call_init.part.0 (dl-init.c:72)
==139659==    by 0x4011CA0: call_init (dl-init.c:30)
==139659==    by 0x4011CA0: _dl_init (dl-init.c:119)
==139659==    by 0x4001139: ??? (in /usr/lib/x86_64-linux-gnu/ld-2.31.so)
==139659== 
==139659== LEAK SUMMARY:
==139659==    definitely lost: 512 bytes in 19 blocks
==139659==    indirectly lost: 0 bytes in 0 blocks
==139659==      possibly lost: 0 bytes in 0 blocks
==139659==    still reachable: 200 bytes in 4 blocks
==139659==         suppressed: 0 bytes in 0 blocks
==139659== Reachable blocks (those to which a pointer was found) are not shown.
==139659== To see them, rerun with: --leak-check=full --show-leak-kinds=all
==139659== 
==139659== For lists of detected and suppressed errors, rerun with: -s
==139659== ERROR SUMMARY: 19 errors from 19 contexts (suppressed: 0 from 0)

The "memory leak" originates from singletons which are not freed upon exit. The amount of bytes lost is independent of the optimization problem, its size or how often you run it.
Fixing this would require to change the singleton pattern implementation to correctly free its data.

Fixed by #472 see also #148

Thank you. I use the release version of 20230223 instead of 20200410, and the problem is solved.