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

linear solver using dense cholesky decomposition More...

#include <linear_solver_dense.h>

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

Public Member Functions

virtual bool init ()
 
 LinearSolverDense ()
 
bool solve (const SparseBlockMatrix< MatrixType > &A, double *x, double *b)
 
virtual ~LinearSolverDense ()
 
- Public Member Functions inherited from g2o::LinearSolver< MatrixType >
 LinearSolver ()
 
virtual void setWriteDebug (bool)
 
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 bool writeDebug () const
 write a debug dump of the system matrix if it is not PSD in solve More...
 
virtual ~LinearSolver ()
 

Protected Attributes

Eigen::LDLT< Eigen::MatrixXd > _cholesky
 
Eigen::MatrixXd _H
 
bool _reset
 

Detailed Description

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

linear solver using dense cholesky decomposition

Definition at line 46 of file linear_solver_dense.h.

Constructor & Destructor Documentation

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

Definition at line 49 of file linear_solver_dense.h.

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

Definition at line 55 of file linear_solver_dense.h.

Member Function Documentation

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

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

Implements g2o::LinearSolver< MatrixType >.

Definition at line 59 of file linear_solver_dense.h.

template<typename MatrixType>
bool g2o::LinearSolverDense< 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 65 of file linear_solver_dense.h.

Member Data Documentation

template<typename MatrixType>
Eigen::LDLT<Eigen::MatrixXd> g2o::LinearSolverDense< MatrixType >::_cholesky
protected

Definition at line 118 of file linear_solver_dense.h.

template<typename MatrixType>
Eigen::MatrixXd g2o::LinearSolverDense< MatrixType >::_H
protected

Definition at line 117 of file linear_solver_dense.h.

template<typename MatrixType>
bool g2o::LinearSolverDense< MatrixType >::_reset
protected

Definition at line 116 of file linear_solver_dense.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