Directory: | ./ |
---|---|
File: | bindings/python/crocoddyl/core/diff-action-base.cpp |
Date: | 2025-03-26 19:23:43 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 66 | 66 | 100.0% |
Branches: | 128 | 256 | 50.0% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | /////////////////////////////////////////////////////////////////////////////// | ||
2 | // BSD 3-Clause License | ||
3 | // | ||
4 | // Copyright (C) 2019-2025, LAAS-CNRS, University of Edinburgh, | ||
5 | // University of Oxford, Heriot-Watt University | ||
6 | // Copyright note valid unless otherwise stated in individual files. | ||
7 | // All rights reserved. | ||
8 | /////////////////////////////////////////////////////////////////////////////// | ||
9 | |||
10 | #include "python/crocoddyl/core/diff-action-base.hpp" | ||
11 | |||
12 | #include "python/crocoddyl/core/core.hpp" | ||
13 | #include "python/crocoddyl/utils/vector-converter.hpp" | ||
14 | |||
15 | namespace crocoddyl { | ||
16 | namespace python { | ||
17 | |||
18 | template <typename Model> | ||
19 | struct DifferentialActionModelAbstractVisitor | ||
20 | : public bp::def_visitor<DifferentialActionModelAbstractVisitor<Model>> { | ||
21 | typedef typename Model::DifferentialActionModel ActionModel; | ||
22 | typedef typename Model::DifferentialActionData ActionData; | ||
23 | typedef typename Model::VectorXs VectorXs; | ||
24 | 40 | BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS( | |
25 | DifferentialActionModel_quasiStatic_wraps, ActionModel::quasiStatic_x, 2, | ||
26 | 4) | ||
27 | template <class PyClass> | ||
28 | 40 | void visit(PyClass& cl) const { | |
29 |
2/4✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
|
40 | cl.def("calc", pure_virtual(&Model::calc), |
30 | bp::args("self", "data", "x", "u"), | ||
31 | "Compute the system acceleration and cost value.\n\n" | ||
32 | ":param data: differential action data\n" | ||
33 | ":param x: state point (dim. state.nx)\n" | ||
34 | ":param u: control input (dim. nu)") | ||
35 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("calc", |
36 | static_cast<void (ActionModel::*)( | ||
37 | const std::shared_ptr<ActionData>&, | ||
38 | const Eigen::Ref<const VectorXs>&)>(&ActionModel::calc), | ||
39 | bp::args("self", "data", "x"), | ||
40 | "Compute the total cost value for nodes that depends only on the " | ||
41 | "state.\n\n" | ||
42 | "It updates the total cost and the system acceleration is not " | ||
43 | "updated as the control input is undefined. This function is used " | ||
44 | "in the terminal nodes of an optimal control problem.\n" | ||
45 | ":param data: differential action data\n" | ||
46 | ":param x: state point (dim. state.nx)") | ||
47 |
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("calcDiff", pure_virtual(&Model::calcDiff), |
48 | bp::args("self", "data", "x", "u"), | ||
49 | "Compute the derivatives of the dynamics and cost functions.\n\n" | ||
50 | "It computes the partial derivatives of the dynamical system and " | ||
51 | "the cost function. It assumes that calc has been run first. This " | ||
52 | "function builds a quadratic approximation of the time-continuous " | ||
53 | "action model (i.e. dynamical system and cost function).\n" | ||
54 | ":param data: differential action data\n" | ||
55 | ":param x: state point (dim. state.nx)\n" | ||
56 | ":param u: control input (dim. nu)") | ||
57 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("calcDiff", |
58 | static_cast<void (ActionModel::*)( | ||
59 | const std::shared_ptr<ActionData>&, | ||
60 | const Eigen::Ref<const VectorXs>&)>(&ActionModel::calcDiff), | ||
61 | bp::args("self", "data", "x"), | ||
62 | "Compute the derivatives of the cost functions with respect to " | ||
63 | "the state only.\n\n" | ||
64 | "It updates the derivatives of the cost function with respect to " | ||
65 | "the state only. This function is used in the terminal nodes of " | ||
66 | "an optimal control problem.\n" | ||
67 | ":param data: action data\n" | ||
68 | ":param x: state point (dim. state.nx)") | ||
69 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
80 | .def("createData", &Model::createData, &Model::default_createData, |
70 | bp::args("self"), | ||
71 | "Create the differential action data.\n\n" | ||
72 | "Each differential action model has its own data that needs to be " | ||
73 | "allocated. This function returns the allocated data for a " | ||
74 | "predefined DAM.\n" | ||
75 | ":return DAM data.") | ||
76 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
40 | .def("quasiStatic", &Model::quasiStatic_x, |
77 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | DifferentialActionModel_quasiStatic_wraps( |
78 | bp::args("self", "data", "x", "maxiter", "tol"), | ||
79 | "Compute the quasic-static control given a state.\n\n" | ||
80 | "It runs an iterative Newton step in order to compute the " | ||
81 | "quasic-static regime given a state configuration.\n" | ||
82 | ":param data: action data\n" | ||
83 | ":param x: discrete-time state vector\n" | ||
84 | ":param maxiter: maximum allowed number of iterations\n" | ||
85 | ":param tol: stopping tolerance criteria (default 1e-9)\n" | ||
86 | ":return u: quasic-static control")) | ||
87 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .def("quasiStatic", &Model::quasiStatic, &Model::default_quasiStatic, |
88 | bp::args("self", "data", "u", "x", "maxiter", "tol")) | ||
89 |
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 | .add_property("nu", bp::make_function(&Model::get_nu), |
90 | "dimension of control vector") | ||
91 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .add_property("nr", bp::make_function(&Model::get_nr), |
92 | "dimension of cost-residual vector") | ||
93 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .add_property("ng", bp::make_function(&Model::get_ng), |
94 | "number of inequality constraints") | ||
95 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .add_property("nh", bp::make_function(&Model::get_nh), |
96 | "number of equality constraints") | ||
97 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .add_property("ng_T", bp::make_function(&Model::get_ng_T), |
98 | "number of inequality terminal constraints") | ||
99 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .add_property("nh_T", bp::make_function(&Model::get_nh_T), |
100 | "number of equality terminal constraints") | ||
101 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
40 | .add_property( |
102 | "state", | ||
103 | bp::make_function(&Model::get_state, | ||
104 | 40 | bp::return_value_policy<bp::return_by_value>()), | |
105 | "state") | ||
106 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
40 | .add_property("g_lb", |
107 | bp::make_function(&Model::get_g_lb, | ||
108 | 40 | bp::return_internal_reference<>()), | |
109 | &Model::set_g_lb, | ||
110 | "lower bound of the inequality constraints") | ||
111 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .add_property("g_ub", |
112 | bp::make_function(&Model::get_g_ub, | ||
113 | 40 | bp::return_internal_reference<>()), | |
114 | &Model::set_g_ub, | ||
115 | "upper bound of the inequality constraints") | ||
116 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .add_property("u_lb", |
117 | bp::make_function(&Model::get_u_lb, | ||
118 | 40 | bp::return_internal_reference<>()), | |
119 | &Model::set_u_lb, "lower control limits") | ||
120 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
80 | .add_property("u_ub", |
121 | bp::make_function(&Model::get_u_ub, | ||
122 | 40 | bp::return_internal_reference<>()), | |
123 | &Model::set_u_ub, "upper control limits") | ||
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 | .add_property("has_control_limits", |
125 | bp::make_function(&Model::get_has_control_limits), | ||
126 | "indicates whether problem has finite control limits"); | ||
127 | 40 | } | |
128 | }; | ||
129 | |||
130 | template <typename Data> | ||
131 | struct DifferentialActionDataAbstractVisitor | ||
132 | : public bp::def_visitor<DifferentialActionDataAbstractVisitor<Data>> { | ||
133 | template <class PyClass> | ||
134 | 40 | void visit(PyClass& cl) const { | |
135 |
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 | cl.add_property( |
136 | "cost", | ||
137 | bp::make_getter(&Data::cost, | ||
138 | 40 | bp::return_value_policy<bp::return_by_value>()), | |
139 | bp::make_setter(&Data::cost), "cost value") | ||
140 |
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 | .add_property( |
141 | "xout", | ||
142 | 40 | bp::make_getter(&Data::xout, bp::return_internal_reference<>()), | |
143 | bp::make_setter(&Data::xout), "evolution state") | ||
144 |
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 | .add_property( |
145 | 40 | "r", bp::make_getter(&Data::r, bp::return_internal_reference<>()), | |
146 | bp::make_setter(&Data::r), "cost residual") | ||
147 |
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 | .add_property( |
148 | 40 | "Fx", bp::make_getter(&Data::Fx, bp::return_internal_reference<>()), | |
149 | bp::make_setter(&Data::Fx), | ||
150 | "Jacobian of the dynamics w.r.t. the state") | ||
151 |
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 | .add_property( |
152 | 40 | "Fu", bp::make_getter(&Data::Fu, bp::return_internal_reference<>()), | |
153 | bp::make_setter(&Data::Fu), | ||
154 | "Jacobian of the dynamics w.r.t. the control") | ||
155 |
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 | .add_property( |
156 | 40 | "Lx", bp::make_getter(&Data::Lx, bp::return_internal_reference<>()), | |
157 | bp::make_setter(&Data::Lx), "Jacobian of the cost w.r.t. the state") | ||
158 |
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 | .add_property( |
159 | 40 | "Lu", bp::make_getter(&Data::Lu, bp::return_internal_reference<>()), | |
160 | bp::make_setter(&Data::Lu), | ||
161 | "Jacobian of the cost w.r.t. the control") | ||
162 |
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 | .add_property( |
163 | "Lxx", | ||
164 | 40 | bp::make_getter(&Data::Lxx, bp::return_internal_reference<>()), | |
165 | bp::make_setter(&Data::Lxx), "Hessian of the cost w.r.t. the state") | ||
166 |
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 | .add_property( |
167 | "Lxu", | ||
168 | 40 | bp::make_getter(&Data::Lxu, bp::return_internal_reference<>()), | |
169 | bp::make_setter(&Data::Lxu), | ||
170 | "Hessian of the cost w.r.t. the state and control") | ||
171 |
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 | .add_property( |
172 | "Luu", | ||
173 | 40 | bp::make_getter(&Data::Luu, bp::return_internal_reference<>()), | |
174 | bp::make_setter(&Data::Luu), | ||
175 | "Hessian of the cost w.r.t. the control") | ||
176 |
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 | .add_property( |
177 | 40 | "g", bp::make_getter(&Data::g, bp::return_internal_reference<>()), | |
178 | bp::make_setter(&Data::g), "Inequality constraint values") | ||
179 |
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 | .add_property( |
180 | 40 | "Gx", bp::make_getter(&Data::Gx, bp::return_internal_reference<>()), | |
181 | bp::make_setter(&Data::Gx), | ||
182 | "Jacobian of the inequality constraint w.r.t. the state") | ||
183 |
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 | .add_property( |
184 | 40 | "Gu", bp::make_getter(&Data::Gu, bp::return_internal_reference<>()), | |
185 | bp::make_setter(&Data::Gu), | ||
186 | "Jacobian of the inequality constraint w.r.t. the control") | ||
187 |
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 | .add_property( |
188 | 40 | "h", bp::make_getter(&Data::h, bp::return_internal_reference<>()), | |
189 | bp::make_setter(&Data::h), "Equality constraint values") | ||
190 |
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 | .add_property( |
191 | 40 | "Hx", bp::make_getter(&Data::Hx, bp::return_internal_reference<>()), | |
192 | bp::make_setter(&Data::Hx), | ||
193 | "Jacobian of the equality constraint w.r.t. the state") | ||
194 |
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 | .add_property( |
195 | 40 | "Hu", bp::make_getter(&Data::Hu, bp::return_internal_reference<>()), | |
196 | bp::make_setter(&Data::Hu), | ||
197 | "Jacobian of the equality constraint w.r.t. the control"); | ||
198 | 40 | } | |
199 | }; | ||
200 | |||
201 | #define CROCODDYL_DIFFACTION_MODEL_ABSTRACT_PYTHON_BINDINGS(Scalar) \ | ||
202 | typedef DifferentialActionModelAbstractTpl<Scalar> Model; \ | ||
203 | typedef DifferentialActionModelAbstractTpl_wrap<Scalar> Model_wrap; \ | ||
204 | typedef StateAbstractTpl<Scalar> State; \ | ||
205 | typedef std::shared_ptr<Model> DifferentialActionModelPtr; \ | ||
206 | StdVectorPythonVisitor<std::vector<DifferentialActionModelPtr>, \ | ||
207 | true>::expose("StdVec_DiffActionModel"); \ | ||
208 | bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ | ||
209 | bp::class_<Model_wrap, boost::noncopyable>( \ | ||
210 | "DifferentialActionModelAbstract", \ | ||
211 | "Abstract class for the differential action model.\n\n" \ | ||
212 | "A differential action model is the time-continuous version of an " \ | ||
213 | "action model. Each node, in our optimal control problem, is described " \ | ||
214 | "through an action model. Every time that we want describe a problem, " \ | ||
215 | "we need to provide ways of computing the dynamics, cost functions, " \ | ||
216 | "constraints and their derivatives. These computations are mainly " \ | ||
217 | "carried out inside calc() and calcDiff(), respectively.", \ | ||
218 | bp::init<std::shared_ptr<State>, std::size_t, \ | ||
219 | bp::optional<std::size_t, std::size_t, std::size_t, \ | ||
220 | std::size_t, std::size_t>>( \ | ||
221 | bp::args("self", "state", "nu", "nr", "ng", "nh", "ng_T", "nh_T"), \ | ||
222 | "Initialize the differential action model.\n\n" \ | ||
223 | "We can also describe autonomous systems by setting nu = 0.\n" \ | ||
224 | ":param state: state\n" \ | ||
225 | ":param nu: dimension of control vector\n" \ | ||
226 | ":param nr: dimension of cost-residual vector (default 1)\n" \ | ||
227 | ":param ng: number of inequality constraints (default 0)\n" \ | ||
228 | ":param nh: number of equality constraints (default 0)\n" \ | ||
229 | ":param ng_T: number of inequality terminal constraints (default " \ | ||
230 | "0)\n" \ | ||
231 | ":param nh_T: number of equality terminal constraints (default 0)")) \ | ||
232 | .def(DifferentialActionModelAbstractVisitor<Model_wrap>()) \ | ||
233 | .def(PrintableVisitor<Model_wrap>()) \ | ||
234 | .def(CopyableVisitor<Model_wrap>()); | ||
235 | |||
236 | #define CROCODDYL_DIFFACTION_DATA_ABSTRACT_PYTHON_BINDINGS(Scalar) \ | ||
237 | typedef DifferentialActionDataAbstractTpl<Scalar> Data; \ | ||
238 | typedef DifferentialActionModelAbstractTpl<Scalar> Model; \ | ||
239 | typedef std::shared_ptr<Data> DifferentialActionDataPtr; \ | ||
240 | StdVectorPythonVisitor<std::vector<DifferentialActionDataPtr>, \ | ||
241 | true>::expose("StdVec_DiffActionData"); \ | ||
242 | bp::register_ptr_to_python<std::shared_ptr<Data>>(); \ | ||
243 | bp::class_<Data, boost::noncopyable>( \ | ||
244 | "DifferentialActionDataAbstract", \ | ||
245 | "Abstract class for differential action data.\n\n" \ | ||
246 | "In crocoddyl, an action data contains all the required information " \ | ||
247 | "for processing an user-defined action model. The action data " \ | ||
248 | "typically is allocated onces by running model.createData() and " \ | ||
249 | "contains the first- and second-order derivatives of the dynamics and " \ | ||
250 | "cost function, respectively.", \ | ||
251 | bp::init<Model*>(bp::args("self", "model"), \ | ||
252 | "Create common data shared between DAMs.\n\n" \ | ||
253 | "The differential action data uses the model in order " \ | ||
254 | "to first process it.\n" \ | ||
255 | ":param model: differential action model")) \ | ||
256 | .def(DifferentialActionDataAbstractVisitor<Data>()) \ | ||
257 | .def(CopyableVisitor<Data>()); | ||
258 | |||
259 | 10 | void exposeDifferentialActionAbstract() { | |
260 |
21/42✓ Branch 2 taken 10 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 10 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 10 times.
✗ Branch 10 not taken.
✓ Branch 18 taken 10 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 10 times.
✗ Branch 22 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 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 48 taken 10 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 10 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 10 times.
✗ Branch 56 not taken.
✓ Branch 62 taken 10 times.
✗ Branch 63 not taken.
✓ Branch 65 taken 10 times.
✗ Branch 66 not taken.
✓ Branch 68 taken 10 times.
✗ Branch 69 not taken.
✓ Branch 71 taken 10 times.
✗ Branch 72 not taken.
✓ Branch 74 taken 10 times.
✗ Branch 75 not taken.
✓ Branch 77 taken 10 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 10 times.
✗ Branch 81 not taken.
|
20 | CROCODDYL_PYTHON_SCALARS(CROCODDYL_DIFFACTION_MODEL_ABSTRACT_PYTHON_BINDINGS) |
261 |
19/38✓ Branch 2 taken 10 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 10 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 10 times.
✗ Branch 10 not taken.
✓ Branch 18 taken 10 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 10 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 10 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 10 times.
✗ Branch 28 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 45 taken 10 times.
✗ Branch 46 not taken.
✓ Branch 49 taken 10 times.
✗ Branch 50 not taken.
✓ Branch 52 taken 10 times.
✗ Branch 53 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 68 taken 10 times.
✗ Branch 69 not taken.
✓ Branch 71 taken 10 times.
✗ Branch 72 not taken.
✓ Branch 74 taken 10 times.
✗ Branch 75 not taken.
|
20 | CROCODDYL_PYTHON_SCALARS(CROCODDYL_DIFFACTION_DATA_ABSTRACT_PYTHON_BINDINGS) |
262 | 10 | } | |
263 | |||
264 | } // namespace python | ||
265 | } // namespace crocoddyl | ||
266 |