Public Types | Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes
g2o::BlockSolver< Traits > Class Template Reference

Implementation of a solver operating on the blocks of the Hessian. More...

#include <block_solver.h>

Inheritance diagram for g2o::BlockSolver< Traits >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef Traits::LandmarkHessianType LandmarkHessianType
typedef Traits::LandmarkMatrixType LandmarkMatrixType
typedef Traits::LandmarkVectorType LandmarkVectorType
typedef Traits::LinearSolverType LinearSolverType
typedef Traits::PoseHessianType PoseHessianType
typedef
Traits::PoseLandmarkHessianType 
PoseLandmarkHessianType
typedef
Traits::PoseLandmarkMatrixType 
PoseLandmarkMatrixType
typedef Traits::PoseMatrixType PoseMatrixType
typedef Traits::PoseVectorType PoseVectorType

Public Member Functions

 BlockSolver (SparseOptimizer *optimizer, LinearSolverType *linearSolver)
virtual bool buildStructure (bool zeroBlocks=false)
virtual bool buildSystem ()
virtual bool computeMarginals ()
virtual bool computeMarginals (SparseBlockMatrix< MatrixXd > &spinv, const std::vector< std::pair< int, int > > &blockIndices)
virtual bool init (bool online=false)
LinearSolver< PoseMatrixType > * linearSolver () const
virtual bool schur ()
 should the solver perform the schur complement or not
virtual bool setLambda (double lambda)
virtual void setSchur (bool s)
virtual bool solve ()
virtual bool supportsSchur ()
virtual bool updateStructure (const std::vector< HyperGraph::Vertex * > &vset, const HyperGraph::EdgeSet &edges)
 ~BlockSolver ()

Static Public Attributes

static const int LandmarkDim = Traits::LandmarkDim
static const int PoseDim = Traits::PoseDim

Protected Member Functions

void resize (int *blockPoseIndices, int numPoseBlocks, int *blockLandmarkIndices, int numLandmarkBlocks, int totalDim)

Protected Attributes

double * _bschur
double * _coefficients
SparseBlockMatrix
< LandmarkMatrixType > * 
_DInvSchur
bool _doSchur
SparseBlockMatrix
< LandmarkMatrixType > * 
_Hll
SparseBlockMatrix
< PoseLandmarkMatrixType > * 
_Hpl
SparseBlockMatrix
< PoseMatrixType > * 
_Hpp
SparseBlockMatrix
< PoseMatrixType > * 
_Hschur
LinearSolver< PoseMatrixType > * _linearSolver
int _numLandmarks
int _numPoses
int _sizeLandmarks
int _sizePoses

Detailed Description

template<typename Traits>
class g2o::BlockSolver< Traits >

Implementation of a solver operating on the blocks of the Hessian.

Definition at line 75 of file block_solver.h.


Member Typedef Documentation

template<typename Traits>
typedef Traits::LandmarkHessianType g2o::BlockSolver< Traits >::LandmarkHessianType

Definition at line 87 of file block_solver.h.

template<typename Traits>
typedef Traits::LandmarkMatrixType g2o::BlockSolver< Traits >::LandmarkMatrixType

Definition at line 81 of file block_solver.h.

template<typename Traits>
typedef Traits::LandmarkVectorType g2o::BlockSolver< Traits >::LandmarkVectorType

Definition at line 84 of file block_solver.h.

template<typename Traits>
typedef Traits::LinearSolverType g2o::BlockSolver< Traits >::LinearSolverType

Definition at line 89 of file block_solver.h.

template<typename Traits>
typedef Traits::PoseHessianType g2o::BlockSolver< Traits >::PoseHessianType

Definition at line 86 of file block_solver.h.

template<typename Traits>
typedef Traits::PoseLandmarkHessianType g2o::BlockSolver< Traits >::PoseLandmarkHessianType

Definition at line 88 of file block_solver.h.

template<typename Traits>
typedef Traits::PoseLandmarkMatrixType g2o::BlockSolver< Traits >::PoseLandmarkMatrixType

Definition at line 82 of file block_solver.h.

template<typename Traits>
typedef Traits::PoseMatrixType g2o::BlockSolver< Traits >::PoseMatrixType

Definition at line 80 of file block_solver.h.

template<typename Traits>
typedef Traits::PoseVectorType g2o::BlockSolver< Traits >::PoseVectorType

Definition at line 83 of file block_solver.h.


Constructor & Destructor Documentation

template<typename Traits >
g2o::BlockSolver< Traits >::BlockSolver ( SparseOptimizer optimizer,
LinearSolverType linearSolver 
)

Allocate a block solver ontop of the underlying linear solver. NOTE: The BlockSolver assumes exclusive access to the linear solver and will therefore free the pointer in its destructor.

Definition at line 30 of file block_solver.hpp.

template<typename Traits >
g2o::BlockSolver< Traits >::~BlockSolver ( )

Definition at line 151 of file block_solver.hpp.


Member Function Documentation

template<typename Traits >
bool g2o::BlockSolver< Traits >::buildStructure ( bool  zeroBlocks = false) [virtual]

build the structure of the system

¿¿¿¿ QUE PASA SI EL EDGE TIENE MAS DE 2 VERTICES ????

Implements g2o::Solver.

Definition at line 188 of file block_solver.hpp.

