linear solver using PCG, pre-conditioner is block Jacobi More...
#include <linear_solver_pcg.h>
Public Member Functions | |
bool | absoluteTolerance () const |
virtual bool | init () |
LinearSolverPCG () | |
int | maxIterations () const |
void | setAbsoluteTolerance (bool absoluteTolerance) |
void | setMaxIterations (int maxIter) |
void | setTolerance (double tolerance) |
void | setVerbose (bool verbose) |
bool | solve (const SparseBlockMatrix< MatrixType > &A, double *x, double *b) |
double | tolerance () const |
return the tolerance for terminating PCG before convergence | |
bool | verbose () const |
virtual | ~LinearSolverPCG () |
Protected Types | |
typedef std::vector< const MatrixType * > | MatrixPtrVector |
typedef std::vector < MatrixType, Eigen::aligned_allocator < MatrixType > > | MatrixVector |
Protected Member Functions | |
void | mult (const std::vector< int > &colBlockIndices, const Eigen::VectorXd &src, Eigen::VectorXd &dest) |
void | multDiag (const std::vector< int > &colBlockIndices, MatrixVector &A, const Eigen::VectorXd &src, Eigen::VectorXd &dest) |
void | multDiag (const std::vector< int > &colBlockIndices, MatrixPtrVector &A, const Eigen::VectorXd &src, Eigen::VectorXd &dest) |
Protected Attributes | |
bool | _absoluteTolerance |
MatrixPtrVector | _diag |
std::vector< std::pair< int, int > > | _indices |
MatrixVector | _J |
int | _maxIter |
double | _residual |
MatrixPtrVector | _sparseMat |
double | _tolerance |
bool | _verbose |
linear solver using PCG, pre-conditioner is block Jacobi
Definition at line 37 of file linear_solver_pcg.h.
typedef std::vector< const MatrixType* > g2o::LinearSolverPCG< MatrixType >::MatrixPtrVector [protected] |
Definition at line 79 of file linear_solver_pcg.h.
typedef std::vector< MatrixType, Eigen::aligned_allocator<MatrixType> > g2o::LinearSolverPCG< MatrixType >::MatrixVector [protected] |
Definition at line 78 of file linear_solver_pcg.h.
g2o::LinearSolverPCG< MatrixType >::LinearSolverPCG | ( | ) | [inline] |
Definition at line 40 of file linear_solver_pcg.h.
virtual g2o::LinearSolverPCG< MatrixType >::~LinearSolverPCG | ( | ) | [inline, virtual] |
Definition at line 50 of file linear_solver_pcg.h.
bool g2o::LinearSolverPCG< MatrixType >::absoluteTolerance | ( | ) | const [inline] |
Definition at line 71 of file linear_solver_pcg.h.
virtual bool g2o::LinearSolverPCG< MatrixType >::init | ( | ) | [inline, virtual] |
init for operating on matrices with a different non-zero pattern like before
Implements g2o::LinearSolver< MatrixType >.
Definition at line 54 of file linear_solver_pcg.h.
int g2o::LinearSolverPCG< MatrixType >::maxIterations | ( | ) | const [inline] |
Definition at line 68 of file linear_solver_pcg.h.
void LinearSolverPCG::mult | ( | const std::vector< int > & | colBlockIndices, |
const Eigen::VectorXd & | src, | ||
Eigen::VectorXd & | dest | ||
) | [protected] |
Definition at line 157 of file linear_solver_pcg.h.
void LinearSolverPCG::multDiag | ( | const std::vector< int > & | colBlockIndices, |
MatrixVector & | A, | ||
const Eigen::VectorXd & | src, | ||
Eigen::VectorXd & | dest | ||
) | [protected] |
Definition at line 137 of file linear_solver_pcg.h.
void LinearSolverPCG::multDiag | ( | const std::vector< int > & | colBlockIndices, |
MatrixPtrVector & | A, | ||
const Eigen::VectorXd & | src, | ||
Eigen::VectorXd & | dest | ||
) | [protected] |
Definition at line 147 of file linear_solver_pcg.h.
void g2o::LinearSolverPCG< MatrixType >::setAbsoluteTolerance | ( | bool | absoluteTolerance | ) | [inline] |
Definition at line 72 of file linear_solver_pcg.h.
void g2o::LinearSolverPCG< MatrixType >::setMaxIterations | ( | int | maxIter | ) | [inline] |
Definition at line 69 of file linear_solver_pcg.h.
void g2o::LinearSolverPCG< MatrixType >::setTolerance | ( | double | tolerance | ) | [inline] |
Definition at line 66 of file linear_solver_pcg.h.
void g2o::LinearSolverPCG< MatrixType >::setVerbose | ( | bool | verbose | ) | [inline] |
Definition at line 75 of file linear_solver_pcg.h.
bool LinearSolverPCG::solve | ( | const SparseBlockMatrix< MatrixType > & | A, |
double * | x, | ||
double * | b | ||
) | [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 60 of file linear_solver_pcg.h.
double g2o::LinearSolverPCG< MatrixType >::tolerance | ( | ) | const [inline] |
return the tolerance for terminating PCG before convergence
Definition at line 65 of file linear_solver_pcg.h.
bool g2o::LinearSolverPCG< MatrixType >::verbose | ( | ) | const [inline] |
Definition at line 74 of file linear_solver_pcg.h.
bool g2o::LinearSolverPCG< MatrixType >::_absoluteTolerance [protected] |
Definition at line 83 of file linear_solver_pcg.h.
MatrixPtrVector g2o::LinearSolverPCG< MatrixType >::_diag [protected] |
Definition at line 87 of file linear_solver_pcg.h.
std::vector<std::pair<int, int> > g2o::LinearSolverPCG< MatrixType >::_indices [protected] |
Definition at line 90 of file linear_solver_pcg.h.
MatrixVector g2o::LinearSolverPCG< MatrixType >::_J [protected] |
Definition at line 88 of file linear_solver_pcg.h.
int g2o::LinearSolverPCG< MatrixType >::_maxIter [protected] |
Definition at line 85 of file linear_solver_pcg.h.
double g2o::LinearSolverPCG< MatrixType >::_residual [protected] |
Definition at line 82 of file linear_solver_pcg.h.
MatrixPtrVector g2o::LinearSolverPCG< MatrixType >::_sparseMat [protected] |
Definition at line 91 of file linear_solver_pcg.h.
double g2o::LinearSolverPCG< MatrixType >::_tolerance [protected] |
Definition at line 81 of file linear_solver_pcg.h.
bool g2o::LinearSolverPCG< MatrixType >::_verbose [protected] |
Definition at line 84 of file linear_solver_pcg.h.