IterativeSolverBase.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017, Justin Carpentier, LAAS-CNRS
3  *
4  * This file is part of eigenpy.
5  * eigenpy is free software: you can redistribute it and/or
6  * modify it under the terms of the GNU Lesser General Public License
7  * as published by the Free Software Foundation, either version 3 of
8  * the License, or (at your option) any later version.
9  * eigenpy is distributed in the hope that it will be
10  * useful, but WITHOUT ANY WARRANTY; without even the implied warranty
11  * of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU Lesser General Public License for more details. You should
13  * have received a copy of the GNU Lesser General Public License along
14  * with eigenpy. If not, see <http://www.gnu.org/licenses/>.
15  */
16 
17 #ifndef __eigenpy_iterative_solver_base_hpp__
18 #define __eigenpy_iterative_solver_base_hpp__
19 
20 #include "eigenpy/fwd.hpp"
22 
23 namespace eigenpy
24 {
25 
26  namespace bp = boost::python;
27 
28  template<typename IterativeSolver>
30  : public boost::python::def_visitor< IterativeSolverVisitor<IterativeSolver> >
31  {
32 
33  typedef typename IterativeSolver::MatrixType MatrixType;
34  typedef typename IterativeSolver::Preconditioner Preconditioner;
35  typedef Eigen::VectorXd VectorType;
36 
37  template<class PyClass>
38  void visit(PyClass& cl) const
39  {
40  typedef IterativeSolver IS;
41 
42  cl
44  .def("error",&IS::error,"Returns the tolerance error reached during the last solve.\n"
45  "It is a close approximation of the true relative residual error |Ax-b|/|b|.")
46  .def("info",&IS::info,"Returns success if the iterations converged, and NoConvergence otherwise.")
47  .def("iterations",&IS::iterations,"Returns the number of iterations performed during the last solve.")
48  .def("maxIterations",&IS::maxIterations,"Returns the max number of iterations.\n"
49  "It is either the value setted by setMaxIterations or, by default, twice the number of columns of the matrix.")
50  .def("setMaxIterations",&IS::setMaxIterations,"Sets the max number of iterations.\n"
51  "Default is twice the number of columns of the matrix.",
52  bp::return_value_policy<bp::reference_existing_object>())
53  .def("tolerance",&IS::tolerance,"Returns he tolerance threshold used by the stopping criteria.")
54  .def("setTolerance",&IS::setTolerance,"Sets the tolerance threshold used by the stopping criteria.\n"
55  "This value is used as an upper bound to the relative residual error: |Ax-b|/|b|. The default value is the machine precision.",
56  bp::return_value_policy<bp::reference_existing_object>())
57  .def("analyzePattern",&analyzePattern,bp::arg("A"),"Initializes the iterative solver for the sparsity pattern of the matrix A for further solving Ax=b problems.\n"
58  "Currently, this function mostly calls analyzePattern on the preconditioner.\n"
59  "In the future we might, for instance, implement column reordering for faster matrix vector products.",
60  bp::return_value_policy<bp::reference_existing_object>())
61  .def("factorize",&factorize,bp::arg("A"),"Initializes the iterative solver with the numerical values of the matrix A for further solving Ax=b problems.\n"
62  "Currently, this function mostly calls factorize on the preconditioner.",
63  bp::return_value_policy<bp::reference_existing_object>())
64  .def("compute",&compute,bp::arg("A"),"Initializes the iterative solver with the numerical values of the matrix A for further solving Ax=b problems.\n"
65  "Currently, this function mostly calls factorize on the preconditioner.\n"
66  "In the future we might, for instance, implement column reordering for faster matrix vector products.",
67  bp::return_value_policy<bp::reference_existing_object>())
68  .def("solveWithGuess",&solveWithGuess,bp::args("b","x0"),
69  "Returns the solution x of Ax = b using the current decomposition of A and x0 as an initial solution.")
70  .def("preconditioner",(Preconditioner & (IS::*)(void))&IS::preconditioner,"Returns a read-write reference to the preconditioner for custom configuration.",bp::return_internal_reference<>())
71  ;
72 
73  }
74 
75  private:
76 
77  static IterativeSolver & factorize(IterativeSolver & self, const MatrixType & m)
78  {
79  return self.factorize(m);
80  }
81 
82  static IterativeSolver & compute(IterativeSolver & self, const MatrixType & m)
83  {
84  return self.compute(m);
85  }
86 
87  static IterativeSolver & analyzePattern(IterativeSolver & self, const MatrixType & m)
88  {
89  return self.analyzePattern(m);
90  }
91 
92  static VectorType solveWithGuess(IterativeSolver & self, const Eigen::VectorXd & b, const Eigen::VectorXd & x0)
93  {
94  return self.solveWithGuess(b,x0);
95  }
96 
97  };
98 
99 
100 } // namespace eigenpy
101 
102 #endif // ifndef __eigenpy_iterative_solver_base_hpp__
static IterativeSolver & analyzePattern(IterativeSolver &self, const MatrixType &m)
IterativeSolver::Preconditioner Preconditioner
static IterativeSolver & factorize(IterativeSolver &self, const MatrixType &m)
IterativeSolver::MatrixType MatrixType
static IterativeSolver & compute(IterativeSolver &self, const MatrixType &m)
static VectorType solveWithGuess(IterativeSolver &self, const Eigen::VectorXd &b, const Eigen::VectorXd &x0)


eigenpy
Author(s): Justin Carpentier, Nicolas Mansard
autogenerated on Sat Apr 17 2021 02:37:59