5 #ifndef __pinocchio_python_algorithm_contact_cholesky_hpp__
6 #define __pinocchio_python_algorithm_contact_cholesky_hpp__
27 template<
typename ContactCholeskyDecomposition>
29 :
public boost::python::def_visitor<
30 ContactCholeskyDecompositionPythonVisitor<ContactCholeskyDecomposition>>
36 typedef typename ContactCholeskyDecomposition::Matrix
Matrix;
37 typedef typename ContactCholeskyDecomposition::Vector
Vector;
39 RigidConstraintModelVector;
41 RigidConstraintDataVector;
46 template<
class PyClass>
49 cl.def(bp::init<>(bp::arg(
"self"),
"Default constructor."))
50 .def(bp::init<const Model &>(bp::args(
"self",
"model"),
"Constructor from a model."))
51 .def(bp::init<const Model &, const RigidConstraintModelVector &>(
52 (bp::arg(
"self"), bp::arg(
"model"), bp::arg(
"contact_models")),
53 "Constructor from a model and a collection of RigidConstraintModels."))
55 .PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(
Self,
U,
"")
56 .PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(
Self,
D,
"")
57 .PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(
Self, Dinv,
"")
59 .def(
"size", &
Self::size, bp::arg(
"self"),
"Size of the decomposition.")
61 "constraintDim", &Self::constraintDim, bp::arg(
"self"),
62 "Returns the total dimension of the constraints contained in the Cholesky "
65 "numContacts", &Self::numContacts, bp::arg(
"self"),
66 "Returns the number of contacts associated to this decomposition.")
68 "matrix", (
Matrix(
Self::*)(
void)
const)&Self::matrix, bp::arg(
"self"),
69 "Returns the matrix resulting from the decomposition.")
74 Self &
self,
const Model &,
Data &,
const RigidConstraintModelVector &,
76 (bp::arg(
"self"), bp::arg(
"model"), bp::arg(
"data"), bp::arg(
"contact_models"),
77 bp::arg(
"contact_datas"), bp::arg(
"mu") = 0),
78 "Computes the Cholesky decompostion of the augmented matrix containing the KKT matrix\n"
79 "related to the system mass matrix and the Jacobians of the contact patches contained "
81 "the vector of RigidConstraintModel named contact_models. The decomposition is "
82 "regularized with a factor mu.")
87 Self &
self,
const Model &,
Data &,
const RigidConstraintModelVector &,
89 (bp::arg(
"self"), bp::arg(
"model"), bp::arg(
"data"), bp::arg(
"contact_models"),
90 bp::arg(
"contact_datas"), bp::arg(
"mus")),
91 "Computes the Cholesky decompostion of the augmented matrix containing the KKT matrix\n"
92 "related to the system mass matrix and the Jacobians of the contact patches contained "
94 "the vector of RigidConstraintModel named contact_models. The decomposition is "
95 "regularized with a factor mu.")
98 "updateDamping", (
void(
Self::*)(
const Scalar &)) & Self::updateDamping,
99 bp::args(
"self",
"mu"),
100 "Update the damping term on the upper left block part of the KKT matrix. The "
101 "damping term should be positive.")
104 "updateDamping", &Self::template updateDamping<Vector>, bp::args(
"self",
"mus"),
105 "Update the damping terms on the upper left block part of the KKT matrix. The "
106 "damping terms should be all positives.")
109 "getInverseOperationalSpaceInertiaMatrix",
110 (
Matrix(
Self::*)(
void)
const)&Self::getInverseOperationalSpaceInertiaMatrix,
112 "Returns the Inverse of the Operational Space Inertia Matrix resulting from the "
114 bp::return_value_policy<bp::return_by_value>())
117 "getOperationalSpaceInertiaMatrix",
118 (
Matrix(
Self::*)(
void)
const)&Self::getOperationalSpaceInertiaMatrix, bp::arg(
"self"),
119 "Returns the Operational Space Inertia Matrix resulting from the decomposition.",
120 bp::return_value_policy<bp::return_by_value>())
123 "getInverseMassMatrix", (
Matrix(
Self::*)(
void)
const)&Self::getInverseMassMatrix,
125 "Returns the inverse of the Joint Space Inertia Matrix or \"mass matrix\".",
126 bp::return_value_policy<bp::return_by_value>())
129 "solve", &solve<Matrix>, bp::args(
"self",
"matrix"),
130 "Computes the solution of \f$ A x = b \f$ where self corresponds to the Cholesky "
131 "decomposition of A.",
132 bp::return_value_policy<bp::return_by_value>())
136 "Returns the inverse matrix resulting from the decomposition.")
139 "getMassMatrixChoeslkyDecomposition",
140 &Self::template getMassMatrixChoeslkyDecomposition<
143 "Retrieves the Cholesky decomposition of the Mass Matrix contained in the current "
147 "getDelassusCholeskyExpression", &Self::getDelassusCholeskyExpression, bp::arg(
"self"),
148 "Returns the Cholesky decomposition expression associated to the underlying "
150 bp::with_custodian_and_ward_postcall<0, 1>())
157 bp::class_<ContactCholeskyDecomposition>(
158 "ContactCholeskyDecomposition",
159 "Contact information container for contact dynamic algorithms.", bp::no_init)
164 typedef typename ContactCholeskyDecomposition::DelassusCholeskyExpression
165 DelassusCholeskyExpression;
167 bp::class_<DelassusCholeskyExpression>(
168 "DelassusCholeskyExpression",
169 "Delassus Cholesky expression associated to a "
170 "given ContactCholeskyDecomposition object.",
172 .def(bp::init<const ContactCholeskyDecomposition &>(
173 bp::args(
"self",
"cholesky_decomposition"),
174 "Build from a given ContactCholeskyDecomposition object.")
175 [bp::with_custodian_and_ward<1, 2>()])
182 "Returns the Constraint Cholesky decomposition associated to this "
183 "DelassusCholeskyExpression.",
184 bp::return_internal_reference<>())
191 bp::class_<DelassusOperatorDense>(
192 "DelassusOperatorDense",
"Delassus Cholesky dense operator from a dense matrix.",
194 .def(
bp::init<
const Eigen::Ref<const context::MatrixXs>>(
195 bp::args(
"self",
"matrix"),
"Build from a given dense matrix"))
203 bp::class_<DelassusOperatorSparse, boost::noncopyable>(
204 "DelassusOperatorSparse",
"Delassus Cholesky sparse operator from a sparse matrix.",
206 .def(bp::init<const context::SparseMatrix &>(
207 bp::args(
"self",
"matrix"),
"Build from a given sparse matrix"))
211 #ifdef PINOCCHIO_WITH_ACCELERATE_SUPPORT
213 typedef Eigen::AccelerateLLT<context::SparseMatrix> AccelerateCholeskyDecomposition;
216 DelassusOperatorSparseAccelerate;
217 bp::class_<DelassusOperatorSparseAccelerate, boost::noncopyable>(
218 "DelassusOperatorSparseAccelerate",
219 "Delassus Cholesky sparse operator leveraging the Accelerate framework on APPLE "
222 .def(bp::init<const context::SparseMatrix &>(
223 bp::args(
"self",
"matrix"),
"Build from a given sparse matrix"))
230 template<
typename MatrixType>
233 return self.solve(
mat);
262 #endif // ifndef __pinocchio_python_algorithm_contact_cholesky_hpp__