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

linear solver which uses CSparse More...

#include <linear_solver_csparse.h>

Inheritance diagram for g2o::LinearSolverCSparse< 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 ()
 LinearSolverCSparse ()
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 ~LinearSolverCSparse ()

Protected Member Functions

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

Protected Attributes

bool _blockOrdering
CSparseExt_ccsA
int * _csIntWorkspace
double * _csWorkspace
int _csWorkspaceSize
MatrixStructure _matrixStructure
VectorXi _scalarPermutation
css_symbolicDecomposition

Detailed Description

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

linear solver which uses CSparse

Definition at line 60 of file linear_solver_csparse.h.


Constructor & Destructor Documentation

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

Definition at line 63 of file linear_solver_csparse.h.

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

Definition at line 74 of file linear_solver_csparse.h.


Member Function Documentation

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

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

Definition at line 211 of file linear_solver_csparse.h.

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

Definition at line 224 of file linear_solver_csparse.h.

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

Definition at line 287 of file linear_solver_csparse.h.

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

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

Implements g2o::LinearSolver< MatrixType >.

Definition at line 85 of file linear_solver_csparse.h.

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

Definition at line 212 of file linear_solver_csparse.h.

template<typename MatrixType >
bool g2o::LinearSolverCSparse< 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 94 of file linear_solver_csparse.h.

template<typename MatrixType >
bool g2o::LinearSolverCSparse< 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 129 of file linear_solver_csparse.h.

template<typename MatrixType >
virtual bool g2o::LinearSolverCSparse< 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 174 of file linear_solver_csparse.h.


Member Data Documentation

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

Definition at line 220 of file linear_solver_csparse.h.

template<typename MatrixType >
CSparseExt* g2o::LinearSolverCSparse< MatrixType >::_ccsA [protected]

Definition at line 219 of file linear_solver_csparse.h.

template<typename MatrixType >
int* g2o::LinearSolverCSparse< MatrixType >::_csIntWorkspace [protected]

Definition at line 218 of file linear_solver_csparse.h.

template<typename MatrixType >
double* g2o::LinearSolverCSparse< MatrixType >::_csWorkspace [protected]

Definition at line 217 of file linear_solver_csparse.h.

template<typename MatrixType >
int g2o::LinearSolverCSparse< MatrixType >::_csWorkspaceSize [protected]

Definition at line 216 of file linear_solver_csparse.h.

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

Definition at line 221 of file linear_solver_csparse.h.

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

Definition at line 222 of file linear_solver_csparse.h.

template<typename MatrixType >
css* g2o::LinearSolverCSparse< MatrixType >::_symbolicDecomposition [protected]

Definition at line 215 of file linear_solver_csparse.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