5 #ifndef __eigenpy_decomposition_minres_hpp__ 6 #define __eigenpy_decomposition_minres_hpp__ 10 #include <unsupported/Eigen/IterativeSolvers> 16 template <
typename _Solver>
18 :
public boost::python::def_visitor<IterativeSolverBaseVisitor<_Solver> > {
22 typedef typename Solver::Scalar
Scalar;
25 typedef Eigen::Matrix<
Scalar, Eigen::Dynamic, Eigen::Dynamic,
29 template <
class PyClass>
31 cl.def(
"analyzePattern",
32 (Solver & (Solver::*)(
const Eigen::EigenBase<MatrixType>& matrix)) &
33 Solver::analyzePattern,
34 bp::args(
"self",
"A"),
35 "Initializes the iterative solver for the sparsity pattern of the " 36 "matrix A for further solving Ax=b problems.",
40 (Solver & (Solver::*)(
const Eigen::EigenBase<MatrixType>& matrix)) &
42 bp::args(
"self",
"A"),
43 "Initializes the iterative solver with the numerical values of the " 44 "matrix A for further solving Ax=b problems.",
48 (Solver & (Solver::*)(
const Eigen::EigenBase<MatrixType>& matrix)) &
50 bp::args(
"self",
"A"),
51 "Initializes the iterative solver with the matrix A for further " 52 "solving Ax=b problems.",
56 "Returns the number of rows.")
58 "Returns the number of columns.")
59 .def(
"tolerance", &Solver::tolerance, bp::arg(
"self"),
60 "Returns the tolerance threshold used by the stopping criteria.")
61 .def(
"setTolerance", &Solver::setTolerance,
62 bp::args(
"self",
"tolerance"),
63 "Sets the tolerance threshold used by the stopping criteria.\n" 64 "This value is used as an upper bound to the relative residual " 65 "error: |Ax-b|/|b|.\n" 66 "The default value is the machine precision given by " 67 "NumTraits<Scalar>::epsilon().",
69 .def(
"preconditioner",
70 (Preconditioner & (Solver::*)()) & Solver::preconditioner,
72 "Returns a read-write reference to the preconditioner for custom " 74 bp::return_internal_reference<>())
76 .def(
"maxIterations", &Solver::maxIterations, bp::arg(
"self"),
77 "Returns the max number of iterations.\n" 78 "It is either the value setted by setMaxIterations or, by " 79 "default, twice the number of columns of the matrix.")
80 .def(
"setMaxIterations", &Solver::setMaxIterations,
81 bp::args(
"self",
"max_iterations"),
82 "Sets the max number of iterations.\n" 83 "Default is twice the number of columns of the matrix.",
87 "iterations", &Solver::iterations, bp::arg(
"self"),
88 "Returns the number of iterations performed during the last solve.")
89 .def(
"error", &Solver::error, bp::arg(
"self"),
90 "Returns the tolerance error reached during the last solve.\n" 91 "It is a close approximation of the true relative residual error " 93 .def(
"info", &Solver::error, bp::arg(
"info"),
94 "Returns Success if the iterations converged, and NoConvergence " 97 .def(
"solveWithGuess", &solveWithGuess<MatrixXs, MatrixXs>,
98 bp::args(
"self",
"b",
"x0"),
99 "Returns the solution x of A x = b using the current " 100 "decomposition of A and x0 as an initial solution.")
103 "solve", &solve<MatrixXs>, bp::args(
"self",
"b"),
104 "Returns the solution x of A x = b using the current decomposition " 105 "of A where b is a right hand side matrix or vector.");
109 template <
typename MatrixOrVector1,
typename MatrixOrVector2>
111 const MatrixOrVector1& b,
112 const MatrixOrVector2& guess) {
113 return self.solveWithGuess(b, guess);
116 template <
typename MatrixOrVector>
117 static MatrixOrVector
solve(
const Solver&
self,
118 const MatrixOrVector& mat_or_vec) {
119 MatrixOrVector
res =
self.solve(mat_or_vec);
124 template <
typename _MatrixType>
126 :
public boost::python::def_visitor<MINRESSolverVisitor<_MatrixType> > {
128 typedef typename MatrixType::Scalar
Scalar;
130 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, MatrixType::Options>
132 typedef Eigen::Matrix<
Scalar, Eigen::Dynamic, Eigen::Dynamic,
135 typedef Eigen::MINRES<MatrixType>
Solver;
137 template <
class PyClass>
139 cl.def(bp::init<>(bp::arg(
"self"),
"Default constructor"))
140 .def(bp::init<MatrixType>(
141 bp::args(
"self",
"matrix"),
142 "Initialize the solver with matrix A for further Ax=b solving.\n" 143 "This constructor is a shortcut for the default constructor " 144 "followed by a call to compute()."))
150 static const std::string classname =
156 bp::class_<Solver, boost::noncopyable>(
158 "A minimal residual solver for sparse symmetric problems.\n" 159 "This class allows to solve for A.x = b sparse linear problems using " 160 "the MINRES algorithm of Paige and Saunders (1975). The sparse matrix " 161 "A must be symmetric (possibly indefinite). The vectors x and b can be " 162 "either dense or sparse.\n" 163 "The maximal number of iterations and tolerance value can be " 164 "controlled via the setMaxIterations() and setTolerance() methods. The " 165 "defaults are the size of the problem for the maximal number of " 166 "iterations and NumTraits<Scalar>::epsilon() for the tolerance.\n",
172 template <
typename MatrixOrVector>
173 static MatrixOrVector
solve(
const Solver&
self,
const MatrixOrVector&
vec) {
174 return self.solve(vec);
180 #endif // ifndef __eigenpy_decomposition_minres_hpp__ Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, MatrixType::Options > MatrixXs
static MatrixOrVector solve(const Solver &self, const MatrixOrVector &mat_or_vec)
void visit(PyClass &cl) const
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, MatrixType::Options > MatrixXs
Solver::RealScalar RealScalar
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, MatrixType::Options > VectorXs
static void expose(const std::string &name)
static std::string shortname()
MatrixType::Scalar Scalar
static MatrixOrVector1 solveWithGuess(const Solver &self, const MatrixOrVector1 &b, const MatrixOrVector2 &guess)
void visit(PyClass &cl) const
Solver::MatrixType MatrixType
MatrixType::RealScalar RealScalar
void expose()
Call the expose function of a given type T.
Eigen::MINRES< MatrixType > Solver
Solver::Preconditioner Preconditioner
static MatrixOrVector solve(const Solver &self, const MatrixOrVector &vec)