Public Member Functions | Protected Member Functions | Protected Attributes
g2o::LinearSolverCholmod< MatrixType > Class Template Reference

basic solver for Ax = b which has to reimplemented for different linear algebra libraries More...

#include <linear_solver_cholmod.h>

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

List of all members.

Public Member Functions

bool blockOrdering () const
 do the AMD ordering on the blocks or on the scalar matrix
virtual bool init ()
 LinearSolverCholmod ()
void setBlockOrdering (bool blockOrdering)
bool solve (const SparseBlockMatrix< MatrixType > &A, double *x, double *b)
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 ~LinearSolverCholmod ()

Protected Member Functions

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

Protected Attributes

bool _blockOrdering
VectorXi _blockPermutation
cholmod_common _cholmodCommon
cholmod_factor * _cholmodFactor
CholmodExt_cholmodSparse
MatrixStructure _matrixStructure
VectorXi _scalarPermutation

Detailed Description

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

basic solver for Ax = b which has to reimplemented for different linear algebra libraries

Definition at line 68 of file linear_solver_cholmod.h.


Constructor & Destructor Documentation

template<typename MatrixType>
g2o::LinearSolverCholmod< MatrixType >::LinearSolverCholmod ( ) [inline]

Definition at line 71 of file linear_solver_cholmod.h.

template<typename MatrixType>
virtual g2o::LinearSolverCholmod< MatrixType >::~LinearSolverCholmod ( ) [inline, virtual]

Definition at line 90 of file linear_solver_cholmod.h.


Member Function Documentation

template<typename MatrixType>
bool g2o::LinearSolverCholmod< MatrixType >::blockOrdering ( ) const [inline]

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

Definition at line 292 of file linear_solver_cholmod.h.

template<typename MatrixType>
void g2o::LinearSolverCholmod< MatrixType >::computeSymbolicDecomposition ( const SparseBlockMatrix< MatrixType > &  A) [inline, protected]

Definition at line 306 of file linear_solver_cholmod.h.

template<typename MatrixType>
void g2o::LinearSolverCholmod< MatrixType >::fillCholmodExt ( const SparseBlockMatrix< MatrixType > &  A,
bool  onlyValues 
) [inline, protected]

Definition at line 386 of file linear_solver_cholmod.h.

template<typename MatrixType>
virtual bool g2o::LinearSolverCholmod< MatrixType >::init ( ) [inline, virtual]

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

Implements g2o::LinearSolver< MatrixType >.

Definition at line 103 of file linear_solver_cholmod.h.

template<typename MatrixType>
void g2o::LinearSolverCholmod< MatrixType >::setBlockOrdering ( bool  blockOrdering) [inline]

Definition at line 293 of file linear_solver_cholmod.h.

template<typename MatrixType>
bool g2o::LinearSolverCholmod< MatrixType >::solve ( const SparseBlockMatrix< MatrixType > &  A,
double *  x,
double *  b 
) [inline, virtual]

Assumes that A has the same non-zero pattern over several calls. If the pattern changes call init() before. solve system Ax = b, x and b have to allocated beforehand!!

Implements g2o::LinearSolver< MatrixType >.

Definition at line 115 of file linear_solver_cholmod.h.

template<typename MatrixType>
bool g2o::LinearSolverCholmod< MatrixType >::solveBlocks ( double **&  blocks,
const SparseBlockMatrix< MatrixType > &  A 
) [inline, virtual]

Inverts the diagonal blocks of A

Returns:
false if not defined.

Reimplemented from g2o::LinearSolver< MatrixType >.

Definition at line 168 of file linear_solver_cholmod.h.

template<typename MatrixType>
virtual bool g2o::LinearSolverCholmod< MatrixType >::solvePattern ( SparseBlockMatrix< MatrixXd > &  spinv,
const std::vector< std::pair< int, int > > &  blockIndices,
const SparseBlockMatrix< MatrixType > &  A 
) [inline, virtual]

Inverts the a block pattern of A in spinv

Returns:
false if not defined.

Reimplemented from g2o::LinearSolver< MatrixType >.

Definition at line 234 of file linear_solver_cholmod.h.


Member Data Documentation

template<typename MatrixType>
bool g2o::LinearSolverCholmod< MatrixType >::_blockOrdering [protected]

Definition at line 300 of file linear_solver_cholmod.h.

template<typename MatrixType>
VectorXi g2o::LinearSolverCholmod< MatrixType >::_blockPermutation [protected]

Definition at line 302 of file linear_solver_cholmod.h.

template<typename MatrixType>
cholmod_common g2o::LinearSolverCholmod< MatrixType >::_cholmodCommon [protected]

Definition at line 297 of file linear_solver_cholmod.h.

template<typename MatrixType>
cholmod_factor* g2o::LinearSolverCholmod< MatrixType >::_cholmodFactor [protected]

Definition at line 299 of file linear_solver_cholmod.h.

template<typename MatrixType>
CholmodExt* g2o::LinearSolverCholmod< MatrixType >::_cholmodSparse [protected]

Definition at line 298 of file linear_solver_cholmod.h.

template<typename MatrixType>
MatrixStructure g2o::LinearSolverCholmod< MatrixType >::_matrixStructure [protected]

Definition at line 301 of file linear_solver_cholmod.h.

template<typename MatrixType>
VectorXi g2o::LinearSolverCholmod< MatrixType >::_scalarPermutation [protected]

Definition at line 302 of file linear_solver_cholmod.h.


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


re_vision
Author(s): Dorian Galvez-Lopez
autogenerated on Sun Jan 5 2014 11:34:30