Generic interface for sparse solvers to be coupled with ACADO Toolkit. More...
#include <sparse_solver.hpp>
Public Member Functions | |
virtual SparseSolver * | clone () const =0 |
virtual returnValue | factorize ()=0 |
virtual int_t | getNegativeEigenvalues () |
virtual int_t | getRank () |
virtual returnValue | getX (double *x)=0 |
virtual returnValue | getZeroPivots (int_t *&zeroPivots) |
virtual SparseSolver & | operator= (const SparseSolver &rhs) |
virtual returnValue | reset () |
virtual returnValue | setDimension (const int &n)=0 |
virtual returnValue | setIndices (const int *rowIdx_, const int *colIdx_)=0 |
virtual returnValue | setMatrix (double *A_)=0 |
virtual returnValue | setMatrixData (int_t dim, int_t numNonzeros, const int_t *const airn, const int_t *const acjn, const real_t *const avals)=0 |
virtual returnValue | setNumberOfEntries (const int &nDense_)=0 |
virtual returnValue | setPrintLevel (PrintLevel PrintLevel_)=0 |
virtual returnValue | setTolerance (double TOL)=0 |
virtual returnValue | solve (int_t dim, const real_t *const rhs, real_t *const sol)=0 |
virtual returnValue | solve (double *b)=0 |
virtual returnValue | solveTranspose (double *b) |
SparseSolver () | |
SparseSolver (const SparseSolver &rhs) | |
SparseSolver () | |
virtual | ~SparseSolver () |
virtual | ~SparseSolver () |
Protected Member Functions | |
returnValue | clear () |
returnValue | copy (const SparseSolver &rhs) |
Generic interface for sparse solvers to be coupled with ACADO Toolkit.
Base class for linear solvers that are used in a Schur-complement implementation in qpOASES.
The class SparseSolver is a generic interface for sparse solver to be coupled with ACADO Toolkit.
A SparseSolver deals with linear equations of the form
A * x = b
where A is (a possibly large but sparse) given matrix and b a given vector. Here, the non-zero elements of A need to be specified by one of the routines that are provided in this class. The aim of the sparse solver is to find the vector x, which is assumed to be uniquely defined by the above equation. For solving the linear equation the zero entries of the matrix A are used efficiently.
Definition at line 66 of file sparse_solver.hpp.
BEGIN_NAMESPACE_QPOASES SparseSolver::SparseSolver | ( | ) |
Default constructor.
Definition at line 47 of file sparse_solver.cpp.
|
virtual |
Destructor.
Definition at line 52 of file sparse_solver.cpp.
SparseSolver::SparseSolver | ( | ) |
Default constructor.
SparseSolver::SparseSolver | ( | const SparseSolver & | rhs | ) |
Copy constructor (deep copy).
rhs | Rhs object. |
Definition at line 67 of file SparseSolver.cpp.
|
virtual |
Destructor.
|
protected |
Frees all allocated memory.
Definition at line 137 of file SparseSolver.cpp.
|
pure virtual |
Clone operator (deep copy).
Implemented in ACADOcsparse, SymmetricConjugateGradientMethod, NormalConjugateGradientMethod, and ConjugateGradientMethod.
|
protected |
Copies all members from given rhs object.
rhs | Rhs object. |
Definition at line 146 of file SparseSolver.cpp.
|
pure virtual |
Compute factorization of current matrix. This method must be called before solve.
|
virtual |
Return the number of negative eigenvalues.
Definition at line 107 of file SparseSolver.cpp.
|
virtual |
Return the rank after a factorization
Definition at line 115 of file SparseSolver.cpp.
|
pure virtual |
Returns the solution of the equation A*x = b if solved.
Implemented in ACADOcsparse, and ConjugateGradientMethod.
|
virtual |
Returns the zero pivots in case the matrix is rank deficient
Definition at line 123 of file SparseSolver.cpp.
|
virtual |
Assignment operator (deep copy).
rhs | Rhs object. |
Definition at line 85 of file SparseSolver.cpp.
|
virtual |
Clears all data structures.
Definition at line 99 of file SparseSolver.cpp.
|
pure virtual |
Defines the dimension n of A R^{n n}
Implemented in ACADOcsparse, and ConjugateGradientMethod.
|
pure virtual |
Sets an index list containing the positions of the
non-zero elements in the matrix A.
Implemented in ACADOcsparse, ConjugateGradientMethod, SymmetricConjugateGradientMethod, and NormalConjugateGradientMethod.
|
pure virtual |
Sets the non-zero elements of the matrix A. The double* A
is assumed to contain nDense entries corresponding to
non-zero elements of A.
Implemented in ACADOcsparse, and ConjugateGradientMethod.
|
pure virtual |
Set new matrix data. The matrix is to be provided in the Harwell-Boeing format. Only the lower triangular part should be set.
dim | Dimension of the linear system. |
numNonzeros | Number of nonzeros in the matrix. |
airn | Row indices for each matrix entry. |
acjn | Column indices for each matrix entry. |
avals | Values for each matrix entry. |
|
pure virtual |
Defines the number of non-zero elements in the
matrix A
Implemented in ACADOcsparse, and ConjugateGradientMethod.
|
pure virtual |
Sets the print level.
Implemented in ACADOcsparse, and ConjugateGradientMethod.
|
pure virtual |
Sets the required tolerance (accuracy) for the solution of
the linear equation. For large tolerances an iterative
algorithm might converge earlier.
Requires || A*x - b || <= TOL
The norm || . || is possibly scaled by a preconditioner.
Implemented in ACADOcsparse, and ConjugateGradientMethod.
|
pure virtual |
Solve linear system with most recently set matrix data.
dim | Dimension of the linear system. |
rhs | Values for the right hand side. |
sol | Solution of the linear system. |
|
pure virtual |
Solves the system A*x = b for the specified data.
Implemented in ACADOcsparse, and ConjugateGradientMethod.
|
virtual |
Solves the system A^T*x = b for the specified data.
Reimplemented in ACADOcsparse.
Definition at line 58 of file sparse_solver.cpp.