Line |
Branch |
Exec |
Source |
1 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
2 |
|
|
// BSD 3-Clause License |
3 |
|
|
// |
4 |
|
|
// Copyright (C) 2020-2025, University of Edinburgh, Heriot-Watt University |
5 |
|
|
// Copyright note valid unless otherwise stated in individual files. |
6 |
|
|
// All rights reserved. |
7 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
8 |
|
|
|
9 |
|
|
// Auto-generated file for float |
10 |
|
|
#include "crocoddyl/core/constraints/constraint-manager.hpp" |
11 |
|
|
|
12 |
|
|
#include "python/crocoddyl/core/action-base.hpp" |
13 |
|
|
#include "python/crocoddyl/core/core.hpp" |
14 |
|
|
#include "python/crocoddyl/core/diff-action-base.hpp" |
15 |
|
|
#include "python/crocoddyl/utils/map-converter.hpp" |
16 |
|
|
#include "python/crocoddyl/utils/set-converter.hpp" |
17 |
|
|
|
18 |
|
|
namespace crocoddyl { |
19 |
|
|
namespace python { |
20 |
|
|
|
21 |
|
|
template <typename Model> |
22 |
|
|
struct ConstraintItemVisitor |
23 |
|
|
: public bp::def_visitor<ConstraintItemVisitor<Model>> { |
24 |
|
|
template <class PyClass> |
25 |
|
✗ |
void visit(PyClass& cl) const { |
26 |
|
✗ |
cl.def_readwrite("name", &Model::name, "constraint name") |
27 |
|
✗ |
.add_property( |
28 |
|
|
"constraint", |
29 |
|
|
bp::make_getter(&Model::constraint, |
30 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
31 |
|
|
"constraint model") |
32 |
|
✗ |
.def_readwrite("active", &Model::active, "constraint status"); |
33 |
|
|
} |
34 |
|
|
}; |
35 |
|
|
|
36 |
|
|
template <typename Model> |
37 |
|
|
struct ConstraintModelManagerVisitor |
38 |
|
|
: public bp::def_visitor<ConstraintModelManagerVisitor<Model>> { |
39 |
|
✗ |
BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS( |
40 |
|
|
ConstraintModelManager_addConstraint_wrap, Model::addConstraint, 2, 3) |
41 |
|
|
typedef typename Model::ConstraintDataManager Data; |
42 |
|
|
typedef typename Model::StateAbstract State; |
43 |
|
|
typedef typename Model::VectorXs VectorXs; |
44 |
|
|
template <class PyClass> |
45 |
|
✗ |
void visit(PyClass& cl) const { |
46 |
|
✗ |
cl.def(bp::init<std::shared_ptr<State>, std::size_t>( |
47 |
|
|
bp::args("self", "state", "nu"), |
48 |
|
|
"Initialize the total constraint model.\n\n" |
49 |
|
|
"For this case the default nu is equals to model.nv.\n" |
50 |
|
|
":param state: state description\n" |
51 |
|
|
":param nu: dimension of control vector")) |
52 |
|
✗ |
.def(bp::init<std::shared_ptr<State>>( |
53 |
|
|
bp::args("self", "state"), |
54 |
|
|
"Initialize the total constraint model.\n\n" |
55 |
|
|
"For this case the default nu is equals to model.nv.\n" |
56 |
|
|
":param state: state description")) |
57 |
|
✗ |
.def("addConstraint", &Model::addConstraint, |
58 |
|
✗ |
ConstraintModelManager_addConstraint_wrap( |
59 |
|
|
bp::args("self", "name", "constraint", "active"), |
60 |
|
|
"Add a constraint item.\n\n" |
61 |
|
|
":param name: constraint name\n" |
62 |
|
|
":param constraint: constraint model\n" |
63 |
|
|
":param active: True if the constraint is activated (default " |
64 |
|
|
"true)")) |
65 |
|
✗ |
.def("removeConstraint", &Model::removeConstraint, |
66 |
|
|
bp::args("self", "name"), |
67 |
|
|
"Remove a constraint item.\n\n" |
68 |
|
|
":param name: constraint name") |
69 |
|
✗ |
.def("changeConstraintStatus", &Model::changeConstraintStatus, |
70 |
|
|
bp::args("self", "name", "active"), |
71 |
|
|
"Change the constraint status.\n\n" |
72 |
|
|
":param name: constraint name\n" |
73 |
|
|
":param active: constraint status (true for active and false for " |
74 |
|
|
"inactive)") |
75 |
|
✗ |
.def( |
76 |
|
|
"calc", |
77 |
|
|
static_cast<void (Model::*)( |
78 |
|
|
const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, |
79 |
|
|
const Eigen::Ref<const VectorXs>&)>(&Model::calc), |
80 |
|
|
bp::args("self", "data", "x", "u"), |
81 |
|
|
"Compute the total constraint.\n\n" |
82 |
|
|
":param data: constraint-manager data\n" |
83 |
|
|
":param x: state point (dim. state.nx)\n" |
84 |
|
|
":param u: control input (dim. nu)") |
85 |
|
✗ |
.def("calc", |
86 |
|
|
static_cast<void (Model::*)(const std::shared_ptr<Data>&, |
87 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
88 |
|
|
&Model::calc), |
89 |
|
|
bp::args("self", "data", "x"), |
90 |
|
|
"Compute the total constraint value for nodes that depends only " |
91 |
|
|
"on the state.\n\n" |
92 |
|
|
"It updates the total constraint based on the state only. This " |
93 |
|
|
"function is used in the terminal nodes of an optimal control " |
94 |
|
|
"problem.\n" |
95 |
|
|
":param data: constraint-manager data\n" |
96 |
|
|
":param x: state point (dim. state.nx)") |
97 |
|
✗ |
.def( |
98 |
|
|
"calcDiff", |
99 |
|
|
static_cast<void (Model::*)( |
100 |
|
|
const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, |
101 |
|
|
const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff), |
102 |
|
|
bp::args("self", "data", "x", "u"), |
103 |
|
|
"Compute the derivatives of the total constraint.\n\n" |
104 |
|
|
"It assumes that calc has been run first.\n" |
105 |
|
|
":param data: constraint-manager data\n" |
106 |
|
|
":param x: state point (dim. state.nx)\n" |
107 |
|
|
":param u: control input (dim. nu)\n") |
108 |
|
✗ |
.def("calcDiff", |
109 |
|
|
static_cast<void (Model::*)(const std::shared_ptr<Data>&, |
110 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
111 |
|
|
&Model::calcDiff), |
112 |
|
|
bp::args("self", "data", "x"), |
113 |
|
|
"Compute the Jacobian of the total constraint for nodes that " |
114 |
|
|
"depends on the state only.\n\n" |
115 |
|
|
"It updates the Jacobian of the total constraint based on the " |
116 |
|
|
"state only. This function is used in the terminal nodes of an " |
117 |
|
|
"optimal control problem.\n" |
118 |
|
|
":param data: constraint-manager data\n" |
119 |
|
|
":param x: state point (dim. state.nx)") |
120 |
|
✗ |
.def("createData", &Model::createData, |
121 |
|
✗ |
bp::with_custodian_and_ward_postcall<0, 2>(), |
122 |
|
|
bp::args("self", "data"), |
123 |
|
|
"Create the total constraint data.\n\n" |
124 |
|
|
":param data: shared data\n" |
125 |
|
|
":return total constraint data.") |
126 |
|
✗ |
.add_property( |
127 |
|
|
"state", |
128 |
|
|
bp::make_function(&Model::get_state, |
129 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
130 |
|
|
"state description") |
131 |
|
✗ |
.add_property( |
132 |
|
|
"constraints", |
133 |
|
|
bp::make_function(&Model::get_constraints, |
134 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
135 |
|
|
"stack of constraints") |
136 |
|
✗ |
.add_property("nu", bp::make_function(&Model::get_nu), |
137 |
|
|
"dimension of control vector") |
138 |
|
✗ |
.add_property("ng", bp::make_function(&Model::get_ng), |
139 |
|
|
"number of active inequality constraints") |
140 |
|
✗ |
.add_property("nh", bp::make_function(&Model::get_nh), |
141 |
|
|
"number of active equality constraints") |
142 |
|
✗ |
.add_property("ng_T", bp::make_function(&Model::get_ng_T), |
143 |
|
|
"number of active inequality terminal constraints") |
144 |
|
✗ |
.add_property("nh_T", bp::make_function(&Model::get_nh_T), |
145 |
|
|
"number of active equality terminal constraints") |
146 |
|
✗ |
.add_property( |
147 |
|
|
"active_set", |
148 |
|
|
bp::make_function(&Model::get_active_set, |
149 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
150 |
|
|
"name of the active set of constraint items") |
151 |
|
✗ |
.add_property( |
152 |
|
|
"inactive_set", |
153 |
|
|
bp::make_function(&Model::get_inactive_set, |
154 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
155 |
|
|
"name of the inactive set of constraint items") |
156 |
|
✗ |
.add_property("g_lb", |
157 |
|
|
bp::make_function(&Model::get_lb, |
158 |
|
✗ |
bp::return_internal_reference<>()), |
159 |
|
|
"lower bound of the inequality constraints") |
160 |
|
✗ |
.add_property("g_ub", |
161 |
|
|
bp::make_function(&Model::get_ub, |
162 |
|
✗ |
bp::return_internal_reference<>()), |
163 |
|
|
"upper bound of the inequality constraints") |
164 |
|
✗ |
.def("getConstraintStatus", &Model::getConstraintStatus, |
165 |
|
|
bp::args("self", "name"), |
166 |
|
|
"Return the constraint status of a given constraint name.\n\n" |
167 |
|
|
":param name: constraint name"); |
168 |
|
|
} |
169 |
|
|
}; |
170 |
|
|
|
171 |
|
|
template <typename Data> |
172 |
|
|
struct ConstraintDataManagerVisitor |
173 |
|
|
: public bp::def_visitor<ConstraintDataManagerVisitor<Data>> { |
174 |
|
✗ |
BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(ConstraintDataManager_resizeConst_wrap, |
175 |
|
|
Data::resize, 1, 2) |
176 |
|
✗ |
BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(ConstraintDataManager_resize_wrap, |
177 |
|
|
Data::resize, 2, 3) |
178 |
|
|
typedef typename Data::Scalar Scalar; |
179 |
|
|
typedef ConstraintModelManagerTpl<Scalar> Model; |
180 |
|
|
typedef DifferentialActionModelAbstractTpl<Scalar> DifferentialActionModel; |
181 |
|
|
typedef DifferentialActionDataAbstractTpl<Scalar> DifferentialActionData; |
182 |
|
|
typedef ActionModelAbstractTpl<Scalar> ActionModel; |
183 |
|
|
typedef ActionDataAbstractTpl<Scalar> ActionData; |
184 |
|
|
template <class PyClass> |
185 |
|
✗ |
void visit(PyClass& cl) const { |
186 |
|
✗ |
cl.def( |
187 |
|
|
"shareMemory", &Data::template shareMemory<DifferentialActionData>, |
188 |
|
|
bp::args("self", "data"), |
189 |
|
|
"Share memory with a given differential action data\n\n" |
190 |
|
|
":param model: differential action data that we want to share memory") |
191 |
|
✗ |
.def("shareMemory", &Data::template shareMemory<ActionData>, |
192 |
|
|
bp::args("self", "data"), |
193 |
|
|
"Share memory with a given action data\n\n" |
194 |
|
|
":param model: action data that we want to share memory") |
195 |
|
✗ |
.def("resize", &Data::template resize<Model>, |
196 |
|
✗ |
bp::with_custodian_and_ward_postcall<0, 1>(), |
197 |
|
✗ |
ConstraintDataManager_resizeConst_wrap( |
198 |
|
|
bp::args("self", "model", "running_node"), |
199 |
|
|
"Resize the data given differential action data\n\n" |
200 |
|
|
":param model: constraint manager model that defines how to " |
201 |
|
|
"resize " |
202 |
|
|
"the data\n" |
203 |
|
|
":param running_node: true if we are resizing for a running " |
204 |
|
|
"node, false for terminal ones (default true)")) |
205 |
|
✗ |
.def( |
206 |
|
|
"resize", |
207 |
|
|
&Data::template resize<DifferentialActionModel, |
208 |
|
|
DifferentialActionData>, |
209 |
|
✗ |
bp::with_custodian_and_ward_postcall<0, 2>(), |
210 |
|
✗ |
ConstraintDataManager_resize_wrap( |
211 |
|
|
bp::args("self", "model", "data", "running_node"), |
212 |
|
|
"Resize the data given differential action data\n\n" |
213 |
|
|
":param model: differential action model that defines how to " |
214 |
|
|
"resize " |
215 |
|
|
"the data\n" |
216 |
|
|
":param data: differential action data that we want to resize\n" |
217 |
|
|
":param running_node: true if we are resizing for a running " |
218 |
|
|
"node, false for terminal ones (default true)")) |
219 |
|
✗ |
.def("resize", &Data::template resize<ActionModel, ActionData>, |
220 |
|
✗ |
bp::with_custodian_and_ward_postcall<0, 2>(), |
221 |
|
✗ |
ConstraintDataManager_resize_wrap( |
222 |
|
|
bp::args("self", "model", "data", "running_node"), |
223 |
|
|
"Resize the data given action data\n\n" |
224 |
|
|
":param model: action model that defines how to resize the " |
225 |
|
|
"data\n" |
226 |
|
|
":param data: action data that we want to resize\n" |
227 |
|
|
":param running_node: true if we are resizing for a running " |
228 |
|
|
"node, false for terminal ones (default true)")) |
229 |
|
✗ |
.add_property( |
230 |
|
|
"constraints", |
231 |
|
|
bp::make_getter(&Data::constraints, |
232 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
233 |
|
|
"stack of constraints data") |
234 |
|
✗ |
.add_property( |
235 |
|
|
"shared", |
236 |
|
✗ |
bp::make_getter(&Data::shared, bp::return_internal_reference<>()), |
237 |
|
|
"shared data") |
238 |
|
✗ |
.add_property( |
239 |
|
|
"g", |
240 |
|
|
bp::make_function(&Data::get_g, |
241 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
242 |
|
|
bp::make_function(&Data::set_g), "Inequality constraint residual") |
243 |
|
✗ |
.add_property( |
244 |
|
|
"Gx", |
245 |
|
|
bp::make_function(&Data::get_Gx, |
246 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
247 |
|
|
bp::make_function(&Data::set_Gx), |
248 |
|
|
"Jacobian of the inequality constraint") |
249 |
|
✗ |
.add_property( |
250 |
|
|
"Gu", |
251 |
|
|
bp::make_function(&Data::get_Gu, |
252 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
253 |
|
|
bp::make_function(&Data::set_Gu), |
254 |
|
|
"Jacobian of the inequality constraint") |
255 |
|
✗ |
.add_property( |
256 |
|
|
"h", |
257 |
|
|
bp::make_function(&Data::get_h, |
258 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
259 |
|
|
bp::make_function(&Data::set_h), "Equality constraint residual") |
260 |
|
✗ |
.add_property( |
261 |
|
|
"Hx", |
262 |
|
|
bp::make_function(&Data::get_Hx, |
263 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
264 |
|
|
bp::make_function(&Data::set_Hx), |
265 |
|
|
"Jacobian of the equality constraint") |
266 |
|
✗ |
.add_property( |
267 |
|
|
"Hu", |
268 |
|
|
bp::make_function(&Data::get_Hu, |
269 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
270 |
|
|
bp::make_function(&Data::set_Hu), |
271 |
|
|
"Jacobian of the equality constraint"); |
272 |
|
|
} |
273 |
|
|
}; |
274 |
|
|
|
275 |
|
|
#define CROCODDYL_CONSTRAINT_ITEM_PYTHON_BINDINGS(Scalar) \ |
276 |
|
|
typedef ConstraintItemTpl<Scalar> Item; \ |
277 |
|
|
typedef Item::ConstraintModelAbstract ConstraintModel; \ |
278 |
|
|
typedef std::shared_ptr<Item> ConstraintItemPtr; \ |
279 |
|
|
StdMapPythonVisitor< \ |
280 |
|
|
std::string, ConstraintItemPtr, std::less<std::string>, \ |
281 |
|
|
std::allocator<std::pair<const std::string, ConstraintItemPtr>>, \ |
282 |
|
|
true>::expose("StdMap_ConstraintItem"); \ |
283 |
|
|
typedef ConstraintDataAbstractTpl<Scalar> ConstraintData; \ |
284 |
|
|
typedef std::shared_ptr<ConstraintData> ConstraintDataPtr; \ |
285 |
|
|
StdMapPythonVisitor< \ |
286 |
|
|
std::string, ConstraintDataPtr, std::less<std::string>, \ |
287 |
|
|
std::allocator<std::pair<const std::string, ConstraintDataPtr>>, \ |
288 |
|
|
true>::expose("StdMap_ConstraintData"); \ |
289 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Item>>(); \ |
290 |
|
|
bp::class_<Item>("ConstraintItem", "Describe a constraint item.\n\n", \ |
291 |
|
|
bp::init<std::string, std::shared_ptr<ConstraintModel>, \ |
292 |
|
|
bp::optional<bool>>( \ |
293 |
|
|
bp::args("self", "name", "constraint", "active"), \ |
294 |
|
|
"Initialize the constraint item.\n\n" \ |
295 |
|
|
":param name: constraint name\n" \ |
296 |
|
|
":param constraint: constraint model\n" \ |
297 |
|
|
":param active: True if the constraint is activated " \ |
298 |
|
|
"(default true)")) \ |
299 |
|
|
.def(ConstraintItemVisitor<Item>()) \ |
300 |
|
|
.def(CastVisitor<Item>()) \ |
301 |
|
|
.def(PrintableVisitor<Item>()) \ |
302 |
|
|
.def(CopyableVisitor<Item>()); |
303 |
|
|
|
304 |
|
|
#define CROCODDYL_CONSTRAINT_MODEL_MANAGER_PYTHON_BINDINGS(Scalar) \ |
305 |
|
|
typedef ConstraintModelManagerTpl<Scalar> Model; \ |
306 |
|
|
typedef Model::StateAbstract State; \ |
307 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ |
308 |
|
|
bp::class_<Model>("ConstraintModelManager", \ |
309 |
|
|
bp::init<std::shared_ptr<State>, std::size_t>( \ |
310 |
|
|
bp::args("self", "state", "nu"), \ |
311 |
|
|
"Initialize the total constraint model.\n\n" \ |
312 |
|
|
":param state: state description\n" \ |
313 |
|
|
":param nu: dimension of control vector")) \ |
314 |
|
|
.def(ConstraintModelManagerVisitor<Model>()) \ |
315 |
|
|
.def(CastVisitor<Model>()) \ |
316 |
|
|
.def(PrintableVisitor<Model>()) \ |
317 |
|
|
.def(CopyableVisitor<Model>()); |
318 |
|
|
|
319 |
|
|
#define CROCODDYL_CONSTRAINT_DATA_MANAGER_PYTHON_BINDINGS(Scalar) \ |
320 |
|
|
typedef ConstraintDataManagerTpl<Scalar> Data; \ |
321 |
|
|
typedef ConstraintModelManagerTpl<Scalar> Model; \ |
322 |
|
|
typedef Model::DataCollectorAbstract DataCollector; \ |
323 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Data>>(); \ |
324 |
|
|
bp::class_<Data>( \ |
325 |
|
|
"ConstraintDataManager", "Class for total constraint data.\n\n", \ |
326 |
|
|
bp::init<Model*, DataCollector*>( \ |
327 |
|
|
bp::args("self", "model", "data"), \ |
328 |
|
|
"Create total constraint data.\n\n" \ |
329 |
|
|
":param model: total constraint model\n" \ |
330 |
|
|
":param data: shared data")[bp::with_custodian_and_ward<1, 3>()]) \ |
331 |
|
|
.def(ConstraintDataManagerVisitor<Data>()) \ |
332 |
|
|
.def(CopyableVisitor<Data>()); |
333 |
|
|
|
334 |
|
✗ |
void exposeConstraintManager() { |
335 |
|
✗ |
CROCODDYL_CONSTRAINT_ITEM_PYTHON_BINDINGS(float) |
336 |
|
✗ |
CROCODDYL_CONSTRAINT_MODEL_MANAGER_PYTHON_BINDINGS(float) |
337 |
|
✗ |
CROCODDYL_CONSTRAINT_DATA_MANAGER_PYTHON_BINDINGS(float) |
338 |
|
|
} |
339 |
|
|
|
340 |
|
|
} // namespace python |
341 |
|
|
} // namespace crocoddyl |
342 |
|
|
|