GCC Code Coverage Report


Directory: ./
File: bindings/python/crocoddyl/core/integ-action-base.cpp
Date: 2025-03-26 19:23:43
Exec Total Coverage
Lines: 18 18 100.0%
Branches: 46 92 50.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2021-2025, LAAS-CNRS, University of Edinburgh,
5 // University of Oxford, University of Trento,
6 // Heriot-Watt University
7 // Copyright note valid unless otherwise stated in individual files.
8 // All rights reserved.
9 ///////////////////////////////////////////////////////////////////////////////
10
11 #include "python/crocoddyl/core/integ-action-base.hpp"
12
13 namespace crocoddyl {
14 namespace python {
15
16 template <typename Model>
17 struct IntegratedActionModelAbstractVisitor
18 : public bp::def_visitor<IntegratedActionModelAbstractVisitor<Model>> {
19 typedef typename Model::Scalar Scalar;
20 typedef typename Model::IntegratedActionModel IntegratedActionModel;
21 typedef typename Model::IntegratedActionData IntegratedActionData;
22 typedef typename Model::DifferentialActionModel DifferentialActionModel;
23 typedef typename Model::ActionData ActionData;
24 typedef typename Model::ControlModel ControlModel;
25 typedef typename Model::VectorXs VectorXs;
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(bp::init<std::shared_ptr<DifferentialActionModel>,
29 std::shared_ptr<ControlModel>, bp::optional<Scalar, bool>>(
30 bp::args("self", "diffModel", "control", "stepTime",
31 "withCostResidual"),
32 "Initialize the integrated-action integrator.\n\n"
33 "You can also integrate autonomous systems (i.e., when "
34 "diffModel.nu is equals to 0).\n"
35 ":param model: differential action model\n"
36 ":param control: the control parametrization\n"
37 ":param stepTime: step time (default 1e-3)\n"
38 ":param withCostResidual: includes the cost residuals and "
39 "derivatives (default True)."))
40
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("calc", pure_virtual(&Model::calc),
41 bp::args("self", "data", "x", "u"),
42 "Compute the next state and cost value.\n\n"
43 "It describes the time-discrete evolution of our dynamical system "
44 "in which we obtain the next state. Additionally it computes the "
45 "cost value associated to this discrete state and control pair.\n"
46 ":param data: integrated-action data\n"
47 ":param x: state point (dim. state.nx)\n"
48 ":param u: control input (dim. nu)")
49
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
80 .def("calc",
50 static_cast<void (IntegratedActionModel::*)(
51 const std::shared_ptr<ActionData>&,
52 const Eigen::Ref<const VectorXs>&)>(
53 &IntegratedActionModel::calc),
54 bp::args("self", "data", "x"))
55
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 .def("calcDiff", pure_virtual(&Model::calcDiff),
56 bp::args("self", "data", "x", "u"),
57 "Compute the derivatives of the dynamics and cost functions.\n\n"
58 "It computes the partial derivatives of the dynamical system and "
59 "the cost function. It assumes that calc has been run first. This "
60 "function builds a quadratic approximation of the action model "
61 "(i.e. linear dynamics and quadratic cost).\n"
62 ":param data: integrated-action data\n"
63 ":param x: state point (dim. state.nx)\n"
64 ":param u: control input (dim. nu)")
65
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
80 .def("calcDiff",
66 static_cast<void (IntegratedActionModel::*)(
67 const std::shared_ptr<ActionData>&,
68 const Eigen::Ref<const VectorXs>&)>(
69 &IntegratedActionModel::calcDiff),
70 bp::args("self", "data", "x"))
71
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, &Model::default_createData,
72 bp::args("self"),
73 "Create the integrated-action data.\n\n"
74 "Each integrated-action model (IAM) has its own data that needs "
75 "to be allocated. This function returns the allocated data for a "
76 "predefined IAM.\n"
77 ":return integrated-action data.")
78
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(
79 "differential",
80 bp::make_function(&Model::get_differential,
81 40 bp::return_value_policy<bp::return_by_value>()),
82 "differential action model")
83
2/4
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
40 .add_property(
84 "control",
85 bp::make_function(&Model::get_control,
86 40 bp::return_value_policy<bp::return_by_value>()),
87 "control parametrization model")
88
2/4
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
40 .add_property(
89 "dt",
90 bp::make_function(&IntegratedActionModelAbstract::get_dt,
91 40 bp::return_value_policy<bp::return_by_value>()),
92 &IntegratedActionModelAbstract::set_dt, "step time");
93 40 }
94 };
95
96 #define CROCODDYL_INTACTION_MODEL_ABSTRACT_PYTHON_BINDINGS(Scalar) \
97 typedef IntegratedActionModelAbstractTpl<Scalar> Model; \
98 typedef IntegratedActionModelAbstractTpl_wrap<Scalar> Model_wrap; \
99 typedef ActionModelAbstractTpl<Scalar> ModelBase; \
100 typedef DifferentialActionModelAbstractTpl<Scalar> DiffModelBase; \
101 bp::register_ptr_to_python<std::shared_ptr<Model>>(); \
102 bp::class_<Model_wrap, boost::noncopyable, bp::bases<ModelBase>>( \
103 "IntegratedActionModelAbstract", \
104 "Abstract class for integrated action models.\n\n" \
105 "In Crocoddyl, an integrated action model transforms a differential " \
106 "action model in a (discrete) action model.\n", \
107 bp::init<std::shared_ptr<DiffModelBase>, bp::optional<Scalar, bool>>( \
108 bp::args("self", "diffModel", "timeStep", "withCostResidual"), \
109 "Initialize the integrated-action model.\n\n" \
110 "You can also integrate autonomous systems (i.e., when " \
111 "diffModel.nu is equals to 0).\n" \
112 ":param diffModel: differential action model\n" \
113 ":param timestep: integration time step (default 1e-3)\n" \
114 ":param withCostResidual: includes the cost residuals and " \
115 "derivatives (default True).")) \
116 .def(IntegratedActionModelAbstractVisitor<Model_wrap>()) \
117 .def(PrintableVisitor<Model_wrap>()) \
118 .def(CopyableVisitor<Model_wrap>());
119
120 #define CROCODDYL_INTACTION_DATA_ABSTRACT_PYTHON_BINDINGS(Scalar) \
121 typedef IntegratedActionDataAbstractTpl<Scalar> Data; \
122 typedef IntegratedActionModelAbstractTpl<Scalar> Model; \
123 typedef ActionDataAbstractTpl<Scalar> DataBase; \
124 bp::register_ptr_to_python<std::shared_ptr<Data>>(); \
125 bp::class_<Data, bp::bases<DataBase>>( \
126 "IntegratedActionDataAbstract", \
127 "Abstract class for integrated-action data.\n\n" \
128 "In Crocoddyl, an action data contains all the required information " \
129 "for processing an user-defined action model. The action data " \
130 "typically is allocated onces by running model.createData() and " \
131 "contains the first- and second- order derivatives of the dynamics and " \
132 "cost function, respectively.", \
133 bp::init<Model*>( \
134 bp::args("self", "model"), \
135 "Create common data shared between integrated-action models.\n\n" \
136 "The integrated-action data uses its model in order to first " \
137 "process it.\n" \
138 ":param model: integrated-action model")) \
139 .def(CopyableVisitor<Data>());
140
141 10 void exposeIntegratedActionAbstract() {
142
15/30
✓ Branch 3 taken 10 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 10 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 10 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 10 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 10 times.
✗ Branch 16 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 32 taken 10 times.
✗ Branch 33 not taken.
✓ Branch 35 taken 10 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 10 times.
✗ Branch 39 not taken.
✓ Branch 41 taken 10 times.
✗ Branch 42 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.
20 CROCODDYL_PYTHON_SCALARS(CROCODDYL_INTACTION_MODEL_ABSTRACT_PYTHON_BINDINGS)
143
11/22
✓ Branch 3 taken 10 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 10 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 10 times.
✗ Branch 10 not taken.
✓ Branch 15 taken 10 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 10 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 10 times.
✗ Branch 22 not taken.
✓ Branch 26 taken 10 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 10 times.
✗ Branch 30 not taken.
✓ Branch 32 taken 10 times.
✗ Branch 33 not taken.
✓ Branch 35 taken 10 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 10 times.
✗ Branch 39 not taken.
20 CROCODDYL_PYTHON_SCALARS(CROCODDYL_INTACTION_DATA_ABSTRACT_PYTHON_BINDINGS)
144 10 }
145
146 } // namespace python
147 } // namespace crocoddyl
148