bindings/python/algorithm/contact-cholesky.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2020-2024 INRIA
3 //
4 
5 #ifndef __pinocchio_python_algorithm_contact_cholesky_hpp__
6 #define __pinocchio_python_algorithm_contact_cholesky_hpp__
7 
8 #include <eigenpy/memory.hpp>
10 
13 
19 
21 
22 namespace pinocchio
23 {
24  namespace python
25  {
26  namespace bp = boost::python;
27 
28  template<typename ContactCholeskyDecomposition>
30  : public boost::python::def_visitor<
31  ContactCholeskyDecompositionPythonVisitor<ContactCholeskyDecomposition>>
32  {
37  typedef typename ContactCholeskyDecomposition::Matrix Matrix;
38  typedef typename ContactCholeskyDecomposition::Vector Vector;
40  RigidConstraintModelVector;
42  RigidConstraintDataVector;
43 
46 
47  template<class PyClass>
48  void visit(PyClass & cl) const
49  {
50  cl.def(bp::init<>(bp::arg("self"), "Default constructor."))
51  .def(bp::init<const Model &>(
52  bp::args("self", "model"),
53  "Constructor from a model.")[mimic_not_supported_function<>(1)])
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.")
58 
59  .PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(Self, U, "")
60  .PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(Self, D, "")
61  .PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(Self, Dinv, "")
62 
63  .def("size", &Self::size, bp::arg("self"), "Size of the decomposition.")
64  .def(
65  "constraintDim", &Self::constraintDim, bp::arg("self"),
66  "Returns the total dimension of the constraints contained in the Cholesky "
67  "factorization.")
68  .def(
69  "numContacts", &Self::numContacts, bp::arg("self"),
70  "Returns the number of contacts associated to this decomposition.")
71  .def(
72  "matrix", (Matrix(Self::*)(void) const)&Self::matrix, bp::arg("self"),
73  "Returns the matrix resulting from the decomposition.")
74 
75  .def(
76  "compute",
77  (void (*)(
78  Self & self, const Model &, Data &, const RigidConstraintModelVector &,
79  RigidConstraintDataVector &, const Scalar))&compute,
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 "
84  "in\n"
85  "the vector of RigidConstraintModel named contact_models. The decomposition is "
86  "regularized with a factor mu.",
88 
89  .def(
90  "compute",
91  (void (*)(
92  Self & self, const Model &, Data &, const RigidConstraintModelVector &,
93  RigidConstraintDataVector &, const Vector &))&compute,
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 "
98  "in\n"
99  "the vector of RigidConstraintModel named contact_models. The decomposition is "
100  "regularized with a factor mu.",
102 
103  .def(
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.")
108 
109  .def(
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.")
113 
114  .def(
115  "getInverseOperationalSpaceInertiaMatrix",
116  (Matrix(Self::*)(void) const)&Self::getInverseOperationalSpaceInertiaMatrix,
117  bp::arg("self"),
118  "Returns the Inverse of the Operational Space Inertia Matrix resulting from the "
119  "decomposition.",
120  bp::return_value_policy<bp::return_by_value>())
121 
122  .def(
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>())
127 
128  .def(
129  "getInverseMassMatrix", (Matrix(Self::*)(void) const)&Self::getInverseMassMatrix,
130  bp::arg("self"),
131  "Returns the inverse of the Joint Space Inertia Matrix or \"mass matrix\".",
132  bp::return_value_policy<bp::return_by_value>())
133 
134  .def(
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>())
139 
140  .def(
141  "inverse", (Matrix(Self::*)(void) const)&Self::inverse, bp::arg("self"),
142  "Returns the inverse matrix resulting from the decomposition.")
143 
144  .def(
145  "getMassMatrixChoeslkyDecomposition",
146  &Self::template getMassMatrixChoeslkyDecomposition<
148  bp::arg("self"),
149  "Retrieves the Cholesky decomposition of the Mass Matrix contained in the current "
150  "decomposition.")
151 
152  .def(
153  "getDelassusCholeskyExpression", &Self::getDelassusCholeskyExpression, bp::arg("self"),
154  "Returns the Cholesky decomposition expression associated to the underlying "
155  "Delassus matrix.",
156  bp::with_custodian_and_ward_postcall<0, 1>())
157 
159  }
160 
161  static void expose()
162  {
163  bp::class_<ContactCholeskyDecomposition>(
164  "ContactCholeskyDecomposition",
165  "Contact information container for contact dynamic algorithms.", bp::no_init)
168 
169  {
170  typedef typename ContactCholeskyDecomposition::DelassusCholeskyExpression
171  DelassusCholeskyExpression;
172 
173  bp::class_<DelassusCholeskyExpression>(
174  "DelassusCholeskyExpression",
175  "Delassus Cholesky expression associated to a "
176  "given ContactCholeskyDecomposition object.",
177  bp::no_init)
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>()])
182  .def(
183  "cholesky",
184  +[](const DelassusCholeskyExpression & self) -> ContactCholeskyDecomposition & {
185  return const_cast<ContactCholeskyDecomposition &>(self.cholesky());
186  },
187  bp::arg("self"),
188  "Returns the Constraint Cholesky decomposition associated to this "
189  "DelassusCholeskyExpression.",
190  bp::return_internal_reference<>())
192  }
193 
194  {
195 #ifndef PINOCCHIO_PYTHON_SKIP_CASADI_UNSUPPORTED
197  bp::class_<DelassusOperatorDense>(
198  "DelassusOperatorDense", "Delassus Cholesky dense operator from a dense matrix.",
199  bp::no_init)
200  .def(bp::init<const Eigen::Ref<const context::MatrixXs>>(
201  bp::args("self", "matrix"), "Build from a given dense matrix"))
202 
204 #endif // PINOCCHIO_PYTHON_SKIP_CASADI_UNSUPPORTED
205  }
206 
207  {
208 #ifndef PINOCCHIO_PYTHON_SKIP_CASADI_UNSUPPORTED
211  bp::class_<DelassusOperatorSparse, boost::noncopyable>(
212  "DelassusOperatorSparse", "Delassus Cholesky sparse operator from a sparse matrix.",
213  bp::no_init)
214  .def(bp::init<const context::SparseMatrix &>(
215  bp::args("self", "matrix"), "Build from a given sparse matrix"))
216 
218 #endif // PINOCCHIO_PYTHON_SKIP_CASADI_UNSUPPORTED
219  }
220 #ifdef PINOCCHIO_WITH_ACCELERATE_SUPPORT
221  {
222  typedef Eigen::AccelerateLLT<context::SparseMatrix> AccelerateCholeskyDecomposition;
224  context::Scalar, context::Options, AccelerateCholeskyDecomposition>
225  DelassusOperatorSparseAccelerate;
226  bp::class_<DelassusOperatorSparseAccelerate, boost::noncopyable>(
227  "DelassusOperatorSparseAccelerate",
228  "Delassus Cholesky sparse operator leveraging the Accelerate framework on APPLE "
229  "systems.",
230  bp::no_init)
231  .def(bp::init<const context::SparseMatrix &>(
232  bp::args("self", "matrix"), "Build from a given sparse matrix"))
233 
235  }
236 #endif
237  }
238 
239  template<typename MatrixType>
240  static Matrix solve(const Self & self, const MatrixType & mat)
241  {
242  return self.solve(mat);
243  }
244 
245  static void compute(
246  Self & self,
247  const Model & model,
248  Data & data,
249  const RigidConstraintModelVector & contact_models,
250  RigidConstraintDataVector & contact_datas,
251  const Scalar mu = static_cast<Scalar>(0))
252  {
253  self.compute(model, data, contact_models, contact_datas, mu);
254  }
255 
256  static void compute(
257  Self & self,
258  const Model & model,
259  Data & data,
260  const RigidConstraintModelVector & contact_models,
261  RigidConstraintDataVector & contact_datas,
262  const Vector & mus)
263  {
264  self.compute(model, data, contact_models, contact_datas, mus);
265  }
266  };
267 
268  } // namespace python
269 } // namespace pinocchio
270 
271 #endif // ifndef __pinocchio_python_algorithm_contact_cholesky_hpp__
pinocchio::RigidConstraintData
RigidConstraintDataTpl< context::Scalar, context::Options > RigidConstraintData
Definition: algorithm/fwd.hpp:27
init
void init(bool compute_local_aabb=true)
boost::python
pinocchio::DataTpl
Definition: context/generic.hpp:25
contact-cholesky.hpp
delassus-operator-sparse.hpp
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::Self
ContactCholeskyDecomposition Self
Definition: bindings/python/algorithm/contact-cholesky.hpp:33
pinocchio::python::ContactCholeskyDecompositionPythonVisitor
Definition: bindings/python/algorithm/contact-cholesky.hpp:29
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::Model
pinocchio::python::context::Model Model
Definition: bindings/python/algorithm/contact-cholesky.hpp:44
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::Scalar
ContactCholeskyDecomposition::Scalar Scalar
Definition: bindings/python/algorithm/contact-cholesky.hpp:34
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::RigidConstraintData
ContactCholeskyDecomposition::RigidConstraintData RigidConstraintData
Definition: bindings/python/algorithm/contact-cholesky.hpp:36
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::DelassusOperatorSparseTpl
Definition: delassus-operator-sparse.hpp:127
pinocchio::DelassusOperatorSparse
DelassusOperatorSparseTpl< context::Scalar, context::Options > DelassusOperatorSparse
Definition: algorithm/fwd.hpp:36
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::compute
static void compute(Self &self, const Model &model, Data &data, const RigidConstraintModelVector &contact_models, RigidConstraintDataVector &contact_datas, const Vector &mus)
Definition: bindings/python/algorithm/contact-cholesky.hpp:256
pinocchio::python::ComparableVisitor
Add the Python method == and != to allow a comparison of this.
Definition: comparable.hpp:21
def
void def(const char *name, Func func)
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::expose
static void expose()
Definition: bindings/python/algorithm/contact-cholesky.hpp:161
simulation-contact-dynamics.contact_datas
list contact_datas
Definition: simulation-contact-dynamics.py:60
pinocchio::python::context::Options
@ Options
Definition: bindings/python/context/generic.hpp:40
pinocchio::python::DelassusOperatorBasePythonVisitor
Definition: delassus-operator.hpp:18
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::visit
void visit(PyClass &cl) const
Definition: bindings/python/algorithm/contact-cholesky.hpp:48
comparable.hpp
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::Data
pinocchio::python::context::Data Data
Definition: bindings/python/algorithm/contact-cholesky.hpp:45
python
mat
mat
D
D
pinocchio::is_floating_point
Definition: math/fwd.hpp:17
size
FCL_REAL size() const
pinocchio::python::CopyableVisitor
Add the Python method copy to allow a copy of this by calling the copy constructor.
Definition: copyable.hpp:21
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::compute
static void compute(Self &self, const Model &model, Data &data, const RigidConstraintModelVector &contact_models, RigidConstraintDataVector &contact_datas, const Scalar mu=static_cast< Scalar >(0))
Definition: bindings/python/algorithm/contact-cholesky.hpp:245
pinocchio::inverse
void inverse(const Eigen::MatrixBase< MatrixIn > &m_in, const Eigen::MatrixBase< MatrixOut > &dest)
Definition: math/matrix.hpp:273
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR
typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) RigidConstraintModelVector
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::solve
static Matrix solve(const Self &self, const MatrixType &mat)
Definition: bindings/python/algorithm/contact-cholesky.hpp:240
copyable.hpp
pinocchio::python::mimic_not_supported_function
Definition: model-checker.hpp:22
macros.hpp
mu
double mu
Definition: delassus.cpp:58
ocp.U
U
Definition: ocp.py:81
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::Matrix
ContactCholeskyDecomposition::Matrix Matrix
Definition: bindings/python/algorithm/contact-cholesky.hpp:37
delassus-operator-dense.hpp
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::RigidConstraintModel
ContactCholeskyDecomposition::RigidConstraintModel RigidConstraintModel
Definition: bindings/python/algorithm/contact-cholesky.hpp:35
cl
cl
memory.hpp
pinocchio::DelassusOperatorDenseTpl
Definition: delassus-operator-dense.hpp:29
pinocchio::RigidConstraintModel
RigidConstraintModelTpl< context::Scalar, context::Options > RigidConstraintModel
Definition: algorithm/fwd.hpp:24
contact-cholesky.contact_models
list contact_models
Definition: contact-cholesky.py:22
std-vector.hpp
pinocchio::ContactCholeskyDecompositionTpl< context::Scalar, context::Options >
pinocchio::JointCollectionDefaultTpl
Definition: context/generic.hpp:15
model-checker.hpp
Scalar
double Scalar
Definition: timings-cppad-jit.cpp:37
pinocchio::ModelTpl
Definition: context/generic.hpp:20
delassus-operator.hpp
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::Vector
ContactCholeskyDecomposition::Vector Vector
Definition: bindings/python/algorithm/contact-cholesky.hpp:38
pinocchio::python::context::Scalar
PINOCCHIO_PYTHON_SCALAR_TYPE Scalar
Definition: bindings/python/context/generic.hpp:37
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:33
pinocchio::DelassusOperatorDense
DelassusOperatorDenseTpl< context::Scalar, context::Options > DelassusOperatorDense
Definition: algorithm/fwd.hpp:30


pinocchio
Author(s):
autogenerated on Fri Apr 25 2025 02:41:37