17 #ifndef __eigenpy_iterative_solver_base_hpp__ 18 #define __eigenpy_iterative_solver_base_hpp__ 25 template <
typename IterativeSolver>
27 IterativeSolverVisitor<IterativeSolver> > {
32 template <
class PyClass>
34 typedef IterativeSolver IS;
37 .def(
"error", &IS::error,
38 "Returns the tolerance error reached during the last solve.\n" 39 "It is a close approximation of the true relative residual error " 41 .def(
"info", &IS::info,
42 "Returns success if the iterations converged, and NoConvergence " 45 "iterations", &IS::iterations,
46 "Returns the number of iterations performed during the last solve.")
47 .def(
"maxIterations", &IS::maxIterations,
48 "Returns the max number of iterations.\n" 49 "It is either the value setted by setMaxIterations or, by " 50 "default, twice the number of columns of the matrix.")
51 .def(
"setMaxIterations", &IS::setMaxIterations,
52 "Sets the max number of iterations.\n" 53 "Default is twice the number of columns of the matrix.",
54 bp::return_value_policy<bp::reference_existing_object>())
55 .def(
"tolerance", &IS::tolerance,
56 "Returns he tolerance threshold used by the stopping criteria.")
57 .def(
"setTolerance", &IS::setTolerance,
58 "Sets the tolerance threshold used by the stopping criteria.\n" 59 "This value is used as an upper bound to the relative residual " 60 "error: |Ax-b|/|b|. The default value is the machine precision.",
61 bp::return_value_policy<bp::reference_existing_object>())
63 "Initializes the iterative solver for the sparsity pattern of the " 64 "matrix A for further solving Ax=b problems.\n" 65 "Currently, this function mostly calls analyzePattern on the " 67 "In the future we might, for instance, implement column " 68 "reordering for faster matrix vector products.",
69 bp::return_value_policy<bp::reference_existing_object>())
70 .def(
"factorize", &
factorize, bp::arg(
"A"),
71 "Initializes the iterative solver with the numerical values of " 72 "the matrix A for further solving Ax=b problems.\n" 73 "Currently, this function mostly calls factorize on the " 75 bp::return_value_policy<bp::reference_existing_object>())
76 .def(
"compute", &
compute, bp::arg(
"A"),
77 "Initializes the iterative solver with the numerical values of " 78 "the matrix A for further solving Ax=b problems.\n" 79 "Currently, this function mostly calls factorize on the " 81 "In the future we might, for instance, implement column " 82 "reordering for faster matrix vector products.",
83 bp::return_value_policy<bp::reference_existing_object>())
85 "Returns the solution x of Ax = b using the current decomposition " 86 "of A and x0 as an initial solution.")
87 .def(
"preconditioner",
88 (Preconditioner & (IS::*)(
void)) & IS::preconditioner,
89 "Returns a read-write reference to the preconditioner for custom " 91 bp::return_internal_reference<>());
95 static IterativeSolver&
factorize(IterativeSolver&
self,
96 const MatrixType& m) {
97 return self.factorize(m);
100 static IterativeSolver&
compute(IterativeSolver&
self,
const MatrixType& m) {
101 return self.compute(m);
105 const MatrixType& m) {
106 return self.analyzePattern(m);
110 const Eigen::VectorXd& b,
111 const Eigen::VectorXd& x0) {
112 return self.solveWithGuess(b, x0);
118 #endif // ifndef __eigenpy_iterative_solver_base_hpp__ static IterativeSolver & analyzePattern(IterativeSolver &self, const MatrixType &m)
Eigen::VectorXd VectorType
IterativeSolver::Preconditioner Preconditioner
static IterativeSolver & factorize(IterativeSolver &self, const MatrixType &m)
IterativeSolver::MatrixType MatrixType
static IterativeSolver & compute(IterativeSolver &self, const MatrixType &m)
void visit(PyClass &cl) const
static VectorType solveWithGuess(IterativeSolver &self, const Eigen::VectorXd &b, const Eigen::VectorXd &x0)