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 
18 
20 
21 namespace pinocchio
22 {
23  namespace python
24  {
25  namespace bp = boost::python;
26 
27  template<typename ContactCholeskyDecomposition>
29  : public boost::python::def_visitor<
30  ContactCholeskyDecompositionPythonVisitor<ContactCholeskyDecomposition>>
31  {
36  typedef typename ContactCholeskyDecomposition::Matrix Matrix;
37  typedef typename ContactCholeskyDecomposition::Vector Vector;
39  RigidConstraintModelVector;
41  RigidConstraintDataVector;
42 
45 
46  template<class PyClass>
47  void visit(PyClass & cl) const
48  {
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."))
54 
55  .PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(Self, U, "")
56  .PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(Self, D, "")
57  .PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(Self, Dinv, "")
58 
59  .def("size", &Self::size, bp::arg("self"), "Size of the decomposition.")
60  .def(
61  "constraintDim", &Self::constraintDim, bp::arg("self"),
62  "Returns the total dimension of the constraints contained in the Cholesky "
63  "factorization.")
64  .def(
65  "numContacts", &Self::numContacts, bp::arg("self"),
66  "Returns the number of contacts associated to this decomposition.")
67  .def(
68  "matrix", (Matrix(Self::*)(void) const) & Self::matrix, bp::arg("self"),
69  "Returns the matrix resulting from the decomposition.")
70 
71  .def(
72  "compute",
73  (void (*)(
74  Self & self, const Model &, Data &, const RigidConstraintModelVector &,
75  RigidConstraintDataVector &, const Scalar))
76  & compute,
77  (bp::arg("self"), bp::arg("model"), bp::arg("data"), bp::arg("contact_models"),
78  bp::arg("contact_datas"), bp::arg("mu") = 0),
79  "Computes the Cholesky decompostion of the augmented matrix containing the KKT matrix\n"
80  "related to the system mass matrix and the Jacobians of the contact patches contained "
81  "in\n"
82  "the vector of RigidConstraintModel named contact_models. The decomposition is "
83  "regularized with a factor mu.")
84 
85  .def(
86  "compute",
87  (void (*)(
88  Self & self, const Model &, Data &, const RigidConstraintModelVector &,
89  RigidConstraintDataVector &, const Vector &))
90  & compute,
91  (bp::arg("self"), bp::arg("model"), bp::arg("data"), bp::arg("contact_models"),
92  bp::arg("contact_datas"), bp::arg("mus")),
93  "Computes the Cholesky decompostion of the augmented matrix containing the KKT matrix\n"
94  "related to the system mass matrix and the Jacobians of the contact patches contained "
95  "in\n"
96  "the vector of RigidConstraintModel named contact_models. The decomposition is "
97  "regularized with a factor mu.")
98 
99  .def(
100  "updateDamping", (void(Self::*)(const Scalar &)) & Self::updateDamping,
101  bp::args("self", "mu"),
102  "Update the damping term on the upper left block part of the KKT matrix. The "
103  "damping term should be positive.")
104 
105  .def(
106  "updateDamping", &Self::template updateDamping<Vector>, bp::args("self", "mus"),
107  "Update the damping terms on the upper left block part of the KKT matrix. The "
108  "damping terms should be all positives.")
109 
110  .def(
111  "getInverseOperationalSpaceInertiaMatrix",
112  (Matrix(Self::*)(void) const) & Self::getInverseOperationalSpaceInertiaMatrix,
113  bp::arg("self"),
114  "Returns the Inverse of the Operational Space Inertia Matrix resulting from the "
115  "decomposition.",
116  bp::return_value_policy<bp::return_by_value>())
117 
118  .def(
119  "getOperationalSpaceInertiaMatrix",
120  (Matrix(Self::*)(void) const) & Self::getOperationalSpaceInertiaMatrix, bp::arg("self"),
121  "Returns the Operational Space Inertia Matrix resulting from the decomposition.",
122  bp::return_value_policy<bp::return_by_value>())
123 
124  .def(
125  "getInverseMassMatrix", (Matrix(Self::*)(void) const) & Self::getInverseMassMatrix,
126  bp::arg("self"),
127  "Returns the inverse of the Joint Space Inertia Matrix or \"mass matrix\".",
128  bp::return_value_policy<bp::return_by_value>())
129 
130  .def(
131  "solve", &solve<Matrix>, bp::args("self", "matrix"),
132  "Computes the solution of \f$ A x = b \f$ where self corresponds to the Cholesky "
133  "decomposition of A.",
134  bp::return_value_policy<bp::return_by_value>())
135 
136  .def(
137  "inverse", (Matrix(Self::*)(void) const) & Self::inverse, bp::arg("self"),
138  "Returns the inverse matrix resulting from the decomposition.")
139 
140  .def(
141  "getMassMatrixChoeslkyDecomposition",
142  &Self::template getMassMatrixChoeslkyDecomposition<
144  bp::arg("self"),
145  "Retrieves the Cholesky decomposition of the Mass Matrix contained in the current "
146  "decomposition.")
147 
148  .def(
149  "getDelassusCholeskyExpression", &Self::getDelassusCholeskyExpression, bp::arg("self"),
150  "Returns the Cholesky decomposition expression associated to the underlying "
151  "Delassus matrix.",
152  bp::with_custodian_and_ward_postcall<0, 1>())
153 
155  }
156 
157  static void expose()
158  {
159  bp::class_<ContactCholeskyDecomposition>(
160  "ContactCholeskyDecomposition",
161  "Contact information container for contact dynamic algorithms.", bp::no_init)
164 
165  {
166  typedef typename ContactCholeskyDecomposition::DelassusCholeskyExpression
167  DelassusCholeskyExpression;
168 
169  bp::class_<DelassusCholeskyExpression>(
170  "DelassusCholeskyExpression",
171  "Delassus Cholesky expression associated to a "
172  "given ContactCholeskyDecomposition object.",
173  bp::no_init)
174  .def(bp::init<const ContactCholeskyDecomposition &>(
175  bp::args("self", "cholesky_decomposition"),
176  "Build from a given ContactCholeskyDecomposition object.")
177  [bp::with_custodian_and_ward<1, 2>()])
178  .def(
179  "cholesky",
180  +[](const DelassusCholeskyExpression & self) -> ContactCholeskyDecomposition & {
181  return const_cast<ContactCholeskyDecomposition &>(self.cholesky());
182  },
183  bp::arg("self"),
184  "Returns the Constraint Cholesky decomposition associated to this "
185  "DelassusCholeskyExpression.",
186  bp::return_internal_reference<>())
187 
189  }
190 
191  {
193  bp::class_<DelassusOperatorDense>(
194  "DelassusOperatorDense", "Delassus Cholesky dense operator from a dense matrix.",
195  bp::no_init)
196  .def(bp::init<const Eigen::Ref<const context::MatrixXs>>(
197  bp::args("self", "matrix"), "Build from a given dense matrix"))
198 
200  }
201 
202  {
205  bp::class_<DelassusOperatorSparse, boost::noncopyable>(
206  "DelassusOperatorSparse", "Delassus Cholesky sparse operator from a sparse matrix.",
207  bp::no_init)
208  .def(bp::init<const context::SparseMatrix &>(
209  bp::args("self", "matrix"), "Build from a given sparse matrix"))
210 
212  }
213 #ifdef PINOCCHIO_WITH_ACCELERATE_SUPPORT
214  {
215  typedef Eigen::AccelerateLLT<context::SparseMatrix> AccelerateCholeskyDecomposition;
217  context::Scalar, context::Options, AccelerateCholeskyDecomposition>
218  DelassusOperatorSparseAccelerate;
219  bp::class_<DelassusOperatorSparseAccelerate, boost::noncopyable>(
220  "DelassusOperatorSparseAccelerate",
221  "Delassus Cholesky sparse operator leveraging the Accelerate framework on APPLE "
222  "systems.",
223  bp::no_init)
224  .def(bp::init<const context::SparseMatrix &>(
225  bp::args("self", "matrix"), "Build from a given sparse matrix"))
226 
228  }
229 #endif
230  }
231 
232  template<typename MatrixType>
233  static Matrix solve(const Self & self, const MatrixType & mat)
234  {
235  return self.solve(mat);
236  }
237 
238  static void compute(
239  Self & self,
240  const Model & model,
241  Data & data,
242  const RigidConstraintModelVector & contact_models,
243  RigidConstraintDataVector & contact_datas,
244  const Scalar mu = static_cast<Scalar>(0))
245  {
246  self.compute(model, data, contact_models, contact_datas, mu);
247  }
248 
249  static void compute(
250  Self & self,
251  const Model & model,
252  Data & data,
253  const RigidConstraintModelVector & contact_models,
254  RigidConstraintDataVector & contact_datas,
255  const Vector & mus)
256  {
257  self.compute(model, data, contact_models, contact_datas, mus);
258  }
259  };
260 
261  } // namespace python
262 } // namespace pinocchio
263 
264 #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:32
pinocchio::python::ContactCholeskyDecompositionPythonVisitor
Definition: bindings/python/algorithm/contact-cholesky.hpp:28
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::Model
pinocchio::python::context::Model Model
Definition: bindings/python/algorithm/contact-cholesky.hpp:43
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::Scalar
ContactCholeskyDecomposition::Scalar Scalar
Definition: bindings/python/algorithm/contact-cholesky.hpp:33
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::RigidConstraintData
ContactCholeskyDecomposition::RigidConstraintData RigidConstraintData
Definition: bindings/python/algorithm/contact-cholesky.hpp:35
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::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
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:249
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:157
simulation-contact-dynamics.contact_datas
list contact_datas
Definition: simulation-contact-dynamics.py:65
pinocchio::python::DelassusOperatorBasePythonVisitor
Definition: delassus-operator.hpp:18
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::visit
void visit(PyClass &cl) const
Definition: bindings/python/algorithm/contact-cholesky.hpp:47
comparable.hpp
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::Data
pinocchio::python::context::Data Data
Definition: bindings/python/algorithm/contact-cholesky.hpp:44
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:238
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:233
copyable.hpp
pinocchio::python::context::Options
@ Options
Definition: bindings/python/context/generic.hpp:40
macros.hpp
mu
double mu
Definition: delassus.cpp:58
ocp.U
U
Definition: ocp.py:61
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::Matrix
ContactCholeskyDecomposition::Matrix Matrix
Definition: bindings/python/algorithm/contact-cholesky.hpp:36
delassus-operator-dense.hpp
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::RigidConstraintModel
ContactCholeskyDecomposition::RigidConstraintModel RigidConstraintModel
Definition: bindings/python/algorithm/contact-cholesky.hpp:34
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:25
std-vector.hpp
pinocchio::ContactCholeskyDecompositionTpl< context::Scalar, context::Options >
pinocchio::JointCollectionDefaultTpl
Definition: context/generic.hpp:15
pinocchio::ModelTpl
Definition: context/generic.hpp:20
delassus-operator.hpp
pinocchio::python::ContactCholeskyDecompositionPythonVisitor::Vector
ContactCholeskyDecomposition::Vector Vector
Definition: bindings/python/algorithm/contact-cholesky.hpp:37
pinocchio::python::context::Scalar
PINOCCHIO_PYTHON_SCALAR_TYPE Scalar
Definition: bindings/python/context/generic.hpp:37
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::DelassusOperatorDense
DelassusOperatorDenseTpl< context::Scalar, context::Options > DelassusOperatorDense
Definition: algorithm/fwd.hpp:30


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:36