GCC Code Coverage Report


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