5 #ifndef __eigenpy_decomposition_llt_hpp__ 6 #define __eigenpy_decomposition_llt_hpp__ 11 #include <Eigen/Cholesky> 18 template<
typename _MatrixType>
20 :
public boost::python::def_visitor< LLTSolverVisitor<_MatrixType> >
24 typedef typename MatrixType::Scalar
Scalar;
26 typedef Eigen::Matrix<Scalar,Eigen::Dynamic,1,MatrixType::Options>
VectorType;
27 typedef Eigen::LLT<MatrixType>
Solver;
29 template<
class PyClass>
34 .def(bp::init<>(
"Default constructor"))
35 .def(bp::init<Eigen::DenseIndex>(bp::arg(
"size"),
36 "Default constructor with memory preallocation"))
37 .def(bp::init<MatrixType>(bp::arg(
"matrix"),
38 "Constructs a LLT factorization from a given matrix."))
40 .def(
"matrixL",&
matrixL,bp::arg(
"self"),
41 "Returns the lower triangular matrix L.")
42 .def(
"matrixU",&
matrixU,bp::arg(
"self"),
43 "Returns the upper triangular matrix U.")
44 .def(
"matrixLLT",&Solver::matrixLLT,bp::arg(
"self"),
45 "Returns the LLT decomposition matrix.",
46 bp::return_internal_reference<>())
48 #if EIGEN_VERSION_AT_LEAST(3,3,90) 49 .def(
"rankUpdate",(Solver& (Solver::*)(
const VectorType &,
const RealScalar &))&Solver::template rankUpdate<VectorType>,
50 bp::args(
"self",
"vector",
"sigma"), bp::return_self<>())
52 .def(
"rankUpdate",(Solver (Solver::*)(
const VectorType &,
const RealScalar &))&Solver::template rankUpdate<VectorType>,
53 bp::args(
"self",
"vector",
"sigma"))
56 #if EIGEN_VERSION_AT_LEAST(3,3,0) 57 .def(
"adjoint",&Solver::adjoint,bp::arg(
"self"),
58 "Returns the adjoint, that is, a reference to the decomposition itself as if the underlying matrix is self-adjoint.",
62 .def(
"compute",(Solver & (Solver::*)(
const Eigen::EigenBase<MatrixType> &
matrix))&Solver::compute,
63 bp::args(
"self",
"matrix"),
64 "Computes the LLT of given matrix.",
67 .def(
"info",&Solver::info,bp::arg(
"self"),
68 "NumericalIssue if the input contains INF or NaN values or overflow occured. Returns Success otherwise.")
69 #if EIGEN_VERSION_AT_LEAST(3,3,0) 70 .def(
"rcond",&Solver::rcond,bp::arg(
"self"),
71 "Returns an estimate of the reciprocal condition number of the matrix.")
73 .def(
"reconstructedMatrix",&Solver::reconstructedMatrix,bp::arg(
"self"),
74 "Returns the matrix represented by the decomposition, i.e., it returns the product: L L^*. This function is provided for debug purpose.")
75 .def(
"solve",&solve<VectorType>,bp::args(
"self",
"b"),
76 "Returns the solution x of A x = b using the current decomposition of A.")
89 bp::class_<Solver>(name.c_str(),
90 "Standard Cholesky decomposition (LL^T) of a matrix and associated features.\n\n" 91 "This class performs a LL^T Cholesky decomposition of a symmetric, positive definite matrix A such that A = LL^* = U^*U, where L is lower triangular.\n\n" 92 "While the Cholesky decomposition is particularly useful to solve selfadjoint problems like D^*D x = b, for that purpose, we recommend the Cholesky decomposition without square root which is more stable and even faster. Nevertheless, this standard Cholesky decomposition remains useful in many other situations like generalised eigen problems with hermitian matrices.",
99 static MatrixType
matrixL(
const Solver &
self) {
return self.matrixL(); }
100 static MatrixType
matrixU(
const Solver &
self) {
return self.matrixU(); }
102 template<
typename VectorType>
103 static VectorType
solve(
const Solver &
self,
const VectorType &
vec)
105 return self.solve(vec);
111 #endif // ifndef __eigenpy_decomposition_llt_hpp__ boost::python::object matrix()
static void expose(const std::string &name)
void visit(PyClass &cl) const
MatrixType::RealScalar RealScalar
static std::string shortname()
Eigen::LLT< MatrixType > Solver
static MatrixType matrixL(const Solver &self)
static MatrixType matrixU(const Solver &self)
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, MatrixType::Options > VectorType
static VectorType solve(const Solver &self, const VectorType &vec)
MatrixType::Scalar Scalar