Directory: | ./ |
---|---|
File: | bindings/python/crocoddyl/multibody/actions/contact-invdyn.cpp |
Date: | 2025-03-26 19:23:43 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 45 | 45 | 100.0% |
Branches: | 133 | 266 | 50.0% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | /////////////////////////////////////////////////////////////////////////////// | ||
2 | // BSD 3-Clause License | ||
3 | // | ||
4 | // Copyright (C) 2021-2025, University of Edinburgh, Heriot-Watt University | ||
5 | // Copyright note valid unless otherwise stated in individual files. | ||
6 | // All rights reserved. | ||
7 | /////////////////////////////////////////////////////////////////////////////// | ||
8 | |||
9 | #include "crocoddyl/multibody/actions/contact-invdyn.hpp" | ||
10 | |||
11 | #include "python/crocoddyl/core/diff-action-base.hpp" | ||
12 | #include "python/crocoddyl/multibody/multibody.hpp" | ||
13 | |||
14 | namespace crocoddyl { | ||
15 | namespace python { | ||
16 | |||
17 | template <typename Model> | ||
18 | struct DifferentialActionModelContactInvDynamicsVisitor | ||
19 | : public bp::def_visitor< | ||
20 | DifferentialActionModelContactInvDynamicsVisitor<Model>> { | ||
21 | typedef typename Model::DifferentialActionDataAbstract Data; | ||
22 | typedef typename Model::VectorXs VectorXs; | ||
23 | template <class PyClass> | ||
24 | 40 | void visit(PyClass& cl) const { | |
25 | 40 | cl.def("calc", | |
26 | static_cast<void (Model::*)( | ||
27 | const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, | ||
28 | const Eigen::Ref<const VectorXs>&)>(&Model::calc), | ||
29 | bp::args("self", "data", "x", "u"), | ||
30 | "Compute the next state, cost value and constraints.\n\n" | ||
31 | ":param data: contact inverse-dynamics data\n" | ||
32 | ":param x: state point (dim. state.nx)\n" | ||
33 | ":param u: control input (dim. nu)") | ||
34 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("calc", |
35 | static_cast<void (Model::*)(const std::shared_ptr<Data>&, | ||
36 | const Eigen::Ref<const VectorXs>&)>( | ||
37 | &Model::calc), | ||
38 | bp::args("self", "data", "x")) | ||
39 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def( |
40 | "calcDiff", | ||
41 | static_cast<void (Model::*)( | ||
42 | const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, | ||
43 | const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff), | ||
44 | bp::args("self", "data", "x", "u"), | ||
45 | "Compute the derivatives of the differential multibody system, and " | ||
46 | "its cost and constraint functions.\n\n" | ||
47 | "It computes the partial derivatives of the differential multibody " | ||
48 | "system, the cost and constraint functions. It assumes that calc " | ||
49 | "has been run first. This function builds a quadratic " | ||
50 | "approximation of the action model (i.e., dynamical system, cost " | ||
51 | "and constraint functions).\n" | ||
52 | ":param data: contact inverse-dynamics data\n" | ||
53 | ":param x: state point (dim. state.nx)\n" | ||
54 | ":param u: control input (dim. nu)") | ||
55 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("calcDiff", |
56 | static_cast<void (Model::*)(const std::shared_ptr<Data>&, | ||
57 | const Eigen::Ref<const VectorXs>&)>( | ||
58 | &Model::calcDiff), | ||
59 | bp::args("self", "data", "x")) | ||
60 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("createData", &Model::createData, bp::args("self"), |
61 | "Create the contact inverse-dynamics differential action data.") | ||
62 |
3/6✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
|
40 | .add_property( |
63 | "actuation", | ||
64 | bp::make_function(&Model::get_actuation, | ||
65 | 40 | bp::return_value_policy<bp::return_by_value>()), | |
66 | "actuation model") | ||
67 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
40 | .add_property( |
68 | "contacts", | ||
69 | bp::make_function(&Model::get_contacts, | ||
70 | 40 | bp::return_value_policy<bp::return_by_value>()), | |
71 | "multiple contact model") | ||
72 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
40 | .add_property( |
73 | "costs", | ||
74 | bp::make_function(&Model::get_costs, | ||
75 | 40 | bp::return_value_policy<bp::return_by_value>()), | |
76 | "total cost model") | ||
77 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
40 | .add_property( |
78 | "constraints", | ||
79 | bp::make_function(&Model::get_constraints, | ||
80 | 40 | bp::return_value_policy<bp::return_by_value>()), | |
81 | "constraint model manager"); | ||
82 | 40 | } | |
83 | }; | ||
84 | |||
85 | template <typename Model> | ||
86 | struct DifferentialActionModelContactInvDynamicsResidualModelActuationVisitor | ||
87 | : public bp::def_visitor< | ||
88 | DifferentialActionModelContactInvDynamicsResidualModelActuationVisitor< | ||
89 | Model>> { | ||
90 | typedef typename Model::ResidualDataAbstract Data; | ||
91 | typedef typename Model::VectorXs VectorXs; | ||
92 | template <class PyClass> | ||
93 | 40 | void visit(PyClass& cl) const { | |
94 | 40 | cl.def("calc", | |
95 | static_cast<void (Model::*)( | ||
96 | const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, | ||
97 | const Eigen::Ref<const VectorXs>&)>(&Model::calc), | ||
98 | bp::args("self", "data", "x", "u"), | ||
99 | "Compute the actuation residual.\n\n" | ||
100 | ":param data: residual data\n" | ||
101 | ":param x: state point (dim. state.nx)\n" | ||
102 | ":param u: control input (dim. nu)") | ||
103 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("calc", |
104 | static_cast<void (Model::*)(const std::shared_ptr<Data>&, | ||
105 | const Eigen::Ref<const VectorXs>&)>( | ||
106 | &Model::calc), | ||
107 | bp::args("self", "data", "x")) | ||
108 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def( |
109 | "calcDiff", | ||
110 | static_cast<void (Model::*)( | ||
111 | const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, | ||
112 | const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff), | ||
113 | bp::args("self", "data", "x", "u"), | ||
114 | "Compute the Jacobians of the actuation residual.\n\n" | ||
115 | "It assumes that calc has been run first.\n" | ||
116 | ":param data: action data\n" | ||
117 | ":param x: state point (dim. state.nx)\n" | ||
118 | ":param u: control input (dim. nu)\n") | ||
119 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("calcDiff", |
120 | static_cast<void (Model::*)(const std::shared_ptr<Data>&, | ||
121 | const Eigen::Ref<const VectorXs>&)>( | ||
122 | &Model::calcDiff), | ||
123 | bp::args("self", "data", "x")) | ||
124 |
3/6✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
|
80 | .def("createData", &Model::createData, |
125 | 40 | bp::with_custodian_and_ward_postcall<0, 2>(), | |
126 | bp::args("self", "data"), | ||
127 | "Create the actuation residual data.\n\n" | ||
128 | "Each residual model has its own data that needs to be allocated. " | ||
129 | "This function returns the allocated data for the actuation " | ||
130 | "residual.\n" | ||
131 | ":param data: shared data\n" | ||
132 | ":return residual data."); | ||
133 | 40 | } | |
134 | }; | ||
135 | |||
136 | template <typename Model> | ||
137 | struct DifferentialActionModelContactInvDynamicsResidualModelContactVisitor | ||
138 | : public bp::def_visitor< | ||
139 | DifferentialActionModelContactInvDynamicsResidualModelContactVisitor< | ||
140 | Model>> { | ||
141 | typedef typename Model::ResidualDataAbstract Data; | ||
142 | typedef typename Model::VectorXs VectorXs; | ||
143 | template <class PyClass> | ||
144 | 40 | void visit(PyClass& cl) const { | |
145 | 40 | cl.def("calc", | |
146 | static_cast<void (Model::*)( | ||
147 | const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, | ||
148 | const Eigen::Ref<const VectorXs>&)>(&Model::calc), | ||
149 | bp::args("self", "data", "x", "u"), | ||
150 | "Compute the contact-acceleration residual.\n\n" | ||
151 | ":param data: residual data\n" | ||
152 | ":param x: state vector\n" | ||
153 | ":param u: control input") | ||
154 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("calc", |
155 | static_cast<void (Model::*)(const std::shared_ptr<Data>&, | ||
156 | const Eigen::Ref<const VectorXs>&)>( | ||
157 | &Model::calc), | ||
158 | bp::args("self", "data", "x")) | ||
159 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def( |
160 | "calcDiff", | ||
161 | static_cast<void (Model::*)( | ||
162 | const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, | ||
163 | const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff), | ||
164 | bp::args("self", "data", "x", "u"), | ||
165 | "Compute the Jacobians of the contact-acceleration residual.\n\n" | ||
166 | "It assumes that calc has been run first.\n" | ||
167 | ":param data: action data\n" | ||
168 | ":param x: state vector\n" | ||
169 | ":param u: control input\n") | ||
170 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("calcDiff", |
171 | static_cast<void (Model::*)(const std::shared_ptr<Data>&, | ||
172 | const Eigen::Ref<const VectorXs>&)>( | ||
173 | &Model::calcDiff), | ||
174 | bp::args("self", "data", "x")) | ||
175 |
3/6✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
|
80 | .def("createData", &Model::createData, |
176 | 40 | bp::with_custodian_and_ward_postcall<0, 2>(), | |
177 | bp::args("self", "data"), | ||
178 | "Create the contact-acceleration residual data.\n\n" | ||
179 | "Each residual model has its own data that needs to be allocated. " | ||
180 | "This function returns the allocated data for the " | ||
181 | "contact-acceleration residual.\n" | ||
182 | ":param data: shared data\n" | ||
183 | ":return residual data."); | ||
184 | 40 | } | |
185 | }; | ||
186 | |||
187 | template <typename Data> | ||
188 | struct DifferentialActionDataContactInvDynamicsVisitor | ||
189 | : public bp::def_visitor< | ||
190 | DifferentialActionDataContactInvDynamicsVisitor<Data>> { | ||
191 | template <class PyClass> | ||
192 | 40 | void visit(PyClass& cl) const { | |
193 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
40 | cl.add_property( |
194 | "pinocchio", | ||
195 | 40 | bp::make_getter(&Data::pinocchio, bp::return_internal_reference<>()), | |
196 | "pinocchio data") | ||
197 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
40 | .add_property("multibody", |
198 | bp::make_getter(&Data::multibody, | ||
199 | 40 | bp::return_internal_reference<>()), | |
200 | "multibody data") | ||
201 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
40 | .add_property( |
202 | "costs", | ||
203 | bp::make_getter(&Data::costs, | ||
204 | 40 | bp::return_value_policy<bp::return_by_value>()), | |
205 | "total cost data") | ||
206 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
40 | .add_property( |
207 | "constraints", | ||
208 | bp::make_getter(&Data::constraints, | ||
209 | 40 | bp::return_value_policy<bp::return_by_value>()), | |
210 | "constraint data"); | ||
211 | 40 | } | |
212 | }; | ||
213 | |||
214 | #define CROCODDYL_ACTION_MODEL_CONTACT_INVDYN_PYTHON_BINDINGS(Scalar) \ | ||
215 | typedef DifferentialActionModelContactInvDynamicsTpl<Scalar> Model; \ | ||
216 | typedef DifferentialActionModelAbstractTpl<Scalar> ModelBase; \ | ||
217 | typedef typename Model::StateMultibody State; \ | ||
218 | typedef typename Model::ActuationModelAbstract Actuation; \ | ||
219 | typedef typename Model::ContactModelMultiple Contacts; \ | ||
220 | typedef typename Model::CostModelSum Costs; \ | ||
221 | typedef typename Model::ConstraintModelManager Constraints; \ | ||
222 | bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ | ||
223 | bp::scope model_outer = \ | ||
224 | bp::class_<Model, bp::bases<ModelBase>>( \ | ||
225 | "DifferentialActionModelContactInvDynamics", \ | ||
226 | "Differential action model for inverse dynamics in multibody " \ | ||
227 | "systems with contacts.\n\n" \ | ||
228 | "This class implements forward kinematic with holonomic contact " \ | ||
229 | "constraints (defined at the acceleration level) and " \ | ||
230 | "inverse-dynamics computation using the Recursive Newton Euler " \ | ||
231 | "Algorithm (RNEA). On the other hand, the stack of cost and " \ | ||
232 | "constraint functions are implemented in ConstraintModelManager() " \ | ||
233 | "and CostModelSum(), respectively.", \ | ||
234 | bp::init<std::shared_ptr<State>, std::shared_ptr<Actuation>, \ | ||
235 | std::shared_ptr<Contacts>, std::shared_ptr<Costs>, \ | ||
236 | bp::optional<std::shared_ptr<Constraints>>>( \ | ||
237 | bp::args("self", "state", "actuation", "contacts", "costs", \ | ||
238 | "constraints"), \ | ||
239 | "Initialize the inverse-dynamics action model for system with " \ | ||
240 | "contact.\n\n" \ | ||
241 | "It describes the kinematic evolution of the multibody system " \ | ||
242 | "with contacts, and computes the needed torques using " \ | ||
243 | "inverse-dynamics.\n." \ | ||
244 | ":param state: multibody state\n" \ | ||
245 | ":param actuation: abstract actuation model\n" \ | ||
246 | ":param contacts: stack of contact model\n" \ | ||
247 | ":param costs: stack of cost functions\n" \ | ||
248 | ":param constraints: stack of constraint functions")) \ | ||
249 | .def(DifferentialActionModelContactInvDynamicsVisitor<Model>()) \ | ||
250 | .def(CastVisitor<Model>()) \ | ||
251 | .def(PrintableVisitor<Model>()) \ | ||
252 | .def(CopyableVisitor<Model>()); \ | ||
253 | typedef typename Model::ResidualModelActuation ResidualModelActuation; \ | ||
254 | typedef typename ResidualModelActuation::Base ResidualModelBase; \ | ||
255 | bp::register_ptr_to_python<std::shared_ptr<ResidualModelActuation>>(); \ | ||
256 | bp::class_<ResidualModelActuation, bp::bases<ResidualModelBase>>( \ | ||
257 | "ResidualModelActuation", \ | ||
258 | "This residual function enforces the torques of under-actuated joints " \ | ||
259 | "(e.g., floating-base joints) to be zero. We compute these torques and " \ | ||
260 | "their derivatives using RNEA inside " \ | ||
261 | "DifferentialActionModelContactInvDynamics.", \ | ||
262 | bp::init<std::shared_ptr<State>, std::size_t, std::size_t>( \ | ||
263 | bp::args("self", "state", "nu", "nc"), \ | ||
264 | "Initialize the actuation residual model.\n\n" \ | ||
265 | ":param nu: dimension of control vector\n" \ | ||
266 | ":param nc: number of the contacts")) \ | ||
267 | .def( \ | ||
268 | DifferentialActionModelContactInvDynamicsResidualModelActuationVisitor< \ | ||
269 | ResidualModelActuation>()) \ | ||
270 | .def(CopyableVisitor<ResidualModelActuation>()); \ | ||
271 | typedef typename Model::ResidualModelContact ResidualModelContact; \ | ||
272 | bp::register_ptr_to_python<std::shared_ptr<ResidualModelContact>>(); \ | ||
273 | bp::class_<ResidualModelContact, bp::bases<ResidualModelBase>>( \ | ||
274 | "ResidualModelContact", \ | ||
275 | "This residual function for the contact acceleration, i.e., r = a0, " \ | ||
276 | "where a0 is the desired contact acceleration which also considers the " \ | ||
277 | "Baumgarte stabilization.", \ | ||
278 | bp::init<std::shared_ptr<State>, pinocchio::FrameIndex, std::size_t, \ | ||
279 | std::size_t>( \ | ||
280 | bp::args("self", "state", "id", "nr", "nc"), \ | ||
281 | "Initialize the contact-acceleration residual model.\n\n" \ | ||
282 | ":param id: contact id\n" \ | ||
283 | ":param nr: dimension of contact residual\n" \ | ||
284 | ":param nc: dimension of contact vector")) \ | ||
285 | .def( \ | ||
286 | DifferentialActionModelContactInvDynamicsResidualModelContactVisitor< \ | ||
287 | ResidualModelContact>()) \ | ||
288 | .def(CopyableVisitor<ResidualModelContact>()); | ||
289 | |||
290 | #define CROCODDYL_ACTION_DATA_CONTACT_INVDYN_PYTHON_BINDINGS(Scalar) \ | ||
291 | typedef DifferentialActionDataContactInvDynamicsTpl<Scalar> Data; \ | ||
292 | typedef DifferentialActionDataAbstractTpl<Scalar> DataBase; \ | ||
293 | typedef DifferentialActionModelContactInvDynamicsTpl<Scalar> Model; \ | ||
294 | bp::register_ptr_to_python<std::shared_ptr<Data>>(); \ | ||
295 | bp::scope data_outer = \ | ||
296 | bp::class_<Data, bp::bases<DataBase>>( \ | ||
297 | "DifferentialActionDataContactInvDynamics", \ | ||
298 | "Differential action data for the inverse-dynamics for system with " \ | ||
299 | "contact.", \ | ||
300 | bp::init<Model*>( \ | ||
301 | bp::args("self", "model"), \ | ||
302 | "Create inverse-dynamics action data for system with " \ | ||
303 | "contacts.\n\n" \ | ||
304 | ":param model: contact inverse-dynamics action model")) \ | ||
305 | .def(DifferentialActionDataContactInvDynamicsVisitor<Data>()) \ | ||
306 | .def(CopyableVisitor<Data>()); \ | ||
307 | typedef typename Model::ResidualModelActuation ResidualModelActuation; \ | ||
308 | typedef typename Data::ResidualDataActuation ResidualDataActuation; \ | ||
309 | typedef typename ResidualDataActuation::Base ResidualDataBase; \ | ||
310 | typedef \ | ||
311 | typename ResidualModelActuation::DataCollectorAbstract DataCollector; \ | ||
312 | bp::register_ptr_to_python<std::shared_ptr<ResidualDataActuation>>(); \ | ||
313 | bp::class_<ResidualDataActuation, bp::bases<ResidualDataBase>>( \ | ||
314 | "ResidualDataActuation", "Data for actuation residual.\n\n", \ | ||
315 | bp::init<ResidualModelActuation*, DataCollector*>( \ | ||
316 | bp::args("self", "model", "data"), \ | ||
317 | "Create actuation residual data.\n\n" \ | ||
318 | ":param model: actuation residual model\n" \ | ||
319 | ":param data: shared data")[bp::with_custodian_and_ward< \ | ||
320 | 1, 2, bp::with_custodian_and_ward<1, 3>>()]) \ | ||
321 | .def(CopyableVisitor<ResidualDataActuation>()); \ | ||
322 | typedef typename Model::ResidualModelContact ResidualModelContact; \ | ||
323 | typedef typename Data::ResidualDataContact ResidualDataContact; \ | ||
324 | bp::register_ptr_to_python<std::shared_ptr<ResidualDataContact>>(); \ | ||
325 | bp::class_<ResidualDataContact, bp::bases<ResidualDataBase>>( \ | ||
326 | "ResidualDataContact", "Data for contact acceleration residual.\n\n", \ | ||
327 | bp::init<ResidualModelContact*, DataCollector*, std::size_t>( \ | ||
328 | bp::args("self", "model", "data", "id"), \ | ||
329 | "Create contact-acceleration residual data.\n\n" \ | ||
330 | ":param model: contact-acceleration residual model\n" \ | ||
331 | ":param data: shared data\n" \ | ||
332 | ":param id: contact id")[bp::with_custodian_and_ward< \ | ||
333 | 1, 2, bp::with_custodian_and_ward<1, 3>>()]) \ | ||
334 | .add_property( \ | ||
335 | "contact", \ | ||
336 | bp::make_getter(&ResidualDataContact::contact, \ | ||
337 | bp::return_value_policy<bp::return_by_value>()), \ | ||
338 | "contact data associated with the current residual") \ | ||
339 | .def(CopyableVisitor<ResidualDataContact>()); | ||
340 | |||
341 | 10 | void exposeDifferentialActionContactInvDynamics() { | |
342 |
45/90✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 10 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 10 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 10 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 10 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 10 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 10 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 10 times.
✗ Branch 26 not taken.
✓ Branch 30 taken 10 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 10 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 10 times.
✗ Branch 37 not taken.
✓ Branch 39 taken 10 times.
✗ Branch 40 not taken.
✓ Branch 42 taken 10 times.
✗ Branch 43 not taken.
✓ Branch 45 taken 10 times.
✗ Branch 46 not taken.
✓ Branch 50 taken 10 times.
✗ Branch 51 not taken.
✓ Branch 53 taken 10 times.
✗ Branch 54 not taken.
✓ Branch 56 taken 10 times.
✗ Branch 57 not taken.
✓ Branch 59 taken 10 times.
✗ Branch 60 not taken.
✓ Branch 62 taken 10 times.
✗ Branch 63 not taken.
✓ Branch 65 taken 10 times.
✗ Branch 66 not taken.
✓ Branch 72 taken 10 times.
✗ Branch 73 not taken.
✓ Branch 75 taken 10 times.
✗ Branch 76 not taken.
✓ Branch 78 taken 10 times.
✗ Branch 79 not taken.
✓ Branch 83 taken 10 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 10 times.
✗ Branch 87 not taken.
✓ Branch 89 taken 10 times.
✗ Branch 90 not taken.
✓ Branch 92 taken 10 times.
✗ Branch 93 not taken.
✓ Branch 95 taken 10 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 10 times.
✗ Branch 99 not taken.
✓ Branch 101 taken 10 times.
✗ Branch 102 not taken.
✓ Branch 104 taken 10 times.
✗ Branch 105 not taken.
✓ Branch 107 taken 10 times.
✗ Branch 108 not taken.
✓ Branch 112 taken 10 times.
✗ Branch 113 not taken.
✓ Branch 115 taken 10 times.
✗ Branch 116 not taken.
✓ Branch 118 taken 10 times.
✗ Branch 119 not taken.
✓ Branch 121 taken 10 times.
✗ Branch 122 not taken.
✓ Branch 124 taken 10 times.
✗ Branch 125 not taken.
✓ Branch 127 taken 10 times.
✗ Branch 128 not taken.
✓ Branch 132 taken 10 times.
✗ Branch 133 not taken.
✓ Branch 135 taken 10 times.
✗ Branch 136 not taken.
✓ Branch 138 taken 10 times.
✗ Branch 139 not taken.
✓ Branch 141 taken 10 times.
✗ Branch 142 not taken.
✓ Branch 144 taken 10 times.
✗ Branch 145 not taken.
✓ Branch 147 taken 10 times.
✗ Branch 148 not taken.
|
20 | CROCODDYL_PYTHON_SCALARS( |
343 | CROCODDYL_ACTION_MODEL_CONTACT_INVDYN_PYTHON_BINDINGS) | ||
344 |
45/90✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 10 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 10 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 10 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 10 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 10 times.
✗ Branch 20 not taken.
✓ Branch 24 taken 10 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 10 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 10 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 10 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 10 times.
✗ Branch 37 not taken.
✓ Branch 39 taken 10 times.
✗ Branch 40 not taken.
✓ Branch 44 taken 10 times.
✗ Branch 45 not taken.
✓ Branch 47 taken 10 times.
✗ Branch 48 not taken.
✓ Branch 50 taken 10 times.
✗ Branch 51 not taken.
✓ Branch 53 taken 10 times.
✗ Branch 54 not taken.
✓ Branch 56 taken 10 times.
✗ Branch 57 not taken.
✓ Branch 59 taken 10 times.
✗ Branch 60 not taken.
✓ Branch 62 taken 10 times.
✗ Branch 63 not taken.
✓ Branch 65 taken 10 times.
✗ Branch 66 not taken.
✓ Branch 73 taken 10 times.
✗ Branch 74 not taken.
✓ Branch 76 taken 10 times.
✗ Branch 77 not taken.
✓ Branch 79 taken 10 times.
✗ Branch 80 not taken.
✓ Branch 84 taken 10 times.
✗ Branch 85 not taken.
✓ Branch 87 taken 10 times.
✗ Branch 88 not taken.
✓ Branch 90 taken 10 times.
✗ Branch 91 not taken.
✓ Branch 93 taken 10 times.
✗ Branch 94 not taken.
✓ Branch 96 taken 10 times.
✗ Branch 97 not taken.
✓ Branch 99 taken 10 times.
✗ Branch 100 not taken.
✓ Branch 102 taken 10 times.
✗ Branch 103 not taken.
✓ Branch 107 taken 10 times.
✗ Branch 108 not taken.
✓ Branch 110 taken 10 times.
✗ Branch 111 not taken.
✓ Branch 113 taken 10 times.
✗ Branch 114 not taken.
✓ Branch 116 taken 10 times.
✗ Branch 117 not taken.
✓ Branch 119 taken 10 times.
✗ Branch 120 not taken.
✓ Branch 122 taken 10 times.
✗ Branch 123 not taken.
✓ Branch 127 taken 10 times.
✗ Branch 128 not taken.
✓ Branch 130 taken 10 times.
✗ Branch 131 not taken.
✓ Branch 133 taken 10 times.
✗ Branch 134 not taken.
✓ Branch 136 taken 10 times.
✗ Branch 137 not taken.
✓ Branch 139 taken 10 times.
✗ Branch 140 not taken.
✓ Branch 142 taken 10 times.
✗ Branch 143 not taken.
✓ Branch 145 taken 10 times.
✗ Branch 146 not taken.
✓ Branch 148 taken 10 times.
✗ Branch 149 not taken.
|
20 | CROCODDYL_PYTHON_SCALARS(CROCODDYL_ACTION_DATA_CONTACT_INVDYN_PYTHON_BINDINGS) |
345 | 10 | } | |
346 | |||
347 | } // namespace python | ||
348 | } // namespace crocoddyl | ||
349 |