Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
g2o::LinearSolverEigen< MatrixType > Class Template Reference

linear solver which uses the sparse Cholesky solver from Eigen More...

#include <linear_solver_eigen.h>

Inheritance diagram for g2o::LinearSolverEigen< MatrixType >:
Inheritance graph
[legend]

Classes

class  CholeskyDecomposition
 Sub-classing Eigen's SimplicialLDLT to perform ordering with a given ordering. More...
 

Public Types

typedef Eigen::PermutationMatrix< Eigen::Dynamic, Eigen::Dynamic > PermutationMatrix
 
typedef Eigen::SparseMatrix< double, Eigen::ColMajor > SparseMatrix
 
typedef Eigen::Triplet< double > Triplet
 

Public Member Functions

bool blockOrdering () const
 do the AMD ordering on the blocks or on the scalar matrix More...
 
virtual bool init ()
 
 LinearSolverEigen ()
 
void setBlockOrdering (bool blockOrdering)
 
virtual void setWriteDebug (bool b)
 
bool solve (const SparseBlockMatrix< MatrixType > &A, double *x, double *b)
 
virtual bool writeDebug () const
 write a debug dump of the system matrix if it is not SPD in solve More...
 
virtual ~LinearSolverEigen ()
 
- Public Member Functions inherited from g2o::LinearSolver< MatrixType >
 LinearSolver ()
 
virtual bool solveBlocks (double **&blocks, const SparseBlockMatrix< MatrixType > &A)
 
virtual bool solvePattern (SparseBlockMatrix< MatrixXd > &spinv, const std::vector< std::pair< int, int > > &blockIndices, const SparseBlockMatrix< MatrixType > &A)
 
virtual ~LinearSolver ()
 

Protected Member Functions

void computeSymbolicDecomposition (const SparseBlockMatrix< MatrixType > &A)
 
void fillSparseMatrix (const SparseBlockMatrix< MatrixType > &A, bool onlyValues)
 

Protected Attributes

bool _blockOrdering
 
CholeskyDecomposition _cholesky
 
bool _init
 
SparseMatrix _sparseMatrix
 
bool _writeDebug
 

Detailed Description

template<typename MatrixType>
class g2o::LinearSolverEigen< MatrixType >

linear solver which uses the sparse Cholesky solver from Eigen

Has no dependencies except Eigen. Hence, should compile almost everywhere without to much issues. Performance should be similar to CSparse, I guess.

Definition at line 51 of file linear_solver_eigen.h.

Member Typedef Documentation

template<typename MatrixType>
typedef Eigen::PermutationMatrix<Eigen::Dynamic, Eigen::Dynamic> g2o::LinearSolverEigen< MatrixType >::PermutationMatrix

Definition at line 56 of file linear_solver_eigen.h.

template<typename MatrixType>
typedef Eigen::SparseMatrix<double, Eigen::ColMajor> g2o::LinearSolverEigen< MatrixType >::SparseMatrix

Definition at line 54 of file linear_solver_eigen.h.

template<typename MatrixType>
typedef Eigen::Triplet<double> g2o::LinearSolverEigen< MatrixType >::Triplet

Definition at line 55 of file linear_solver_eigen.h.

Constructor & Destructor Documentation

template<typename MatrixType>
g2o::LinearSolverEigen< MatrixType >::LinearSolverEigen ( )
inline

Definition at line 78 of file linear_solver_eigen.h.

template<typename MatrixType>
virtual g2o::LinearSolverEigen< MatrixType >::~LinearSolverEigen ( )
inlinevirtual

Definition at line 84 of file linear_solver_eigen.h.

Member Function Documentation

template<typename MatrixType>
bool g2o::LinearSolverEigen< MatrixType >::blockOrdering ( ) const
inline

do the AMD ordering on the blocks or on the scalar matrix

Definition at line 127 of file linear_solver_eigen.h.

template<typename MatrixType>
void g2o::LinearSolverEigen< MatrixType >::computeSymbolicDecomposition ( const SparseBlockMatrix< MatrixType > &  A)
inlineprotected

compute the symbolic decompostion of the matrix only once. Since A has the same pattern in all the iterations, we only compute the fill-in reducing ordering once and re-use for all the following iterations.

Definition at line 147 of file linear_solver_eigen.h.

template<typename MatrixType>
void g2o::LinearSolverEigen< MatrixType >::fillSparseMatrix ( const SparseBlockMatrix< MatrixType > &  A,
bool  onlyValues 
)
inlineprotected

Definition at line 203 of file linear_solver_eigen.h.

template<typename MatrixType>
virtual bool g2o::LinearSolverEigen< MatrixType >::init ( )
inlinevirtual

init for operating on matrices with a different non-zero pattern like before

Implements g2o::LinearSolver< MatrixType >.

Definition at line 88 of file linear_solver_eigen.h.

template<typename MatrixType>
void g2o::LinearSolverEigen< MatrixType >::setBlockOrdering ( bool  blockOrdering)
inline

Definition at line 128 of file linear_solver_eigen.h.

template<typename MatrixType>
virtual void g2o::LinearSolverEigen< MatrixType >::setWriteDebug ( bool  b)
inlinevirtual

Reimplemented from g2o::LinearSolver< MatrixType >.

Definition at line 132 of file linear_solver_eigen.h.

template<typename MatrixType>
bool g2o::LinearSolverEigen< MatrixType >::solve ( const SparseBlockMatrix< MatrixType > &  A,
double *  x,
double *  b 
)
inlinevirtual

Assumes that A is the same matrix for several calls. Among other assumptions, the non-zero pattern does not change! If the matrix changes call init() before. solve system Ax = b, x and b have to allocated beforehand!!

Implements g2o::LinearSolver< MatrixType >.

Definition at line 94 of file linear_solver_eigen.h.

template<typename MatrixType>
virtual bool g2o::LinearSolverEigen< MatrixType >::writeDebug ( ) const
inlinevirtual

write a debug dump of the system matrix if it is not SPD in solve

Reimplemented from g2o::LinearSolver< MatrixType >.

Definition at line 131 of file linear_solver_eigen.h.

Member Data Documentation

template<typename MatrixType>
bool g2o::LinearSolverEigen< MatrixType >::_blockOrdering
protected

Definition at line 136 of file linear_solver_eigen.h.

template<typename MatrixType>
CholeskyDecomposition g2o::LinearSolverEigen< MatrixType >::_cholesky
protected

Definition at line 139 of file linear_solver_eigen.h.

template<typename MatrixType>
bool g2o::LinearSolverEigen< MatrixType >::_init
protected

Definition at line 135 of file linear_solver_eigen.h.

template<typename MatrixType>
SparseMatrix g2o::LinearSolverEigen< MatrixType >::_sparseMatrix
protected

Definition at line 138 of file linear_solver_eigen.h.

template<typename MatrixType>
bool g2o::LinearSolverEigen< MatrixType >::_writeDebug
protected

Definition at line 137 of file linear_solver_eigen.h.


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


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