template<typename Traits >
bool g2o::BlockSolver< Traits >::buildSystem ( ) [virtual]

build the current system

Implements g2o::Solver.

Definition at line 840 of file block_solver.hpp.

template<typename Traits >
bool g2o::BlockSolver< Traits >::computeMarginals ( ) [virtual]

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

Implements g2o::Solver.

Definition at line 802 of file block_solver.hpp.

template<typename Traits >
bool g2o::BlockSolver< Traits >::computeMarginals ( SparseBlockMatrix< MatrixXd > &  spinv,
const std::vector< std::pair< int, int > > &  blockIndices 
) [virtual]

computes the block diagonal elements of the pattern specified in the input and stores them in the nodes of the graph.

Implements g2o::Solver.

Definition at line 824 of file block_solver.hpp.

template<typename Traits >
bool g2o::BlockSolver< Traits >::init ( bool  online = false) [virtual]

initialize the solver, called once before the first iteration

Implements g2o::Solver.

Definition at line 930 of file block_solver.hpp.

template<typename Traits>
LinearSolver<PoseMatrixType>* g2o::BlockSolver< Traits >::linearSolver ( ) const [inline]

Definition at line 121 of file block_solver.h.

template<typename Traits >
void g2o::BlockSolver< Traits >::resize ( int *  blockPoseIndices,
int  numPoseBlocks,
int *  blockLandmarkIndices,
int  numLandmarkBlocks,
int  totalDim 
) [protected]

Definition at line 55 of file block_solver.hpp.

template<typename Traits>
virtual bool g2o::BlockSolver< Traits >::schur ( ) [inline, virtual]

should the solver perform the schur complement or not

Implements g2o::Solver.

Definition at line 118 of file block_solver.h.

template<typename Traits >
bool g2o::BlockSolver< Traits >::setLambda ( double  lambda) [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.

Implements g2o::Solver.

Definition at line 906 of file block_solver.hpp.

template<typename Traits>
virtual void g2o::BlockSolver< Traits >::setSchur ( bool  s) [inline, virtual]

Implements g2o::Solver.

Definition at line 119 of file block_solver.h.

template<typename Traits >
bool g2o::BlockSolver< Traits >::solve ( ) [virtual]

solve Ax = b

¿¿¿¿ QUE PASA SI EL EDGE TIENE MAS DE 2 VERTICES ????

Implements g2o::Solver.

Definition at line 523 of file block_solver.hpp.

template<typename Traits>
virtual bool g2o::BlockSolver< Traits >::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 from g2o::Solver.

Definition at line 117 of file block_solver.h.

template<typename Traits >
bool g2o::BlockSolver< Traits >::updateStructure ( const std::vector< HyperGraph::Vertex * > &  vset,
const HyperGraph::EdgeSet edges 
) [virtual]

update the structures for online processing

Implements g2o::Solver.

Definition at line 435 of file block_solver.hpp.


Member Data Documentation

template<typename Traits>
double* g2o::BlockSolver< Traits >::_bschur [protected]

Definition at line 142 of file block_solver.h.

template<typename Traits>
double* g2o::BlockSolver< Traits >::_coefficients [protected]

Definition at line 141 of file block_solver.h.

template<typename Traits>
SparseBlockMatrix<LandmarkMatrixType>* g2o::BlockSolver< Traits >::_DInvSchur [protected]

Definition at line 135 of file block_solver.h.

template<typename Traits>
bool g2o::BlockSolver< Traits >::_doSchur [protected]

Definition at line 139 of file block_solver.h.

template<typename Traits>
SparseBlockMatrix<LandmarkMatrixType>* g2o::BlockSolver< Traits >::_Hll [protected]

Definition at line 131 of file block_solver.h.

template<typename Traits>
SparseBlockMatrix<PoseLandmarkMatrixType>* g2o::BlockSolver< Traits >::_Hpl [protected]

Definition at line 132 of file block_solver.h.

template<typename Traits>
SparseBlockMatrix<PoseMatrixType>* g2o::BlockSolver< Traits >::_Hpp [protected]

Definition at line 130 of file block_solver.h.

template<typename Traits>
SparseBlockMatrix<PoseMatrixType>* g2o::BlockSolver< Traits >::_Hschur [protected]

Definition at line 134 of file block_solver.h.

template<typename Traits>
LinearSolver<PoseMatrixType>* g2o::BlockSolver< Traits >::_linearSolver [protected]

Definition at line 137 of file block_solver.h.

template<typename Traits>
int g2o::BlockSolver< Traits >::_numLandmarks [protected]

Definition at line 144 of file block_solver.h.

template<typename Traits>
int g2o::BlockSolver< Traits >::_numPoses [protected]

Definition at line 144 of file block_solver.h.

template<typename Traits>
int g2o::BlockSolver< Traits >::_sizeLandmarks [protected]

Definition at line 145 of file block_solver.h.

template<typename Traits>
int g2o::BlockSolver< Traits >::_sizePoses [protected]

Definition at line 145 of file block_solver.h.

template<typename Traits>
const int g2o::BlockSolver< Traits >::LandmarkDim = Traits::LandmarkDim [static]

Definition at line 79 of file block_solver.h.

template<typename Traits>
const int g2o::BlockSolver< Traits >::PoseDim = Traits::PoseDim [static]

Definition at line 78 of file block_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