Generic interface for a sparse solver operating on a graph. More...
#include <solver.h>
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 | |
SparseOptimizer * | optimizer () 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 |
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.
size_t g2o::Solver::additionalVectorSpace | ( | ) | const [inline] |
double* g2o::Solver::b | ( | ) | [inline] |
const double* g2o::Solver::b | ( | ) | const [inline] |
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] |
SparseOptimizer* g2o::Solver::optimizer | ( | ) | const [inline] |
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 >.
void g2o::Solver::setAdditionalVectorSpace | ( | size_t | s | ) |
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.
void g2o::Solver::setOptimizer | ( | SparseOptimizer * | optimizer | ) |
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 >.
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] |
double* g2o::Solver::x | ( | ) | [inline] |
const double* g2o::Solver::x | ( | ) | const [inline] |
size_t g2o::Solver::_additionalVectorSpace [protected] |
double* g2o::Solver::_b [protected] |
bool g2o::Solver::_isLevenberg [protected] |
size_t g2o::Solver::_maxXSize [protected] |
SparseOptimizer* g2o::Solver::_optimizer [protected] |
double* g2o::Solver::_x [protected] |
size_t g2o::Solver::_xSize [protected] |