Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | List of all members
g2o::Solver Class Referenceabstract

Generic interface for a sparse solver operating on a graph which solves one iteration of the linearized objective function. More...

#include <solver.h>

Inheritance diagram for g2o::Solver:
Inheritance graph
[legend]

Public Member Functions

size_t additionalVectorSpace () const
 
double * b ()
 return b, the right hand side of the system More...
 
const double * b () const
 
virtual bool buildStructure (bool zeroBlocks=false)=0
 
virtual bool buildSystem ()=0
 
virtual bool computeMarginals (SparseBlockMatrix< MatrixXd > &spinv, const std::vector< std::pair< int, int > > &blockIndices)=0
 
virtual bool init (SparseOptimizer *optimizer, bool online=false)=0
 
bool levenberg () const
 the system is Levenberg-Marquardt More...
 
SparseOptimizeroptimizer () const
 the optimizer (graph) on which the solver works More...
 
virtual void restoreDiagonal ()=0
 
virtual bool saveHessian (const std::string &) const =0
 write the hessian to disk using the specified file name More...
 
virtual bool schur ()=0
 should the solver perform the schur complement or not More...
 
void setAdditionalVectorSpace (size_t s)
 
virtual bool setLambda (double lambda, bool backup=false)=0
 
void setLevenberg (bool levenberg)
 
void setOptimizer (SparseOptimizer *optimizer)
 
virtual void setSchur (bool s)=0
 
virtual void setWriteDebug (bool)=0
 
virtual bool solve ()=0
 
 Solver ()
 
virtual bool supportsSchur ()
 
virtual bool updateStructure (const std::vector< HyperGraph::Vertex * > &vset, const HyperGraph::EdgeSet &edges)=0
 
size_t vectorSize () const
 return the size of the solution vector (x) and b More...
 
virtual bool writeDebug () const =0
 
double * x ()
 return x, the solution vector More...
 
const double * x () const
 
virtual ~Solver ()
 

Protected Member Functions

void resizeVector (size_t sx)
 

Protected Attributes

size_t _additionalVectorSpace
 
double * _b
 
bool _isLevenberg
 the system we gonna solve is a Levenberg-Marquardt system More...
 
size_t _maxXSize
 
SparseOptimizer_optimizer
 
double * _x
 
size_t _xSize
 

Private Member Functions

Solveroperator= (const Solver &)
 
 Solver (const Solver &)
 

Detailed Description

Generic interface for a sparse solver operating on a graph which solves one iteration of the linearized objective function.

Definition at line 43 of file solver.h.

Constructor & Destructor Documentation

g2o::Solver::Solver ( )

Definition at line 34 of file solver.cpp.

g2o::Solver::~Solver ( )
virtual

Definition at line 40 of file solver.cpp.

g2o::Solver::Solver ( const Solver )
inlineprivate

Definition at line 146 of file solver.h.

Member Function Documentation

size_t g2o::Solver::additionalVectorSpace ( ) const
inline

Definition at line 122 of file solver.h.

double* g2o::Solver::b ( )
inline

return b, the right hand side of the system

Definition at line 98 of file solver.h.

const double* g2o::Solver::b ( ) const
inline

Definition at line 99 of file solver.h.

virtual bool g2o::Solver::buildStructure ( bool  zeroBlocks = false)
pure virtual

build the structure of the system

Implemented in g2o::BlockSolver< Traits >.

virtual bool g2o::Solver::buildSystem ( )
pure virtual

build the current system

Implemented in g2o::BlockSolver< Traits >.

virtual bool g2o::Solver::computeMarginals ( SparseBlockMatrix< MatrixXd > &  spinv,
const std::vector< std::pair< int, int > > &  blockIndices 
)
pure virtual

computes the block diagonal elements of the pattern specified in the input and stores them in given SparseBlockMatrix

Implemented in g2o::BlockSolver< Traits >.

virtual bool g2o::Solver::init ( SparseOptimizer optimizer,
bool  online = false 
)
pure virtual

initialize the solver, called once before the first iteration

Implemented in g2o::BlockSolver< Traits >.

