base for the block solvers with some basic function interfaces More...
#include <block_solver.h>

Public Member Functions | |
| virtual void | multiplyHessian (double *dest, const double *src) const =0 |
| virtual | ~BlockSolverBase () |
Public Member Functions inherited from g2o::Solver | |
| 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... | |
| SparseOptimizer * | optimizer () 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 () |
Additional Inherited Members | |
Protected Member Functions inherited from g2o::Solver | |
| void | resizeVector (size_t sx) |
Protected Attributes inherited from g2o::Solver | |
| 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 |
base for the block solvers with some basic function interfaces
Definition at line 83 of file block_solver.h.
|
inlinevirtual |
Definition at line 86 of file block_solver.h.
|
pure virtual |
compute dest = H * src
Implemented in g2o::BlockSolver< Traits >.