5 #ifndef __eigenpy_decomposition_ldlt_hpp__ 6 #define __eigenpy_decomposition_ldlt_hpp__ 8 #include <Eigen/Cholesky> 16 template <
typename _MatrixType>
18 :
public boost::python::def_visitor<LDLTSolverVisitor<_MatrixType> > {
20 typedef typename MatrixType::Scalar
Scalar;
22 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 1, MatrixType::Options>
24 typedef Eigen::Matrix<
Scalar, Eigen::Dynamic, Eigen::Dynamic,
27 typedef Eigen::LDLT<MatrixType>
Solver;
29 template <
class PyClass>
31 cl.def(bp::init<>(bp::arg(
"self"),
"Default constructor"))
32 .def(bp::init<Eigen::DenseIndex>(
33 bp::args(
"self",
"size"),
34 "Default constructor with memory preallocation"))
35 .def(bp::init<MatrixType>(
36 bp::args(
"self",
"matrix"),
37 "Constructs a LDLT factorization from a given matrix."))
39 .def(
"isNegative", &Solver::isNegative, bp::arg(
"self"),
40 "Returns true if the matrix is negative (semidefinite).")
41 .def(
"isPositive", &Solver::isPositive, bp::arg(
"self"),
42 "Returns true if the matrix is positive (semidefinite).")
44 .def(
"matrixL", &
matrixL, bp::arg(
"self"),
45 "Returns the lower triangular matrix L.")
46 .def(
"matrixU", &
matrixU, bp::arg(
"self"),
47 "Returns the upper triangular matrix U.")
48 .def(
"vectorD", &
vectorD, bp::arg(
"self"),
49 "Returns the coefficients of the diagonal matrix D.")
51 "Returns the permutation matrix P.")
53 .def(
"matrixLDLT", &Solver::matrixLDLT, bp::arg(
"self"),
54 "Returns the LDLT decomposition matrix.",
55 bp::return_internal_reference<>())
58 (Solver & (Solver::*)(
const Eigen::MatrixBase<VectorXs> &,
59 const RealScalar &)) &
60 Solver::template rankUpdate<VectorXs>,
61 bp::args(
"self",
"vector",
"sigma"), bp::return_self<>())
63 #if EIGEN_VERSION_AT_LEAST(3, 3, 0) 64 .def(
"adjoint", &Solver::adjoint, bp::arg(
"self"),
65 "Returns the adjoint, that is, a reference to the decomposition " 66 "itself as if the underlying matrix is self-adjoint.",
72 (Solver & (Solver::*)(
const Eigen::EigenBase<MatrixType> &matrix)) &
74 bp::args(
"self",
"matrix"),
"Computes the LDLT of given matrix.",
77 .def(
"info", &Solver::info, bp::arg(
"self"),
78 "NumericalIssue if the input contains INF or NaN values or " 79 "overflow occured. Returns Success otherwise.")
80 #if EIGEN_VERSION_AT_LEAST(3, 3, 0) 81 .def(
"rcond", &Solver::rcond, bp::arg(
"self"),
82 "Returns an estimate of the reciprocal condition number of the " 85 .def(
"reconstructedMatrix", &Solver::reconstructedMatrix,
87 "Returns the matrix represented by the decomposition, i.e., it " 88 "returns the product: L L^*. This function is provided for debug " 90 .def(
"solve", &solve<VectorXs>, bp::args(
"self",
"b"),
91 "Returns the solution x of A x = b using the current " 92 "decomposition of A.")
93 .def(
"solve", &solve<MatrixXs>, bp::args(
"self",
"B"),
94 "Returns the solution X of A X = B using the current " 95 "decomposition of A where B is a right hand side matrix.")
98 "Clear any existing decomposition.");
102 static const std::string classname =
110 "Robust Cholesky decomposition of a matrix with pivoting.\n\n" 111 "Perform a robust Cholesky decomposition of a positive semidefinite or " 112 "negative semidefinite matrix $ A $ such that $ A = P^TLDL^*P $, where " 113 "P is a permutation matrix, L is lower triangular with a unit diagonal " 114 "and D is a diagonal matrix.\n\n" 115 "The decomposition uses pivoting to ensure stability, so that L will " 116 "have zeros in the bottom right rank(A) - n submatrix. Avoiding the " 117 "square root on D also stabilizes the computation.",
123 static MatrixType
matrixL(
const Solver &
self) {
return self.matrixL(); }
124 static MatrixType
matrixU(
const Solver &
self) {
return self.matrixU(); }
128 return self.transpositionsP() *
132 template <
typename MatrixOrVector>
133 static MatrixOrVector
solve(
const Solver &
self,
const MatrixOrVector &
vec) {
134 return self.solve(vec);
140 #endif // ifndef __eigenpy_decomposition_ldlt_hpp__ MatrixType::Scalar Scalar
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, MatrixType::Options > VectorXs
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
void setZero(std::vector< MatType, Eigen::aligned_allocator< MatType > > &Ms)
static MatrixType transpositionsP(const Solver &self)
static void expose(const std::string &name)
static VectorXs vectorD(const Solver &self)
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, MatrixType::Options > MatrixXs
static MatrixOrVector solve(const Solver &self, const MatrixOrVector &vec)
MatrixType::RealScalar RealScalar