bool g2o::Solver::levenberg ( ) const
inline

the system is Levenberg-Marquardt

Definition at line 109 of file solver.h.

Solver& g2o::Solver::operator= ( const Solver )
inlineprivate

Definition at line 147 of file solver.h.

SparseOptimizer* g2o::Solver::optimizer ( ) const
inline

the optimizer (graph) on which the solver works

Definition at line 105 of file solver.h.

void g2o::Solver::resizeVector ( size_t  sx)
protected

Definition at line 46 of file solver.cpp.

virtual void g2o::Solver::restoreDiagonal ( )
pure virtual

restore a previosly made backup of the diagonal

Implemented in g2o::BlockSolver< Traits >.

virtual bool g2o::Solver::saveHessian ( const std::string &  ) const
pure virtual

write the hessian to disk using the specified file name

Implemented in g2o::BlockSolver< Traits >.

virtual bool g2o::Solver::schur ( )
pure virtual

should the solver perform the schur complement or not

Implemented in g2o::BlockSolver< Traits >.

void g2o::Solver::setAdditionalVectorSpace ( size_t  s)

Definition at line 82 of file solver.cpp.

virtual bool g2o::Solver::setLambda ( double  lambda,
bool  backup = false 
)
pure virtual

update the system while performing Levenberg, i.e., modifying the diagonal components of A by doing += lambda along the main diagonal of the Matrix. Note that this function may be called with a positive and a negative lambda. The latter is used to undo a former modification. If backup is true, then the solver should store a backup of the diagonal, which can be restored by restoreDiagonal()

Implemented in g2o::BlockSolver< Traits >.

void g2o::Solver::setLevenberg ( bool  levenberg)

Definition at line 77 of file solver.cpp.

void g2o::Solver::setOptimizer ( SparseOptimizer optimizer)

Definition at line 72 of file solver.cpp.

virtual void g2o::Solver::setSchur ( bool  s)
pure virtual

Implemented in g2o::BlockSolver< Traits >.

virtual void g2o::Solver::setWriteDebug ( bool  )
pure virtual

write debug output of the Hessian if system is not positive definite

Implemented in g2o::BlockSolver< Traits >.

virtual bool g2o::Solver::solve ( )
pure virtual

solve Ax = b

Implemented in g2o::BlockSolver< Traits >.

virtual bool g2o::Solver::supportsSchur ( )
inlinevirtual

does this solver support the Schur complement for solving a system consisting of poses and landmarks. Re-implemement in a derived solver, if your solver supports it.

Reimplemented in g2o::BlockSolver< Traits >.

Definition at line 116 of file solver.h.

virtual bool g2o::Solver::updateStructure ( const std::vector< HyperGraph::Vertex * > &  vset,
const HyperGraph::EdgeSet edges 
)
pure virtual

update the structures for online processing

Implemented in g2o::BlockSolver< Traits >.

size_t g2o::Solver::vectorSize ( ) const
inline

return the size of the solution vector (x) and b

Definition at line 102 of file solver.h.

virtual bool g2o::Solver::writeDebug ( ) const
pure virtual

Implemented in g2o::BlockSolver< Traits >.

double* g2o::Solver::x ( )
inline

return x, the solution vector

Definition at line 95 of file solver.h.

const double* g2o::Solver::x ( ) const
inline

Definition at line 96 of file solver.h.

Member Data Documentation

size_t g2o::Solver::_additionalVectorSpace
protected

Definition at line 140 of file solver.h.

double* g2o::Solver::_b
protected

Definition at line 137 of file solver.h.

bool g2o::Solver::_isLevenberg
protected

the system we gonna solve is a Levenberg-Marquardt system

Definition at line 139 of file solver.h.

size_t g2o::Solver::_maxXSize
protected

Definition at line 138 of file solver.h.

SparseOptimizer* g2o::Solver::_optimizer
protected

Definition at line 135 of file solver.h.

double* g2o::Solver::_x
protected

Definition at line 136 of file solver.h.

size_t g2o::Solver::_xSize
protected

Definition at line 138 of file solver.h.


The documentation for this class was generated from the following files:


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:06