GCC Code Coverage Report


Directory: ./
File: bindings/python/crocoddyl/core/constraint-base-float.cpp
Date: 2025-04-18 16:41:15
Exec Total Coverage
Lines: 0 46 0.0%
Branches: 0 144 0.0%

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 "python/crocoddyl/core/constraint-base.hpp"
11
12 #define SCALAR_float32
13
14 namespace crocoddyl {
15 namespace python {
16
17 template <typename Model>
18 struct ConstraintModelAbstractVisitor
19 : public bp::def_visitor<ConstraintModelAbstractVisitor<Model>> {
20 typedef typename Model::ConstraintModel ConstraintModel;
21 typedef typename Model::ConstraintData ConstraintData;
22 typedef typename Model::State State;
23 typedef typename Model::VectorXs VectorXs;
24 template <class PyClass>
25 void visit(PyClass& cl) const {
26 cl
27 .def(bp::init<std::shared_ptr<State>, std::size_t, std::size_t,
28 std::size_t, bp::optional<bool>>(
29 bp::args("self", "state", "nu", "ng", "nh", "T_const"),
30 "Initialize the constraint model.\n\n"
31 ":param state: state description\n"
32 ":param nu: dimension of control vector (default state.nv)\n"
33 ":param ng: number of inequality constraints\n"
34 ":param nh: number of equality constraints\n"
35 ":param T_const: True if this is a constraint in both running and "
36 "terminal nodes.\n"
37 " False if it is a constraint on running nodes only "
38 "(default true)"))
39 .def(bp::init<std::shared_ptr<State>, std::size_t, std::size_t,
40 bp::optional<bool>>(
41 bp::args("self", "state", "ng", "nh", "T_const"),
42 "Initialize the constraint model.\n\n"
43 ":param state: state description\n"
44 ":param ng: number of inequality constraints\n"
45 ":param nh: number of equality constraints\n"
46 ":param T_const: True if this is a constraint in both running and "
47 "terminal nodes.\n"
48 " False if it is a constraint on running nodes only "
49 "(default true)"))
50 .def("calc", pure_virtual(&Model::calc),
51 bp::args("self", "data", "x", "u"),
52 "Compute the constraint value.\n\n"
53 ":param data: constraint data\n"
54 ":param x: state point (dim. state.nx)\n"
55 ":param u: control input (dim. nu)")
56 .def("calc",
57 static_cast<void (ConstraintModel::*)(
58 const std::shared_ptr<ConstraintData>&,
59 const Eigen::Ref<const VectorXs>&)>(&ConstraintModel::calc),
60 bp::args("self", "data", "x"),
61 "Compute the constraint value for nodes that depends only on the "
62 "state.\n\n"
63 "It updates the constraint based on the state only.\n"
64 "This function is commonly used in the terminal nodes of an "
65 "optimal "
66 "control problem.\n"
67 ":param data: constraint data\n"
68 ":param x: state point (dim. state.nx)")
69 .def("calcDiff", pure_virtual(&Model::calcDiff),
70 bp::args("self", "data", "x", "u"),
71 "Compute the Jacobians of the constraint function.\n\n"
72 "It computes the Jacobians of the constraint function.\n"
73 "It assumes that calc has been run first.\n"
74 ":param data: constraint data\n"
75 ":param x: state point (dim. state.nx)\n"
76 ":param u: control input (dim. nu)\n")
77 .def(
78 "calcDiff",
79 static_cast<void (ConstraintModel::*)(
80 const std::shared_ptr<ConstraintData>&,
81 const Eigen::Ref<const VectorXs>&)>(&ConstraintModel::calcDiff),
82 bp::args("self", "data", "x"),
83 "Compute the Jacobian of the constraint with respect to the state "
84 "only.\n\n"
85 "It computes the Jacobian of the constraint function based on the "
86 "state only.\n"
87 "This function is commonly used in the terminal nodes of an "
88 "optimal "
89 "control problem.\n"
90 ":param data: constraint data\n"
91 ":param x: state point (dim. state.nx)")
92 .def("createData", &Model::createData,
93 bp::with_custodian_and_ward_postcall<0, 2>(),
94 bp::args("self", "data"),
95 "Create the constraint data.\n\n"
96 "Each constraint model has its own data that needs to be "
97 "allocated. "
98 "This function\n"
99 "returns the allocated data for a predefined constraint.\n"
100 ":param data: shared data\n"
101 ":return constraint data.")
102 .def("createData", &Model::default_createData,
103 bp::with_custodian_and_ward_postcall<0, 2>())
104 .def("updateBounds", &Model::update_bounds,
105 bp::args("self", "lower", "upper"),
106 "Update the lower and upper bounds.\n\n"
107 ":param lower: lower bound\n"
108 ":param upper: upper bound")
109 .def("removeBounds", &Model::remove_bounds, bp::args("self"),
110 "Remove the bounds.")
111 .add_property(
112 "state",
113 bp::make_function(&Model::get_state,
114 bp::return_value_policy<bp::return_by_value>()),
115 "state description")
116 .add_property(
117 "residual",
118 bp::make_function(&Model::get_residual,
119 bp::return_value_policy<bp::return_by_value>()),
120 "residual model")
121 .add_property("type", bp::make_function(&Model::get_type),
122 "type of constraint")
123 .add_property("lb",
124 bp::make_function(&Model::get_lb,
125 bp::return_internal_reference<>()),
126 "lower bound of constraint")
127 .add_property("ub",
128 bp::make_function(&Model::get_ub,
129 bp::return_internal_reference<>()),
130 "upper bound of constraint")
131 .add_property("nu", bp::make_function(&Model::get_nu),
132 "dimension of control vector")
133 .add_property("ng", bp::make_function(&Model::get_ng),
134 "number of inequality constraints")
135 .add_property("nh", bp::make_function(&Model::get_nh),
136 "number of equality constraints")
137 .add_property(
138 "T_constraint", bp::make_function(&Model::get_T_constraint),
139 "True if the constraint is imposed in terminal nodes as well");
140 }
141 };
142
143 template <typename Data>
144 struct ConstraintDataAbstractVisitor
145 : public bp::def_visitor<ConstraintDataAbstractVisitor<Data>> {
146 template <class PyClass>
147 void visit(PyClass& cl) const {
148 cl.add_property(
149 "shared",
150 bp::make_getter(&Data::shared, bp::return_internal_reference<>()),
151 "shared data")
152 .add_property(
153 "residual",
154 bp::make_getter(&Data::residual,
155 bp::return_value_policy<bp::return_by_value>()),
156 "residual data")
157 .add_property(
158 "g", bp::make_getter(&Data::g, bp::return_internal_reference<>()),
159 bp::make_setter(&Data::g), "inequality constraint residual")
160 .add_property(
161 "Gx", bp::make_getter(&Data::Gx, bp::return_internal_reference<>()),
162 bp::make_setter(&Data::Gx), "Jacobian of the inequality constraint")
163 .add_property(
164 "Gu", bp::make_getter(&Data::Gu, bp::return_internal_reference<>()),
165 bp::make_setter(&Data::Gu), "Jacobian of the inequality constraint")
166 .add_property(
167 "h", bp::make_getter(&Data::h, bp::return_internal_reference<>()),
168 bp::make_setter(&Data::h), "equality constraint residual")
169 .add_property(
170 "Hx", bp::make_getter(&Data::Hx, bp::return_internal_reference<>()),
171 bp::make_setter(&Data::Hx), "Jacobian of the equality constraint")
172 .add_property(
173 "Hu", bp::make_getter(&Data::Hu, bp::return_internal_reference<>()),
174 bp::make_setter(&Data::Hu), "Jacobian of the equality constraint");
175 }
176 };
177
178 #define CROCODDYL_CONSTRAINT_MODEL_ABSTRACT_PYTHON_BINDINGS(Scalar) \
179 typedef ConstraintModelAbstractTpl<Scalar> Model; \
180 typedef ConstraintModelAbstractTpl_wrap<Scalar> Model_wrap; \
181 typedef StateAbstractTpl<Scalar> State; \
182 typedef Model::ResidualModelAbstract ResidualModel; \
183 bp::register_ptr_to_python<std::shared_ptr<Model>>(); \
184 bp::class_<Model_wrap, boost::noncopyable>( \
185 "ConstraintModelAbstract", \
186 "Abstract multibody constraint models.\n\n" \
187 "A constraint model defines both: inequality g(x,u) and equality h(x, " \
188 "u) constraints. The constraint function depends on the state point x, " \
189 "which lies in the state manifold described with a nx-tuple, its " \
190 "velocity xd that belongs to the tangent space with ndx dimension, and " \
191 "the control input u.", \
192 bp::init<std::shared_ptr<State>, std::shared_ptr<ResidualModel>, \
193 std::size_t, std::size_t>( \
194 bp::args("self", "state", "residual", "ng", "nh"), \
195 "Initialize the constraint model.\n\n" \
196 ":param state: state description\n" \
197 ":param residual: residual model\n" \
198 ":param ng: number of inequality constraints\n" \
199 ":param nh: number of equality constraints")) \
200 .def(ConstraintModelAbstractVisitor<Model_wrap>()) \
201 .def(PrintableVisitor<Model_wrap>()) \
202 .def(CopyableVisitor<Model_wrap>());
203
204 #define CROCODDYL_CONSTRAINT_DATA_ABSTRACT_PYTHON_BINDINGS(Scalar) \
205 typedef ConstraintDataAbstractTpl<Scalar> Data; \
206 typedef ConstraintModelAbstractTpl<Scalar> Model; \
207 typedef Model::DataCollectorAbstract DataCollector; \
208 bp::register_ptr_to_python<std::shared_ptr<Data>>(); \
209 bp::class_<Data, boost::noncopyable>( \
210 "ConstraintDataAbstract", "Abstract class for constraint data.\n\n", \
211 bp::init<Model*, DataCollector*>( \
212 bp::args("self", "model", "data"), \
213 "Create common data shared between constraint models.\n\n" \
214 ":param model: constraint model\n" \
215 ":param data: shared data")[bp::with_custodian_and_ward< \
216 1, 2, bp::with_custodian_and_ward<1, 3>>()]) \
217 .def(ConstraintDataAbstractVisitor<Data>()) \
218 .def(CopyableVisitor<Data>());
219
220 void exposeConstraintAbstract() {
221 #ifdef SCALAR_float64
222 bp::enum_<ConstraintType>("ConstraintType")
223 .value("Inequality", Inequality)
224 .value("Equality", Equality)
225 .value("Both", Both)
226 .export_values();
227 #endif
228
229 CROCODDYL_CONSTRAINT_MODEL_ABSTRACT_PYTHON_BINDINGS(float)
230 CROCODDYL_CONSTRAINT_DATA_ABSTRACT_PYTHON_BINDINGS(float)
231 }
232
233 } // namespace python
234 } // namespace crocoddyl
235