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