5 #ifndef __pinocchio_python_algorithm_contact_cholesky_hpp__
6 #define __pinocchio_python_algorithm_contact_cholesky_hpp__
28 template<
typename ContactCholeskyDecomposition>
30 :
public boost::python::def_visitor<
31 ContactCholeskyDecompositionPythonVisitor<ContactCholeskyDecomposition>>
37 typedef typename ContactCholeskyDecomposition::Matrix
Matrix;
38 typedef typename ContactCholeskyDecomposition::Vector
Vector;
40 RigidConstraintModelVector;
42 RigidConstraintDataVector;
47 template<
class PyClass>
50 cl.def(bp::init<>(bp::arg(
"self"),
"Default constructor."))
51 .def(bp::init<const Model &>(
52 bp::args(
"self",
"model"),
54 .def(bp::init<const Model &, const RigidConstraintModelVector &>(
55 (bp::arg(
"self"), bp::arg(
"model"), bp::arg(
"contact_models")),
56 "Constructor from a model and a collection of RigidConstraintModels.")
59 .PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(
Self,
U,
"")
60 .PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(
Self,
D,
"")
61 .PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(
Self, Dinv,
"")
63 .def(
"size", &
Self::size, bp::arg(
"self"),
"Size of the decomposition.")
65 "constraintDim", &Self::constraintDim, bp::arg(
"self"),
66 "Returns the total dimension of the constraints contained in the Cholesky "
69 "numContacts", &Self::numContacts, bp::arg(
"self"),
70 "Returns the number of contacts associated to this decomposition.")
72 "matrix", (
Matrix(
Self::*)(
void)
const)&Self::matrix, bp::arg(
"self"),
73 "Returns the matrix resulting from the decomposition.")
78 Self &
self,
const Model &,
Data &,
const RigidConstraintModelVector &,
80 (bp::arg(
"self"), bp::arg(
"model"), bp::arg(
"data"), bp::arg(
"contact_models"),
81 bp::arg(
"contact_datas"), bp::arg(
"mu") = 0),
82 "Computes the Cholesky decompostion of the augmented matrix containing the KKT matrix\n"
83 "related to the system mass matrix and the Jacobians of the contact patches contained "
85 "the vector of RigidConstraintModel named contact_models. The decomposition is "
86 "regularized with a factor mu.",
92 Self &
self,
const Model &,
Data &,
const RigidConstraintModelVector &,
94 (bp::arg(
"self"), bp::arg(
"model"), bp::arg(
"data"), bp::arg(
"contact_models"),
95 bp::arg(
"contact_datas"), bp::arg(
"mus")),
96 "Computes the Cholesky decompostion of the augmented matrix containing the KKT matrix\n"
97 "related to the system mass matrix and the Jacobians of the contact patches contained "
99 "the vector of RigidConstraintModel named contact_models. The decomposition is "
100 "regularized with a factor mu.",
104 "updateDamping", (
void(
Self::*)(
const Scalar &)) & Self::updateDamping,
105 bp::args(
"self",
"mu"),
106 "Update the damping term on the upper left block part of the KKT matrix. The "
107 "damping term should be positive.")
110 "updateDamping", &Self::template updateDamping<Vector>, bp::args(
"self",
"mus"),
111 "Update the damping terms on the upper left block part of the KKT matrix. The "
112 "damping terms should be all positives.")
115 "getInverseOperationalSpaceInertiaMatrix",
116 (
Matrix(
Self::*)(
void)
const)&Self::getInverseOperationalSpaceInertiaMatrix,
118 "Returns the Inverse of the Operational Space Inertia Matrix resulting from the "
120 bp::return_value_policy<bp::return_by_value>())
123 "getOperationalSpaceInertiaMatrix",
124 (
Matrix(
Self::*)(
void)
const)&Self::getOperationalSpaceInertiaMatrix, bp::arg(
"self"),
125 "Returns the Operational Space Inertia Matrix resulting from the decomposition.",
126 bp::return_value_policy<bp::return_by_value>())
129 "getInverseMassMatrix", (
Matrix(
Self::*)(
void)
const)&Self::getInverseMassMatrix,
131 "Returns the inverse of the Joint Space Inertia Matrix or \"mass matrix\".",
132 bp::return_value_policy<bp::return_by_value>())
135 "solve", &solve<Matrix>, bp::args(
"self",
"matrix"),
136 "Computes the solution of \f$ A x = b \f$ where self corresponds to the Cholesky "
137 "decomposition of A.",
138 bp::return_value_policy<bp::return_by_value>())
142 "Returns the inverse matrix resulting from the decomposition.")
145 "getMassMatrixChoeslkyDecomposition",
146 &Self::template getMassMatrixChoeslkyDecomposition<
149 "Retrieves the Cholesky decomposition of the Mass Matrix contained in the current "
153 "getDelassusCholeskyExpression", &Self::getDelassusCholeskyExpression, bp::arg(
"self"),
154 "Returns the Cholesky decomposition expression associated to the underlying "
156 bp::with_custodian_and_ward_postcall<0, 1>())
163 bp::class_<ContactCholeskyDecomposition>(
164 "ContactCholeskyDecomposition",
165 "Contact information container for contact dynamic algorithms.", bp::no_init)
170 typedef typename ContactCholeskyDecomposition::DelassusCholeskyExpression
171 DelassusCholeskyExpression;
173 bp::class_<DelassusCholeskyExpression>(
174 "DelassusCholeskyExpression",
175 "Delassus Cholesky expression associated to a "
176 "given ContactCholeskyDecomposition object.",
178 .def(bp::init<const ContactCholeskyDecomposition &>(
179 bp::args(
"self",
"cholesky_decomposition"),
180 "Build from a given ContactCholeskyDecomposition object.")
181 [bp::with_custodian_and_ward<1, 2>()])
188 "Returns the Constraint Cholesky decomposition associated to this "
189 "DelassusCholeskyExpression.",
190 bp::return_internal_reference<>())
195 #ifndef PINOCCHIO_PYTHON_SKIP_CASADI_UNSUPPORTED
197 bp::class_<DelassusOperatorDense>(
198 "DelassusOperatorDense",
"Delassus Cholesky dense operator from a dense matrix.",
200 .def(
bp::init<
const Eigen::Ref<const context::MatrixXs>>(
201 bp::args(
"self",
"matrix"),
"Build from a given dense matrix"))
204 #endif // PINOCCHIO_PYTHON_SKIP_CASADI_UNSUPPORTED
208 #ifndef PINOCCHIO_PYTHON_SKIP_CASADI_UNSUPPORTED
211 bp::class_<DelassusOperatorSparse, boost::noncopyable>(
212 "DelassusOperatorSparse",
"Delassus Cholesky sparse operator from a sparse matrix.",
214 .def(bp::init<const context::SparseMatrix &>(
215 bp::args(
"self",
"matrix"),
"Build from a given sparse matrix"))
218 #endif // PINOCCHIO_PYTHON_SKIP_CASADI_UNSUPPORTED
220 #ifdef PINOCCHIO_WITH_ACCELERATE_SUPPORT
222 typedef Eigen::AccelerateLLT<context::SparseMatrix> AccelerateCholeskyDecomposition;
225 DelassusOperatorSparseAccelerate;
226 bp::class_<DelassusOperatorSparseAccelerate, boost::noncopyable>(
227 "DelassusOperatorSparseAccelerate",
228 "Delassus Cholesky sparse operator leveraging the Accelerate framework on APPLE "
231 .def(bp::init<const context::SparseMatrix &>(
232 bp::args(
"self",
"matrix"),
"Build from a given sparse matrix"))
239 template<
typename MatrixType>
242 return self.solve(
mat);
271 #endif // ifndef __pinocchio_python_algorithm_contact_cholesky_hpp__