5 #ifndef __eigenpy_decomposition_ldlt_hpp__ 6 #define __eigenpy_decomposition_ldlt_hpp__ 11 #include <Eigen/Cholesky> 18 template<
typename _MatrixType>
20 :
public boost::python::def_visitor< LDLTSolverVisitor<_MatrixType> >
24 typedef typename MatrixType::Scalar
Scalar;
26 typedef Eigen::Matrix<Scalar,Eigen::Dynamic,1,MatrixType::Options>
VectorType;
27 typedef Eigen::LDLT<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 LDLT factorization from a given matrix."))
40 .def(
"isNegative",&Solver::isNegative,bp::arg(
"self"),
41 "Returns true if the matrix is negative (semidefinite).")
42 .def(
"isPositive",&Solver::isPositive,bp::arg(
"self"),
43 "Returns true if the matrix is positive (semidefinite).")
45 .def(
"matrixL",&
matrixL,bp::arg(
"self"),
46 "Returns the lower triangular matrix L.")
47 .def(
"matrixU",&
matrixU,bp::arg(
"self"),
48 "Returns the upper triangular matrix U.")
49 .def(
"vectorD",&
vectorD,bp::arg(
"self"),
50 "Returns the coefficients of the diagonal matrix D.")
52 "Returns the permutation matrix P.")
54 .def(
"matrixLDLT",&Solver::matrixLDLT,bp::arg(
"self"),
55 "Returns the LDLT decomposition matrix.",
56 bp::return_internal_reference<>())
58 .def(
"rankUpdate",(Solver & (Solver::*)(
const Eigen::MatrixBase<VectorType> &,
const RealScalar &))&Solver::template rankUpdate<VectorType>,
59 bp::args(
"self",
"vector",
"sigma"),
62 #if EIGEN_VERSION_AT_LEAST(3,3,0) 63 .def(
"adjoint",&Solver::adjoint,bp::arg(
"self"),
64 "Returns the adjoint, that is, a reference to the decomposition itself as if the underlying matrix is self-adjoint.",
68 .def(
"compute",(Solver & (Solver::*)(
const Eigen::EigenBase<MatrixType> &
matrix))&Solver::compute,
69 bp::args(
"self",
"matrix"),
70 "Computes the LDLT of given matrix.",
73 .def(
"info",&Solver::info,bp::arg(
"self"),
74 "NumericalIssue if the input contains INF or NaN values or overflow occured. Returns Success otherwise.")
75 #if EIGEN_VERSION_AT_LEAST(3,3,0) 76 .def(
"rcond",&Solver::rcond,bp::arg(
"self"),
77 "Returns an estimate of the reciprocal condition number of the matrix.")
79 .def(
"reconstructedMatrix",&Solver::reconstructedMatrix,bp::arg(
"self"),
80 "Returns the matrix represented by the decomposition, i.e., it returns the product: L L^*. This function is provided for debug purpose.")
81 .def(
"solve",&solve<VectorType>,bp::args(
"self",
"b"),
82 "Returns the solution x of A x = b using the current decomposition of A.")
84 .def(
"setZero",&Solver::setZero,bp::arg(
"self"),
85 "Clear any existing decomposition.")
98 bp::class_<Solver>(name.c_str(),
99 "Robust Cholesky decomposition of a matrix with pivoting.\n\n" 100 "Perform a robust Cholesky decomposition of a positive semidefinite or negative semidefinite matrix $ A $ such that $ A = P^TLDL^*P $, where P is a permutation matrix, L is lower triangular with a unit diagonal and D is a diagonal matrix.\n\n" 101 "The decomposition uses pivoting to ensure stability, so that L will have zeros in the bottom right rank(A) - n submatrix. Avoiding the square root on D also stabilizes the computation.",
108 static MatrixType
matrixL(
const Solver &
self) {
return self.matrixL(); }
109 static MatrixType
matrixU(
const Solver &
self) {
return self.matrixU(); }
110 static VectorType
vectorD(
const Solver &
self) {
return self.vectorD(); }
114 return self.transpositionsP() * MatrixType::Identity(
self.
matrixL().
rows(),
118 template<
typename VectorType>
119 static VectorType
solve(
const Solver &
self,
const VectorType &
vec)
121 return self.solve(vec);
127 #endif // ifndef __eigenpy_decomposition_ldlt_hpp__ MatrixType::Scalar Scalar
boost::python::object matrix()
static MatrixType matrixL(const Solver &self)
Eigen::LDLT< MatrixType > Solver
static std::string shortname()
static MatrixType matrixU(const Solver &self)
void visit(PyClass &cl) const
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, MatrixType::Options > VectorType
static VectorType vectorD(const Solver &self)
static VectorType solve(const Solver &self, const VectorType &vec)
static MatrixType transpositionsP(const Solver &self)
static void expose(const std::string &name)
MatrixType::RealScalar RealScalar