GCC Code Coverage Report


Directory: ./
File: bindings/python/crocoddyl/core/action-base.cpp
Date: 2025-03-26 19:23:43
Exec Total Coverage
Lines: 71 75 94.7%
Branches: 145 290 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/action-base.hpp"
11
12 #include "python/crocoddyl/utils/deprecate.hpp"
13 #include "python/crocoddyl/utils/vector-converter.hpp"
14
15 namespace crocoddyl {
16 namespace python {
17
18 template <typename Model>
19 struct ActionModelAbstractVisitor
20 : public bp::def_visitor<ActionModelAbstractVisitor<Model>> {
21 typedef typename Model::ActionModel ActionModel;
22 typedef typename Model::ActionData ActionData;
23 typedef typename Model::VectorXs VectorXs;
24 40 BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(ActionModel_quasiStatic_wraps,
25 ActionModel::quasiStatic_x, 2, 4)
26 template <class PyClass>
27 40 void visit(PyClass& cl) const {
28
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),
29 bp::args("self", "data", "x", "u"),
30 "Compute the next state and cost value.\n\n"
31 "It describes the time-discrete evolution of our dynamical system "
32 "in which we obtain the next state. Additionally it computes the "
33 "cost value associated to this discrete state and control pair.\n"
34 ":param data: action data\n"
35 ":param x: state point (dim. state.nx)\n"
36 ":param u: control input (dim. nu)")
37
2/4
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
80 .def("calc",
38 static_cast<void (ActionModel::*)(
39 const std::shared_ptr<ActionData>&,
40 const Eigen::Ref<const VectorXs>&)>(&ActionModel::calc),
41 bp::args("self", "data", "x"),
42 "Compute the total cost value for nodes that depends only on the "
43 "state.\n\n"
44 "It updates the total cost and the next state is not computed as "
45 "it is not expected to change. This function is used in the "
46 "terminal nodes of an optimal control problem.\n"
47 ":param data: action data\n"
48 ":param x: state point (dim. state.nx)")
49
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),
50 bp::args("self", "data", "x", "u"),
51 "Compute the derivatives of the dynamics and cost functions.\n\n"
52 "It computes the partial derivatives of the dynamical system and "
53 "the cost function. It assumes that calc has been run first. This "
54 "function builds a quadratic approximation of the action model "
55 "(i.e. linear dynamics and quadratic cost).\n"
56 ":param data: action data\n"
57 ":param x: state point (dim. state.nx)\n"
58 ":param u: control input (dim. nu)")
59
2/4
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
80 .def("calcDiff",
60 static_cast<void (ActionModel::*)(
61 const std::shared_ptr<ActionData>&,
62 const Eigen::Ref<const VectorXs>&)>(&ActionModel::calcDiff),
63 bp::args("self", "data", "x"),
64 "Compute the derivatives of the cost functions with respect to "
65 "the state only.\n\n"
66 "It updates the derivatives of the cost function with respect to "
67 "the state only. This function is used in the terminal nodes of "
68 "an optimal control problem.\n"
69 ":param data: action data\n"
70 ":param x: state point (dim. state.nx)")
71
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
80 .def("createData", &Model::createData, &Model::default_createData,
72 bp::args("self"),
73 "Create the action data.\n\n"
74 "Each action model (AM) has its own data that needs to be "
75 "allocated.\n"
76 "This function returns the allocated data for a predefined AM.\n"
77 ":return AM data.")
78
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
40 .def("quasiStatic", &Model::quasiStatic_x,
79
2/4
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
80 ActionModel_quasiStatic_wraps(
80 bp::args("self", "data", "x", "maxiter", "tol"),
81 "Compute the quasic-static control given a state.\n\n"
82 "It runs an iterative Newton step in order to compute the "
83 "quasic-static regime given a state configuration.\n"
84 ":param data: action data\n"
85 ":param x: discrete-time state vector\n"
86 ":param maxiter: maximum allowed number of iterations\n"
87 ":param tol: stopping tolerance criteria (default 1e-9)\n"
88 ":return u: quasic-static control"))
89
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,
90 bp::args("self", "data", "u", "x", "maxiter", "tol"))
91
4/8
✓ 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.
✓ Branch 10 taken 20 times.
✗ Branch 11 not taken.
80 .add_property(
92 "nu", bp::make_function(&Model::get_nu),
93 40 bp::make_setter(&Model::nu_, bp::return_internal_reference<>()),
94 "dimension of control vector")
95
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),
96 "dimension of cost-residual vector")
97
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(
98 "ng", bp::make_function(&Model::get_ng),
99 bp::make_setter(
100 &Model::ng_,
101
2/4
✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
80 deprecated<bp::return_internal_reference<>>(
102 "Deprecated. Contraint dimension should not be modified.")),
103 "number of inequality constraints")
104 .def("get_ng", &Model::get_ng, &Model::default_get_ng,
105 "Return the number of inequality constraints.")
106
4/8
✓ 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.
✓ Branch 10 taken 20 times.
✗ Branch 11 not taken.
120 .add_property(
107 "nh", bp::make_function(&Model::get_nh),
108 bp::make_setter(
109 &Model::nh_,
110
2/4
✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
80 deprecated<bp::return_internal_reference<>>(
111 "Deprecated. Contraint dimension should not be modified.")),
112 "number of equality constraints")
113 .def("get_nh", &Model::get_nh, &Model::default_get_nh,
114 "Return the number of equality constraints.")
115
4/8
✓ 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.
✓ Branch 10 taken 20 times.
✗ Branch 11 not taken.
120 .add_property(
116 "ng_T", bp::make_function(&Model::get_ng_T),
117 bp::make_setter(
118 &Model::ng_T_,
119
2/4
✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
80 deprecated<bp::return_internal_reference<>>(
120 "Deprecated. Contraint dimension should not be modified.")),
121 "number of inequality terminal constraints")
122 .def("get_ng_T", &Model::get_ng_T, &Model::default_get_ng_T,
123 "Return the number of inequality terminal constraints.")
124
4/8
✓ 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.
✓ Branch 10 taken 20 times.
✗ Branch 11 not taken.
120 .add_property(
125 "nh_T", bp::make_function(&Model::get_nh_T),
126 bp::make_setter(
127 &Model::nh_T_,
128
2/4
✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
80 deprecated<bp::return_internal_reference<>>(
129 "Deprecated. Contraint dimension should not be modified.")),
130 "number of equality terminal constraints")
131 .def("get_nh_T", &Model::get_nh_T, &Model::default_get_nh_T,
132 "Return the number of equality terminal constraints.")
133
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(
134 "state",
135 bp::make_function(&Model::get_state,
136 40 bp::return_value_policy<bp::return_by_value>()),
137 "state")
138
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
40 .add_property("g_lb",
139 bp::make_function(&Model::get_g_lb,
140 40 bp::return_internal_reference<>()),
141 &Model::set_g_lb,
142 "lower bound of the inequality constraints")
143
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",
144 bp::make_function(&Model::get_g_ub,
145 40 bp::return_internal_reference<>()),
146 &Model::set_g_ub,
147 "upper bound of the inequality constraints")
148
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",
149 bp::make_function(&Model::get_u_lb,
150 40 bp::return_internal_reference<>()),
151 &Model::set_u_lb, "lower control limits")
152
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",
153 bp::make_function(&Model::get_u_ub,
154 40 bp::return_internal_reference<>()),
155 &Model::set_u_ub, "upper control limits")
156
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",
157 bp::make_function(&Model::get_has_control_limits),
158 "indicates whether problem has finite control limits");
159 40 }
160 };
161
162 template <typename Data>
163 struct ActionDataAbstractVisitor
164 : public bp::def_visitor<ActionDataAbstractVisitor<Data>> {
165 template <class PyClass>
166 40 void visit(PyClass& cl) const {
167
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(
168 "cost",
169 bp::make_getter(&Data::cost,
170 40 bp::return_value_policy<bp::return_by_value>()),
171 bp::make_setter(&Data::cost), "cost value")
172
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(
173 "xnext",
174 40 bp::make_getter(&Data::xnext, bp::return_internal_reference<>()),
175 bp::make_setter(&Data::xnext), "next state")
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 "r", bp::make_getter(&Data::r, bp::return_internal_reference<>()),
178 bp::make_setter(&Data::r), "cost residual")
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 "Fx", bp::make_getter(&Data::Fx, bp::return_internal_reference<>()),
181 bp::make_setter(&Data::Fx),
182 "Jacobian of the dynamics 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 "Fu", bp::make_getter(&Data::Fu, bp::return_internal_reference<>()),
185 bp::make_setter(&Data::Fu),
186 "Jacobian of the dynamics 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 "Lx", bp::make_getter(&Data::Lx, bp::return_internal_reference<>()),
189 bp::make_setter(&Data::Lx), "Jacobian of the cost w.r.t. the state")
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 "Lu", bp::make_getter(&Data::Lu, bp::return_internal_reference<>()),
192 bp::make_setter(&Data::Lu), "Jacobian of the cost")
193
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(
194 "Lxx",
195 40 bp::make_getter(&Data::Lxx, bp::return_internal_reference<>()),
196 bp::make_setter(&Data::Lxx), "Hessian of the cost w.r.t. the state")
197
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(
198 "Lxu",
199 40 bp::make_getter(&Data::Lxu, bp::return_internal_reference<>()),
200 bp::make_setter(&Data::Lxu),
201 "Hessian of the cost w.r.t. the state and control")
202
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(
203 "Luu",
204 40 bp::make_getter(&Data::Luu, bp::return_internal_reference<>()),
205 bp::make_setter(&Data::Luu),
206 "Hessian of the cost w.r.t. the control")
207
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(
208 40 "g", bp::make_getter(&Data::g, bp::return_internal_reference<>()),
209 bp::make_setter(&Data::g), "inequality constraint values")
210
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(
211 40 "Gx", bp::make_getter(&Data::Gx, bp::return_internal_reference<>()),
212 bp::make_setter(&Data::Gx),
213 "Jacobian of the inequality constraint w.r.t. the state")
214
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(
215 40 "Gu", bp::make_getter(&Data::Gu, bp::return_internal_reference<>()),
216 bp::make_setter(&Data::Gu),
217 "Jacobian of the inequality constraint w.r.t. the control")
218
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(
219 40 "h", bp::make_getter(&Data::h, bp::return_internal_reference<>()),
220 bp::make_setter(&Data::h), "equality constraint values")
221
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(
222 40 "Hx", bp::make_getter(&Data::Hx, bp::return_internal_reference<>()),
223 bp::make_setter(&Data::Hx),
224 "Jacobian of the equality constraint w.r.t. the state")
225
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(
226 40 "Hu", bp::make_getter(&Data::Hu, bp::return_internal_reference<>()),
227 bp::make_setter(&Data::Hu),
228 "Jacobian of the equality constraint w.r.t. the control");
229 40 }
230 };
231
232 #define CROCODDYL_ACTION_MODEL_ABSTRACT_PYTHON_BINDINGS(Scalar) \
233 typedef ActionModelAbstractTpl<Scalar> Model; \
234 typedef ActionModelAbstractTpl_wrap<Scalar> Model_wrap; \
235 typedef StateAbstractTpl<Scalar> State; \
236 typedef std::shared_ptr<Model> ActionModelPtr; \
237 StdVectorPythonVisitor<std::vector<ActionModelPtr>, true>::expose( \
238 "StdVec_ActionModel"); \
239 bp::register_ptr_to_python<std::shared_ptr<Model>>(); \
240 bp::class_<Model_wrap, boost::noncopyable>( \
241 "ActionModelAbstract", \
242 "Abstract class for action models.\n\n" \
243 "An action model combines dynamics and cost data. Each node, in our " \
244 "optimal control problem, is described through an action model. Every " \
245 "time that we want to describe a problem, we need to provide ways of " \
246 "computing the dynamics, cost functions and their derivatives. These " \
247 "computations are mainly carried out inside calc() and calcDiff(), " \
248 "respectively.", \
249 bp::init<std::shared_ptr<State>, std::size_t, \
250 bp::optional<std::size_t, std::size_t, std::size_t, \
251 std::size_t, std::size_t>>( \
252 bp::args("self", "state", "nu", "nr", "ng", "nh", "ng_T", "nh_T"), \
253 "Initialize the action model.\n\n" \
254 "We can also describe autonomous systems by setting nu = 0.\n" \
255 ":param state: state description,\n" \
256 ":param nu: dimension of control vector,\n" \
257 ":param nr: dimension of the cost-residual vector (default 1)\n" \
258 ":param ng: number of inequality constraints (default 0)\n" \
259 ":param nh: number of equality constraints (default 0)\n" \
260 ":param ng_T: number of inequality terminal constraints (default " \
261 "0)\n" \
262 ":param nh_T: number of equality terminal constraints (default 0)")) \
263 .def(ActionModelAbstractVisitor<Model_wrap>()) \
264 .def(PrintableVisitor<Model_wrap>()) \
265 .def(CopyableVisitor<Model_wrap>());
266
267 #define CROCODDYL_ACTION_DATA_ABSTRACT_PYTHON_BINDINGS(Scalar) \
268 typedef ActionDataAbstractTpl<Scalar> Data; \
269 typedef ActionModelAbstractTpl<Scalar> Model; \
270 typedef std::shared_ptr<Data> ActionDataPtr; \
271 StdVectorPythonVisitor<std::vector<ActionDataPtr>, true>::expose( \
272 "StdVec_ActionData"); \
273 bp::register_ptr_to_python<std::shared_ptr<Data>>(); \
274 bp::class_<Data, boost::noncopyable>( \
275 "ActionDataAbstract", \
276 "Abstract class for action data.\n\n" \
277 "In crocoddyl, an action data contains all the required information " \
278 "for processing an user-defined action model. The action data " \
279 "typically is allocated onces by running model.createData() and " \
280 "contains the first- and second-order derivatives of the dynamics and " \
281 "cost function, respectively.", \
282 bp::init<Model*>( \
283 bp::args("self", "model"), \
284 "Create common data shared between AMs.\n\n" \
285 "The action data uses the model in order to first process it.\n" \
286 ":param model: action model")) \
287 .def(ActionDataAbstractVisitor<Data>()) \
288 .def(CopyableVisitor<Data>());
289
290 10 void exposeActionAbstract() {
291
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_ACTION_MODEL_ABSTRACT_PYTHON_BINDINGS)
292
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_ACTION_DATA_ABSTRACT_PYTHON_BINDINGS)
293 10 }
294
295 } // namespace python
296 } // namespace crocoddyl
297