GCC Code Coverage Report


Directory: ./
File: bindings/python/algorithm/expose-constrained-dynamics.cpp
Date: 2025-04-30 16:14:33
Exec Total Coverage
Lines: 22 27 81.5%
Branches: 17 32 53.1%

Line Branch Exec Source
1 //
2 // Copyright (c) 2020-2021 INRIA
3 //
4
5 #include "pinocchio/bindings/python/algorithm/algorithms.hpp"
6 #include "pinocchio/bindings/python/algorithm/contact-info.hpp"
7 #include "pinocchio/bindings/python/algorithm/proximal.hpp"
8 #include "pinocchio/bindings/python/algorithm/contact-cholesky.hpp"
9
10 #include "pinocchio/bindings/python/utils/std-vector.hpp"
11 #include "pinocchio/bindings/python/utils/registration.hpp"
12 #include "pinocchio/bindings/python/utils/model-checker.hpp"
13
14 #include "pinocchio/algorithm/constrained-dynamics.hpp"
15
16 namespace bp = boost::python;
17
18 namespace pinocchio
19 {
20 namespace python
21 {
22
23 typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(context::RigidConstraintModel)
24 RigidConstraintModelVector;
25 typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(context::RigidConstraintData)
26 RigidConstraintDataVector;
27
28 static const context::VectorXs constraintDynamics_proxy(
29 const context::Model & model,
30 context::Data & data,
31 const context::VectorXs & q,
32 const context::VectorXs & v,
33 const context::VectorXs & tau,
34 const RigidConstraintModelVector & contact_models,
35 RigidConstraintDataVector & contact_datas,
36 context::ProximalSettings & prox_settings)
37 {
38 return constraintDynamics(
39 model, data, q, v, tau, contact_models, contact_datas, prox_settings);
40 }
41
42 static const context::VectorXs constraintDynamics_proxy_default(
43 const context::Model & model,
44 context::Data & data,
45 const context::VectorXs & q,
46 const context::VectorXs & v,
47 const context::VectorXs & tau,
48 const RigidConstraintModelVector & contact_models,
49 RigidConstraintDataVector & contact_datas)
50 {
51 return constraintDynamics(model, data, q, v, tau, contact_models, contact_datas);
52 }
53
54 72 void exposeConstraintDynamics()
55 {
56 using namespace Eigen;
57
58 // Expose type of contacts
59
2/2
✓ Branch 1 taken 68 times.
✓ Branch 2 taken 4 times.
72 if (!register_symbolic_link_to_registered_type<ContactType>())
60 {
61 136 bp::enum_<ContactType>("ContactType")
62
1/2
✓ Branch 1 taken 68 times.
✗ Branch 2 not taken.
68 .value("CONTACT_3D", CONTACT_3D)
63
1/2
✓ Branch 1 taken 68 times.
✗ Branch 2 not taken.
68 .value("CONTACT_6D", CONTACT_6D)
64
1/2
✓ Branch 1 taken 68 times.
✗ Branch 2 not taken.
68 .value("CONTACT_UNDEFINED", CONTACT_UNDEFINED);
65 }
66
67 72 ProximalSettingsPythonVisitor<context::ProximalSettings>::expose();
68
69 72 RigidConstraintModelPythonVisitor<context::RigidConstraintModel>::expose();
70 72 RigidConstraintDataPythonVisitor<context::RigidConstraintData>::expose();
71
72
3/6
✓ Branch 2 taken 72 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 72 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 72 times.
✗ Branch 10 not taken.
72 StdVectorPythonVisitor<RigidConstraintModelVector>::expose("StdVec_RigidConstraintModel");
73
74
3/6
✓ Branch 2 taken 72 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 72 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 72 times.
✗ Branch 10 not taken.
72 StdVectorPythonVisitor<RigidConstraintDataVector>::expose("StdVec_RigidConstraintData");
75
76 72 ContactCholeskyDecompositionPythonVisitor<context::ContactCholeskyDecomposition>::expose();
77
78
1/2
✓ Branch 1 taken 72 times.
✗ Branch 2 not taken.
72 bp::def(
79 "initConstraintDynamics",
80 &initConstraintDynamics<
81 context::Scalar, context::Options, JointCollectionDefaultTpl,
82 typename RigidConstraintModelVector::allocator_type>,
83
1/2
✓ Branch 1 taken 72 times.
✗ Branch 2 not taken.
144 bp::args("model", "data", "contact_models"),
84 "This function allows to allocate the memory before hand for contact dynamics algorithms.\n"
85 "This allows to avoid online memory allocation when running these algorithms.",
86 72 mimic_not_supported_function<>(0));
87
88
1/2
✓ Branch 1 taken 72 times.
✗ Branch 2 not taken.
72 bp::def(
89 "constraintDynamics", constraintDynamics_proxy,
90
1/2
✓ Branch 1 taken 72 times.
✗ Branch 2 not taken.
144 bp::args(
91 "model", "data", "q", "v", "tau", "contact_models", "contact_datas", "prox_settings"),
92 "Computes the forward dynamics with contact constraints according to a given list of "
93 "Contact information.\n"
94 "When using constraintDynamics for the first time, you should call first "
95 "initConstraintDynamics to initialize the internal memory used in the algorithm.\n"
96 "This function returns joint acceleration of the system. The contact forces are "
97 "stored in the list data.contact_forces.",
98 72 mimic_not_supported_function<>(0));
99
100
1/2
✓ Branch 1 taken 72 times.
✗ Branch 2 not taken.
72 bp::def(
101 "constraintDynamics", constraintDynamics_proxy_default,
102
1/2
✓ Branch 1 taken 72 times.
✗ Branch 2 not taken.
144 bp::args("model", "data", "q", "v", "tau", "contact_models", "contact_datas"),
103 "Computes the forward dynamics with contact constraints according to a given list of "
104 "Contact information.\n"
105 "When using constraintDynamics for the first time, you should call first "
106 "initConstraintDynamics to initialize the internal memory used in the algorithm.\n"
107 "This function returns joint acceleration of the system. The contact forces are "
108 "stored in the list data.contact_forces.",
109 72 mimic_not_supported_function<>(0));
110 72 }
111 } // namespace python
112 } // namespace pinocchio
113