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 "crocoddyl/multibody/actions/impulse-fwddyn.hpp" |
12 |
|
|
|
13 |
|
|
#include "python/crocoddyl/core/action-base.hpp" |
14 |
|
|
#include "python/crocoddyl/multibody/multibody.hpp" |
15 |
|
|
|
16 |
|
|
namespace crocoddyl { |
17 |
|
|
namespace python { |
18 |
|
|
|
19 |
|
|
template <typename Model> |
20 |
|
|
struct ActionModelImpulseFwdDynamicsVisitor |
21 |
|
|
: public bp::def_visitor<ActionModelImpulseFwdDynamicsVisitor<Model>> { |
22 |
|
|
typedef typename Model::Scalar Scalar; |
23 |
|
|
typedef typename Model::ActionDataAbstract Data; |
24 |
|
|
typedef typename Model::StateMultibody State; |
25 |
|
|
typedef typename Model::ImpulseModelMultiple Impulses; |
26 |
|
|
typedef typename Model::CostModelSum Costs; |
27 |
|
|
typedef typename Model::ConstraintModelManager Constraints; |
28 |
|
|
typedef typename Model::VectorXs VectorXs; |
29 |
|
|
template <class PyClass> |
30 |
|
✗ |
void visit(PyClass& cl) const { |
31 |
|
✗ |
cl.def(bp::init<std::shared_ptr<State>, std::shared_ptr<Impulses>, |
32 |
|
|
std::shared_ptr<Costs>, std::shared_ptr<Constraints>, |
33 |
|
|
bp::optional<Scalar, Scalar, bool>>( |
34 |
|
|
bp::args("self", "state", "impulses", "costs", "constraints", |
35 |
|
|
"r_coeff", "inv_damping", "enable_force"), |
36 |
|
|
"Initialize the constrained forward-dynamics action model.\n\n" |
37 |
|
|
"The damping factor is needed when the contact Jacobian is not " |
38 |
|
|
"full-rank. Otherwise, a good damping factor could be 1e-12. In " |
39 |
|
|
"addition, if you have cost based on forces, you need to enable " |
40 |
|
|
"the computation of the force Jacobians (i.e., " |
41 |
|
|
"enable_force=True).\n" |
42 |
|
|
":param state: multibody state\n" |
43 |
|
|
":param impulses: multiple impulse model\n" |
44 |
|
|
":param costs: stack of cost functions\n" |
45 |
|
|
":param constraints: stack of constraint functions\n" |
46 |
|
|
":param r_coeff: restitution coefficient (default 0.)\n" |
47 |
|
|
":param inv_damping: Damping factor for cholesky decomposition " |
48 |
|
|
"of JMinvJt (default 0.)\n" |
49 |
|
|
":param enable_force: Enable the computation of force Jacobians " |
50 |
|
|
"(default False)")) |
51 |
|
✗ |
.def( |
52 |
|
|
"calc", |
53 |
|
|
static_cast<void (Model::*)( |
54 |
|
|
const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, |
55 |
|
|
const Eigen::Ref<const VectorXs>&)>(&Model::calc), |
56 |
|
|
bp::args("self", "data", "x", "u"), |
57 |
|
|
"Compute the next state and cost value.\n\n" |
58 |
|
|
"It describes the time-continuous evolution of the multibody " |
59 |
|
|
"system with impulse. The impulses are modelled as holonomic " |
60 |
|
|
"constraints. Additionally it computes the cost value associated " |
61 |
|
|
"to this state and control pair.\n" |
62 |
|
|
":param data: impulse forward-dynamics action data\n" |
63 |
|
|
":param x: time-continuous state vector\n" |
64 |
|
|
":param u: time-continuous control input") |
65 |
|
✗ |
.def("calc", |
66 |
|
|
static_cast<void (Model::*)(const std::shared_ptr<Data>&, |
67 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
68 |
|
|
&Model::calc), |
69 |
|
|
bp::args("self", "data", "x")) |
70 |
|
✗ |
.def( |
71 |
|
|
"calcDiff", |
72 |
|
|
static_cast<void (Model::*)( |
73 |
|
|
const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, |
74 |
|
|
const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff), |
75 |
|
|
bp::args("self", "data", "x", "u"), |
76 |
|
|
"Compute the derivatives of the differential multibody system and " |
77 |
|
|
"its cost functions.\n\n" |
78 |
|
|
"It computes the partial derivatives of the differential multibody " |
79 |
|
|
"system and the cost function. It assumes that calc has been run " |
80 |
|
|
"first. This function builds a quadratic approximation of the " |
81 |
|
|
"action model (i.e. dynamical system and cost function).\n" |
82 |
|
|
":param data: impulse forward-dynamics action data\n" |
83 |
|
|
":param x: time-continuous state vector\n" |
84 |
|
|
":param u: time-continuous control input\n" |
85 |
|
|
"") |
86 |
|
✗ |
.def("calcDiff", |
87 |
|
|
static_cast<void (Model::*)(const std::shared_ptr<Data>&, |
88 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
89 |
|
|
&Model::calcDiff), |
90 |
|
|
bp::args("self", "data", "x")) |
91 |
|
✗ |
.def("createData", &Model::createData, bp::args("self"), |
92 |
|
|
"Create the impulse forward dynamics differential action data.") |
93 |
|
✗ |
.add_property( |
94 |
|
|
"ng", bp::make_function(&Model::get_ng), "number of equality constraints") |
95 |
|
✗ |
.add_property( |
96 |
|
|
"nh", bp::make_function(&Model::get_nh), "number of inequality constraints") |
97 |
|
✗ |
.add_property( |
98 |
|
|
"ng_T", bp::make_function(&Model::get_ng_T), "number of equality terminal constraints") |
99 |
|
✗ |
.add_property( |
100 |
|
|
"nh_T", bp::make_function(&Model::get_nh_T), "number of inequality terminal constraints") |
101 |
|
✗ |
.add_property("pinocchio", |
102 |
|
|
bp::make_function(&Model::get_pinocchio, |
103 |
|
✗ |
bp::return_internal_reference<>()), |
104 |
|
|
"multibody model (i.e. pinocchio model)") |
105 |
|
✗ |
.add_property( |
106 |
|
|
"impulses", |
107 |
|
|
bp::make_function(&Model::get_impulses, |
108 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
109 |
|
|
"multiple contact model") |
110 |
|
✗ |
.add_property( |
111 |
|
|
"costs", |
112 |
|
|
bp::make_function(&Model::get_costs, |
113 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
114 |
|
|
"total cost model") |
115 |
|
✗ |
.add_property( |
116 |
|
|
"constraints", |
117 |
|
|
bp::make_function(&Model::get_constraints, |
118 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
119 |
|
|
"constraint model manager") |
120 |
|
✗ |
.add_property("armature", |
121 |
|
|
bp::make_function(&Model::get_armature, |
122 |
|
✗ |
bp::return_internal_reference<>()), |
123 |
|
|
bp::make_function(&Model::set_armature), |
124 |
|
|
"set an armature mechanism in the joints") |
125 |
|
✗ |
.add_property("r_coeff", |
126 |
|
|
bp::make_function(&Model::get_restitution_coefficient), |
127 |
|
|
bp::make_function(&Model::set_restitution_coefficient), |
128 |
|
|
"Restitution coefficient that describes elastic impacts") |
129 |
|
✗ |
.add_property("JMinvJt_damping", |
130 |
|
|
bp::make_function(&Model::get_damping_factor), |
131 |
|
|
bp::make_function(&Model::set_damping_factor), |
132 |
|
|
"Damping factor for cholesky decomposition of JMinvJt"); |
133 |
|
|
} |
134 |
|
|
}; |
135 |
|
|
|
136 |
|
|
template <typename Data> |
137 |
|
|
struct ActionDataImpulseFwdDynamicsVisitor |
138 |
|
|
: public bp::def_visitor<ActionDataImpulseFwdDynamicsVisitor<Data>> { |
139 |
|
|
template <class PyClass> |
140 |
|
✗ |
void visit(PyClass& cl) const { |
141 |
|
✗ |
cl.add_property( |
142 |
|
|
"pinocchio", |
143 |
|
✗ |
bp::make_getter(&Data::pinocchio, bp::return_internal_reference<>()), |
144 |
|
|
"pinocchio data") |
145 |
|
✗ |
.add_property("multibody", |
146 |
|
|
bp::make_getter(&Data::multibody, |
147 |
|
✗ |
bp::return_internal_reference<>()), |
148 |
|
|
"multibody data") |
149 |
|
✗ |
.add_property( |
150 |
|
|
"costs", |
151 |
|
|
bp::make_getter(&Data::costs, |
152 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
153 |
|
|
"total cost data") |
154 |
|
✗ |
.add_property( |
155 |
|
|
"constraints", |
156 |
|
|
bp::make_getter(&Data::constraints, |
157 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
158 |
|
|
"constraint data") |
159 |
|
✗ |
.add_property( |
160 |
|
|
"Kinv", |
161 |
|
✗ |
bp::make_getter(&Data::Kinv, bp::return_internal_reference<>()), |
162 |
|
|
"inverse of the KKT matrix") |
163 |
|
✗ |
.add_property( |
164 |
|
|
"df_dx", |
165 |
|
✗ |
bp::make_getter(&Data::df_dx, bp::return_internal_reference<>()), |
166 |
|
|
"Jacobian of the contact impulse"); |
167 |
|
|
} |
168 |
|
|
}; |
169 |
|
|
|
170 |
|
|
#define CROCODDYL_ACTION_MODEL_IMPULSE_FWDDYN_PYTHON_BINDINGS(Scalar) \ |
171 |
|
|
typedef ActionModelImpulseFwdDynamicsTpl<Scalar> Model; \ |
172 |
|
|
typedef ActionModelAbstractTpl<Scalar> ModelBase; \ |
173 |
|
|
typedef typename Model::StateMultibody State; \ |
174 |
|
|
typedef typename Model::ImpulseModelMultiple Impulses; \ |
175 |
|
|
typedef typename Model::CostModelSum Costs; \ |
176 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ |
177 |
|
|
bp::class_<Model, bp::bases<ModelBase>>( \ |
178 |
|
|
"ActionModelImpulseFwdDynamics", \ |
179 |
|
|
"Action model for impulse forward dynamics in multibody systems.\n\n" \ |
180 |
|
|
"The impulse is modelled as holonomic constraits in the contact frame. " \ |
181 |
|
|
"There is also a custom implementation in case of system with " \ |
182 |
|
|
"armatures. If you want to include the armature, you need to use " \ |
183 |
|
|
"set_armature(). On the other hand, the stack of cost functions are " \ |
184 |
|
|
"implemented in CostModelSum().", \ |
185 |
|
|
bp::init<std::shared_ptr<State>, std::shared_ptr<Impulses>, \ |
186 |
|
|
std::shared_ptr<Costs>, bp::optional<Scalar, Scalar, bool>>( \ |
187 |
|
|
bp::args("self", "state", " impulses", "costs", "r_coeff", \ |
188 |
|
|
"inv_damping", "enable_force"), \ |
189 |
|
|
"Initialize the impulse forward-dynamics action model.\n\n" \ |
190 |
|
|
"The damping factor is needed when the contact Jacobian is not " \ |
191 |
|
|
"full-rank. Otherwise, a good damping factor could be 1e-12. In " \ |
192 |
|
|
"addition, if you have cost based on forces, you need to enable " \ |
193 |
|
|
"the computation of the force Jacobians (i.e., " \ |
194 |
|
|
"enable_force=True).\n" \ |
195 |
|
|
":param state: multibody state\n" \ |
196 |
|
|
":param impulses: multiple impulse model\n" \ |
197 |
|
|
":param costs: stack of cost functions\n" \ |
198 |
|
|
":param r_coeff: restitution coefficient (default 0.)\n" \ |
199 |
|
|
":param inv_damping: Damping factor for cholesky decomposition of " \ |
200 |
|
|
"JMinvJt (default 0.)\n" \ |
201 |
|
|
":param enable_force: Enable the computation of force Jacobians " \ |
202 |
|
|
"(default False)")) \ |
203 |
|
|
.def(ActionModelImpulseFwdDynamicsVisitor<Model>()) \ |
204 |
|
|
.def(CastVisitor<Model>()) \ |
205 |
|
|
.def(PrintableVisitor<Model>()) \ |
206 |
|
|
.def(CopyableVisitor<Model>()); |
207 |
|
|
|
208 |
|
|
#define CROCODDYL_ACTION_DATA_IMPULSE_FWDDYN_PYTHON_BINDINGS(Scalar) \ |
209 |
|
|
typedef ActionDataImpulseFwdDynamicsTpl<Scalar> Data; \ |
210 |
|
|
typedef ActionDataAbstractTpl<Scalar> DataBase; \ |
211 |
|
|
typedef ActionModelImpulseFwdDynamicsTpl<Scalar> Model; \ |
212 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Data>>(); \ |
213 |
|
|
bp::class_<Data, bp::bases<DataBase>>( \ |
214 |
|
|
"ActionDataImpulseFwdDynamics", \ |
215 |
|
|
"Action data for the impulse forward dynamics system.", \ |
216 |
|
|
bp::init<Model*>(bp::args("self", "model"), \ |
217 |
|
|
"Create impulse forward-dynamics action data.\n\n" \ |
218 |
|
|
":param model: impulse forward-dynamics action model")) \ |
219 |
|
|
.def(ActionDataImpulseFwdDynamicsVisitor<Data>()) \ |
220 |
|
|
.def(CopyableVisitor<Data>()); |
221 |
|
|
|
222 |
|
✗ |
void exposeActionImpulseFwdDynamics() { |
223 |
|
✗ |
CROCODDYL_ACTION_MODEL_IMPULSE_FWDDYN_PYTHON_BINDINGS(double) |
224 |
|
✗ |
CROCODDYL_ACTION_DATA_IMPULSE_FWDDYN_PYTHON_BINDINGS(double) |
225 |
|
|
} |
226 |
|
|
|
227 |
|
|
} // namespace python |
228 |
|
|
} // namespace crocoddyl |
229 |
|
|
|