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, University of Trento, |
6 |
|
|
// Heriot-Watt University |
7 |
|
|
// Copyright note valid unless otherwise stated in individual files. |
8 |
|
|
// All rights reserved. |
9 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
10 |
|
|
|
11 |
|
|
// Auto-generated file for float |
12 |
|
|
#include "crocoddyl/core/integrator/euler.hpp" |
13 |
|
|
|
14 |
|
|
#include "python/crocoddyl/core/core.hpp" |
15 |
|
|
#include "python/crocoddyl/core/integ-action-base.hpp" |
16 |
|
|
|
17 |
|
|
namespace crocoddyl { |
18 |
|
|
namespace python { |
19 |
|
|
|
20 |
|
|
template <typename Model> |
21 |
|
|
struct IntegratedActionModelEulerVisitor |
22 |
|
|
: public bp::def_visitor<IntegratedActionModelEulerVisitor<Model>> { |
23 |
|
|
typedef typename Model::Scalar Scalar; |
24 |
|
|
typedef typename Model::ActionDataAbstract Data; |
25 |
|
|
typedef |
26 |
|
|
typename Model::DifferentialActionModelAbstract DifferentialActionModel; |
27 |
|
|
typedef typename Model::ControlParametrizationModelAbstract |
28 |
|
|
ControlParametrizationModel; |
29 |
|
|
typedef typename Model::VectorXs VectorXs; |
30 |
|
|
template <class PyClass> |
31 |
|
✗ |
void visit(PyClass& cl) const { |
32 |
|
✗ |
cl.def(bp::init<std::shared_ptr<DifferentialActionModel>, |
33 |
|
|
std::shared_ptr<ControlParametrizationModel>, |
34 |
|
|
bp::optional<Scalar, bool>>( |
35 |
|
|
bp::args("self", "diffModel", "control", "stepTime", |
36 |
|
|
"withCostResidual"), |
37 |
|
|
"Initialize the Euler integrator.\n\n" |
38 |
|
|
":param diffModel: differential action model\n" |
39 |
|
|
":param control: the control parametrization\n" |
40 |
|
|
":param stepTime: step time (default 1e-3)\n" |
41 |
|
|
":param withCostResidual: includes the cost residuals and " |
42 |
|
|
"derivatives (default True).")) |
43 |
|
✗ |
.def( |
44 |
|
|
"calc", |
45 |
|
|
static_cast<void (Model::*)( |
46 |
|
|
const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, |
47 |
|
|
const Eigen::Ref<const VectorXs>&)>(&Model::calc), |
48 |
|
|
bp::args("self", "data", "x", "u"), |
49 |
|
|
"Compute the time-discrete evolution of a differential action " |
50 |
|
|
"model.\n\n" |
51 |
|
|
"It describes the time-discrete evolution of action model.\n" |
52 |
|
|
":param data: action data\n" |
53 |
|
|
":param x: state point (dim. state.nx)\n" |
54 |
|
|
":param u: control input (dim. nu)") |
55 |
|
✗ |
.def("calc", |
56 |
|
|
static_cast<void (Model::*)(const std::shared_ptr<Data>&, |
57 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
58 |
|
|
&Model::calc), |
59 |
|
|
bp::args("self", "data", "x")) |
60 |
|
✗ |
.def( |
61 |
|
|
"calcDiff", |
62 |
|
|
static_cast<void (Model::*)( |
63 |
|
|
const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, |
64 |
|
|
const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff), |
65 |
|
|
bp::args("self", "data", "x", "u"), |
66 |
|
|
"Computes the derivatives of the integrated action model wrt state " |
67 |
|
|
"and control. \n\n" |
68 |
|
|
"This function builds a quadratic approximation of the action " |
69 |
|
|
"model (i.e. dynamical system and cost function). It assumes that " |
70 |
|
|
"calc has been run first.\n" |
71 |
|
|
":param data: action data\n" |
72 |
|
|
":param x: state point (dim. state.nx)\n" |
73 |
|
|
":param u: control input (dim. nu)") |
74 |
|
✗ |
.def("calcDiff", |
75 |
|
|
static_cast<void (Model::*)(const std::shared_ptr<Data>&, |
76 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
77 |
|
|
&Model::calcDiff), |
78 |
|
|
bp::args("self", "data", "x")) |
79 |
|
✗ |
.def("createData", &Model::createData, bp::args("self"), |
80 |
|
|
"Create the Euler integrator data.") |
81 |
|
✗ |
.add_property( |
82 |
|
|
"ng", bp::make_function(&Model::get_ng), "number of equality constraints") |
83 |
|
✗ |
.add_property( |
84 |
|
|
"nh", bp::make_function(&Model::get_nh), "number of inequality constraints") |
85 |
|
✗ |
.add_property( |
86 |
|
|
"ng_T", bp::make_function(&Model::get_ng_T), "number of equality terminal constraints") |
87 |
|
✗ |
.add_property( |
88 |
|
|
"nh_T", bp::make_function(&Model::get_nh_T), "number of inequality terminal constraints"); |
89 |
|
|
} |
90 |
|
|
}; |
91 |
|
|
|
92 |
|
|
template <typename Data> |
93 |
|
|
struct IntegratedActionDataEulerVisitor |
94 |
|
|
: public bp::def_visitor<IntegratedActionDataEulerVisitor<Data>> { |
95 |
|
|
template <class PyClass> |
96 |
|
✗ |
void visit(PyClass& cl) const { |
97 |
|
✗ |
cl.add_property( |
98 |
|
|
"differential", |
99 |
|
|
bp::make_getter(&Data::differential, |
100 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
101 |
|
|
"differential action data") |
102 |
|
✗ |
.add_property( |
103 |
|
|
"control", |
104 |
|
|
bp::make_getter(&Data::control, |
105 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
106 |
|
|
"control parametrization data") |
107 |
|
✗ |
.add_property( |
108 |
|
✗ |
"dx", bp::make_getter(&Data::dx, bp::return_internal_reference<>()), |
109 |
|
|
"state rate.") |
110 |
|
✗ |
.add_property( |
111 |
|
|
"Lwu", |
112 |
|
✗ |
bp::make_getter(&Data::Lwu, bp::return_internal_reference<>()), |
113 |
|
|
"Hessian of the cost wrt the differential control (w) and " |
114 |
|
|
"the control parameters (u)."); |
115 |
|
|
} |
116 |
|
|
}; |
117 |
|
|
|
118 |
|
|
#define CROCODDYL_INTACTION_MODEL_EULER_PYTHON_BINDINGS(Scalar) \ |
119 |
|
|
typedef IntegratedActionModelEulerTpl<Scalar> Model; \ |
120 |
|
|
typedef IntegratedActionModelAbstractTpl<Scalar> ModelBase; \ |
121 |
|
|
typedef ActionModelAbstractTpl<Scalar> ActionBase; \ |
122 |
|
|
typedef DifferentialActionModelAbstractTpl<Scalar> DiffActionBase; \ |
123 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ |
124 |
|
|
bp::class_<Model, bp::bases<ModelBase, ActionBase>>( \ |
125 |
|
|
"IntegratedActionModelEuler", \ |
126 |
|
|
"Sympletic Euler integrator for differential action models.\n\n" \ |
127 |
|
|
"This class implements a sympletic Euler integrator (a.k.a " \ |
128 |
|
|
"semi-implicit integrator) give a differential action model, i.e.:\n" \ |
129 |
|
|
" [q+, v+] = State.integrate([q, v], [v + a * dt, a * dt] * dt).", \ |
130 |
|
|
bp::init<std::shared_ptr<DiffActionBase>, bp::optional<Scalar, bool>>( \ |
131 |
|
|
bp::args("self", "diffModel", "stepTime", "withCostResidual"), \ |
132 |
|
|
"Initialize the sympletic Euler integrator.\n\n" \ |
133 |
|
|
":param diffModel: differential action model\n" \ |
134 |
|
|
":param stepTime: step time (default 1e-3)\n" \ |
135 |
|
|
":param withCostResidual: includes the cost residuals and " \ |
136 |
|
|
"derivatives (default True).")) \ |
137 |
|
|
.def(IntegratedActionModelEulerVisitor<Model>()) \ |
138 |
|
|
.def(CastVisitor<Model>()) \ |
139 |
|
|
.def(PrintableVisitor<Model>()) \ |
140 |
|
|
.def(CopyableVisitor<Model>()); |
141 |
|
|
|
142 |
|
|
#define CROCODDYL_INTACTION_DATA_EULER_PYTHON_BINDINGS(Scalar) \ |
143 |
|
|
typedef IntegratedActionDataEulerTpl<Scalar> Data; \ |
144 |
|
|
typedef IntegratedActionDataAbstractTpl<Scalar> DataBase; \ |
145 |
|
|
typedef IntegratedActionModelEulerTpl<Scalar> Model; \ |
146 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Data>>(); \ |
147 |
|
|
bp::class_<Data, bp::bases<DataBase>>( \ |
148 |
|
|
"IntegratedActionDataEuler", "Sympletic Euler integrator data.", \ |
149 |
|
|
bp::init<Model*>(bp::args("self", "model"), \ |
150 |
|
|
"Create sympletic Euler integrator data.\n\n" \ |
151 |
|
|
":param model: sympletic Euler integrator model")) \ |
152 |
|
|
.def(IntegratedActionDataEulerVisitor<Data>()) \ |
153 |
|
|
.def(CopyableVisitor<Data>()); |
154 |
|
|
|
155 |
|
✗ |
void exposeIntegratedActionEuler() { |
156 |
|
✗ |
CROCODDYL_INTACTION_MODEL_EULER_PYTHON_BINDINGS(float) |
157 |
|
✗ |
CROCODDYL_INTACTION_DATA_EULER_PYTHON_BINDINGS(float) |
158 |
|
|
} |
159 |
|
|
|
160 |
|
|
} // namespace python |
161 |
|
|
} // namespace crocoddyl |
162 |
|
|
|