Public Member Functions | Protected Member Functions | Protected Attributes
g2o::Solver Class Reference

Generic interface for a sparse solver operating on a graph. More...

#include <solver.h>

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

List of all members.

Public Member Functions

size_t additionalVectorSpace () const
double * b ()
 return b, the right hand side of the system
const double * b () const
virtual bool buildStructure (bool zeroBlocks=false)=0
virtual bool buildSystem ()=0
virtual bool computeMarginals ()=0
virtual bool computeMarginals (SparseBlockMatrix< MatrixXd > &spinv, const std::vector< std::pair< int, int > > &blockIndices)=0
virtual bool init (bool online=false)=0
bool levenberg () const
 the system is Levenberg-Marquardt
SparseOptimizeroptimizer () const
 the optimizer (graph) on which the solver works
virtual bool schur ()=0
 should the solver perform the schur complement or not
void setAdditionalVectorSpace (size_t s)
virtual bool setLambda (double lambda)=0
void setLevenberg (bool levenberg)
void setOptimizer (SparseOptimizer *optimizer)
virtual void setSchur (bool s)=0
virtual bool solve ()=0
 Solver (SparseOptimizer *optimizer)
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
double * x ()
 return x, the solution vector
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
size_t _maxXSize
SparseOptimizer_optimizer
double * _x
size_t _xSize

Detailed Description

Generic interface for a sparse solver operating on a graph.

Definition at line 33 of file solver.h.


Constructor & Destructor Documentation

g2o::Solver::Solver ( SparseOptimizer optimizer) [explicit]

Definition at line 24 of file solver.cpp.

g2o::Solver::~Solver ( ) [virtual]

Definition at line 30 of file solver.cpp.


Member Function Documentation

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

Definition at line 111 of file solver.h.

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

return b, the right hand side of the system

Definition at line 87 of file solver.h.

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

Definition at line 88 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 ( ) [pure virtual]

computes the block diagonal elements of the inverted hessian and stores them in the nodes of the graph.

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 the nodes of the graph.

Implemented in g2o::BlockSolver< Traits >.

virtual bool g2o::Solver::init ( 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 98 of file solver.h.

the optimizer (graph) on which the solver works

Definition at line 94 of file solver.h.

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

Definition at line 36 of file solver.cpp.

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

should the solver perform the schur complement or not

Implemented in g2o::BlockSolver< Traits >.

Definition at line 72 of file solver.cpp.

virtual bool g2o::Solver::setLambda ( double  lambda) [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.

Implemented in g2o::BlockSolver< Traits >.

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

Definition at line 67 of file solver.cpp.

Definition at line 62 of file solver.cpp.

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

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 ( ) [inline, virtual]

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 105 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 91 of file solver.h.

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

return x, the solution vector

Definition at line 84 of file solver.h.

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

Definition at line 85 of file solver.h.


Member Data Documentation

Definition at line 120 of file solver.h.

double* g2o::Solver::_b [protected]

Definition at line 117 of file solver.h.

the system we gonna solve is a Levenberg-Marquardt system

Definition at line 119 of file solver.h.

size_t g2o::Solver::_maxXSize [protected]

Definition at line 118 of file solver.h.

Definition at line 115 of file solver.h.

double* g2o::Solver::_x [protected]

Definition at line 116 of file solver.h.

size_t g2o::Solver::_xSize [protected]

Definition at line 118 of file solver.h.


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


re_vision
Author(s): Dorian Galvez-Lopez
autogenerated on Sun Jan 5 2014 11:34:30