| 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 float | ||
| 11 | #include "python/crocoddyl/core/action-base.hpp" | ||
| 12 | |||
| 13 | #include "python/crocoddyl/utils/deprecate.hpp" | ||
| 14 | #include "python/crocoddyl/utils/vector-converter.hpp" | ||
| 15 | |||
| 16 | namespace crocoddyl { | ||
| 17 | namespace python { | ||
| 18 | |||
| 19 | template <typename Model> | ||
| 20 | struct ActionModelAbstractVisitor | ||
| 21 | : public bp::def_visitor<ActionModelAbstractVisitor<Model>> { | ||
| 22 | typedef typename Model::ActionModel ActionModel; | ||
| 23 | typedef typename Model::ActionData ActionData; | ||
| 24 | typedef typename Model::VectorXs VectorXs; | ||
| 25 | ✗ | BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(ActionModel_quasiStatic_wraps, | |
| 26 | ActionModel::quasiStatic_x, 2, 4) | ||
| 27 | template <class PyClass> | ||
| 28 | ✗ | void visit(PyClass& cl) const { | |
| 29 | ✗ | cl.def("calc", pure_virtual(&Model::calc), | |
| 30 | bp::args("self", "data", "x", "u"), | ||
| 31 | "Compute the next state and cost value.\n\n" | ||
| 32 | "It describes the time-discrete evolution of our dynamical system " | ||
| 33 | "in which we obtain the next state. Additionally it computes the " | ||
| 34 | "cost value associated to this discrete state and control pair.\n" | ||
| 35 | ":param data: action data\n" | ||
| 36 | ":param x: state point (dim. state.nx)\n" | ||
| 37 | ":param u: control input (dim. nu)") | ||
| 38 | ✗ | .def("calc", | |
| 39 | static_cast<void (ActionModel::*)( | ||
| 40 | const std::shared_ptr<ActionData>&, | ||
| 41 | const Eigen::Ref<const VectorXs>&)>(&ActionModel::calc), | ||
| 42 | bp::args("self", "data", "x"), | ||
| 43 | "Compute the total cost value for nodes that depends only on the " | ||
| 44 | "state.\n\n" | ||
| 45 | "It updates the total cost and the next state is not computed as " | ||
| 46 | "it is not expected to change. This function is used in the " | ||
| 47 | "terminal nodes of an optimal control problem.\n" | ||
| 48 | ":param data: action data\n" | ||
| 49 | ":param x: state point (dim. state.nx)") | ||
| 50 | ✗ | .def("calcDiff", pure_virtual(&Model::calcDiff), | |
| 51 | bp::args("self", "data", "x", "u"), | ||
| 52 | "Compute the derivatives of the dynamics and cost functions.\n\n" | ||
| 53 | "It computes the partial derivatives of the dynamical system and " | ||
| 54 | "the cost function. It assumes that calc has been run first. This " | ||
| 55 | "function builds a quadratic approximation of the action model " | ||
| 56 | "(i.e. linear dynamics and quadratic cost).\n" | ||
| 57 | ":param data: action data\n" | ||
| 58 | ":param x: state point (dim. state.nx)\n" | ||
| 59 | ":param u: control input (dim. nu)") | ||
| 60 | ✗ | .def("calcDiff", | |
| 61 | static_cast<void (ActionModel::*)( | ||
| 62 | const std::shared_ptr<ActionData>&, | ||
| 63 | const Eigen::Ref<const VectorXs>&)>(&ActionModel::calcDiff), | ||
| 64 | bp::args("self", "data", "x"), | ||
| 65 | "Compute the derivatives of the cost functions with respect to " | ||
| 66 | "the state only.\n\n" | ||
| 67 | "It updates the derivatives of the cost function with respect to " | ||
| 68 | "the state only. This function is used in the terminal nodes of " | ||
| 69 | "an optimal control problem.\n" | ||
| 70 | ":param data: action data\n" | ||
| 71 | ":param x: state point (dim. state.nx)") | ||
| 72 | ✗ | .def("createData", &Model::createData, &Model::default_createData, | |
| 73 | bp::args("self"), | ||
| 74 | "Create the action data.\n\n" | ||
| 75 | "Each action model (AM) has its own data that needs to be " | ||
| 76 | "allocated.\n" | ||
| 77 | "This function returns the allocated data for a predefined AM.\n" | ||
| 78 | ":return AM data.") | ||
| 79 | ✗ | .def("quasiStatic", &Model::quasiStatic_x, | |
| 80 | ✗ | ActionModel_quasiStatic_wraps( | |
| 81 | bp::args("self", "data", "x", "maxiter", "tol"), | ||
| 82 | "Compute the quasic-static control given a state.\n\n" | ||
| 83 | "It runs an iterative Newton step in order to compute the " | ||
| 84 | "quasic-static regime given a state configuration.\n" | ||
| 85 | ":param data: action data\n" | ||
| 86 | ":param x: discrete-time state vector\n" | ||
| 87 | ":param maxiter: maximum allowed number of iterations\n" | ||
| 88 | ":param tol: stopping tolerance criteria (default 1e-9)\n" | ||
| 89 | ":return u: quasic-static control")) | ||
| 90 | ✗ | .def("quasiStatic", &Model::quasiStatic, &Model::default_quasiStatic, | |
| 91 | bp::args("self", "data", "u", "x", "maxiter", "tol")) | ||
| 92 | ✗ | .add_property( | |
| 93 | "nu", bp::make_function(&Model::get_nu), | ||
| 94 | ✗ | bp::make_setter(&Model::nu_, bp::return_internal_reference<>()), | |
| 95 | "dimension of control vector") | ||
| 96 | ✗ | .add_property("nr", bp::make_function(&Model::get_nr), | |
| 97 | "dimension of cost-residual vector") | ||
| 98 | ✗ | .add_property( | |
| 99 | "ng", bp::make_function(&Model::get_ng), | ||
| 100 | bp::make_setter( | ||
| 101 | ✗ | &Model::ng_, | |
| 102 | ✗ | deprecated<bp::return_internal_reference<>>( | |
| 103 | "Deprecated. Constraint dimension should not be modified.")), | ||
| 104 | "number of inequality constraints") | ||
| 105 | ✗ | .def("get_ng", &Model::get_ng, &Model::default_get_ng, | |
| 106 | "Return the number of inequality constraints.") | ||
| 107 | ✗ | .add_property( | |
| 108 | "nh", bp::make_function(&Model::get_nh), | ||
| 109 | bp::make_setter( | ||
| 110 | ✗ | &Model::nh_, | |
| 111 | ✗ | deprecated<bp::return_internal_reference<>>( | |
| 112 | "Deprecated. Constraint dimension should not be modified.")), | ||
| 113 | "number of equality constraints") | ||
| 114 | ✗ | .def("get_nh", &Model::get_nh, &Model::default_get_nh, | |
| 115 | "Return the number of equality constraints.") | ||
| 116 | ✗ | .add_property( | |
| 117 | "ng_T", bp::make_function(&Model::get_ng_T), | ||
| 118 | bp::make_setter( | ||
| 119 | ✗ | &Model::ng_T_, | |
| 120 | ✗ | deprecated<bp::return_internal_reference<>>( | |
| 121 | "Deprecated. Constraint dimension should not be modified.")), | ||
| 122 | "number of inequality terminal constraints") | ||
| 123 | ✗ | .def("get_ng_T", &Model::get_ng_T, &Model::default_get_ng_T, | |
| 124 | "Return the number of inequality terminal constraints.") | ||
| 125 | ✗ | .add_property( | |
| 126 | "nh_T", bp::make_function(&Model::get_nh_T), | ||
| 127 | bp::make_setter( | ||
| 128 | ✗ | &Model::nh_T_, | |
| 129 | ✗ | deprecated<bp::return_internal_reference<>>( | |
| 130 | "Deprecated. Constraint dimension should not be modified.")), | ||
| 131 | "number of equality terminal constraints") | ||
| 132 | ✗ | .def("get_nh_T", &Model::get_nh_T, &Model::default_get_nh_T, | |
| 133 | "Return the number of equality terminal constraints.") | ||
| 134 | ✗ | .add_property( | |
| 135 | "state", | ||
| 136 | bp::make_function(&Model::get_state, | ||
| 137 | ✗ | bp::return_value_policy<bp::return_by_value>()), | |
| 138 | "state") | ||
| 139 | ✗ | .add_property("g_lb", | |
| 140 | bp::make_function(&Model::get_g_lb, | ||
| 141 | ✗ | bp::return_internal_reference<>()), | |
| 142 | &Model::set_g_lb, | ||
| 143 | "lower bound of the inequality constraints") | ||
| 144 | ✗ | .add_property("g_ub", | |
| 145 | bp::make_function(&Model::get_g_ub, | ||
| 146 | ✗ | bp::return_internal_reference<>()), | |
| 147 | &Model::set_g_ub, | ||
| 148 | "upper bound of the inequality constraints") | ||
| 149 | ✗ | .add_property("u_lb", | |
| 150 | bp::make_function(&Model::get_u_lb, | ||
| 151 | ✗ | bp::return_internal_reference<>()), | |
| 152 | &Model::set_u_lb, "lower control limits") | ||
| 153 | ✗ | .add_property("u_ub", | |
| 154 | bp::make_function(&Model::get_u_ub, | ||
| 155 | ✗ | bp::return_internal_reference<>()), | |
| 156 | &Model::set_u_ub, "upper control limits") | ||
| 157 | ✗ | .add_property("has_control_limits", | |
| 158 | bp::make_function(&Model::get_has_control_limits), | ||
| 159 | "indicates whether problem has finite control limits"); | ||
| 160 | ✗ | } | |
| 161 | }; | ||
| 162 | |||
| 163 | template <typename Data> | ||
| 164 | struct ActionDataAbstractVisitor | ||
| 165 | : public bp::def_visitor<ActionDataAbstractVisitor<Data>> { | ||
| 166 | template <class PyClass> | ||
| 167 | ✗ | void visit(PyClass& cl) const { | |
| 168 | ✗ | cl.add_property( | |
| 169 | "cost", | ||
| 170 | ✗ | bp::make_getter(&Data::cost, | |
| 171 | ✗ | bp::return_value_policy<bp::return_by_value>()), | |
| 172 | ✗ | bp::make_setter(&Data::cost), "cost value") | |
| 173 | ✗ | .add_property( | |
| 174 | "xnext", | ||
| 175 | ✗ | bp::make_getter(&Data::xnext, bp::return_internal_reference<>()), | |
| 176 | ✗ | bp::make_setter(&Data::xnext), "next state") | |
| 177 | ✗ | .add_property( | |
| 178 | ✗ | "r", bp::make_getter(&Data::r, bp::return_internal_reference<>()), | |
| 179 | ✗ | bp::make_setter(&Data::r), "cost residual") | |
| 180 | ✗ | .add_property( | |
| 181 | ✗ | "Fx", bp::make_getter(&Data::Fx, bp::return_internal_reference<>()), | |
| 182 | ✗ | bp::make_setter(&Data::Fx), | |
| 183 | "Jacobian of the dynamics w.r.t. the state") | ||
| 184 | ✗ | .add_property( | |
| 185 | ✗ | "Fu", bp::make_getter(&Data::Fu, bp::return_internal_reference<>()), | |
| 186 | ✗ | bp::make_setter(&Data::Fu), | |
| 187 | "Jacobian of the dynamics w.r.t. the control") | ||
| 188 | ✗ | .add_property( | |
| 189 | ✗ | "Lx", bp::make_getter(&Data::Lx, bp::return_internal_reference<>()), | |
| 190 | ✗ | bp::make_setter(&Data::Lx), "Jacobian of the cost w.r.t. the state") | |
| 191 | ✗ | .add_property( | |
| 192 | ✗ | "Lu", bp::make_getter(&Data::Lu, bp::return_internal_reference<>()), | |
| 193 | ✗ | bp::make_setter(&Data::Lu), "Jacobian of the cost") | |
| 194 | ✗ | .add_property( | |
| 195 | "Lxx", | ||
| 196 | ✗ | bp::make_getter(&Data::Lxx, bp::return_internal_reference<>()), | |
| 197 | ✗ | bp::make_setter(&Data::Lxx), "Hessian of the cost w.r.t. the state") | |
| 198 | ✗ | .add_property( | |
| 199 | "Lxu", | ||
| 200 | ✗ | bp::make_getter(&Data::Lxu, bp::return_internal_reference<>()), | |
| 201 | ✗ | bp::make_setter(&Data::Lxu), | |
| 202 | "Hessian of the cost w.r.t. the state and control") | ||
| 203 | ✗ | .add_property( | |
| 204 | "Luu", | ||
| 205 | ✗ | bp::make_getter(&Data::Luu, bp::return_internal_reference<>()), | |
| 206 | ✗ | bp::make_setter(&Data::Luu), | |
| 207 | "Hessian of the cost w.r.t. the control") | ||
| 208 | ✗ | .add_property( | |
| 209 | ✗ | "g", bp::make_getter(&Data::g, bp::return_internal_reference<>()), | |
| 210 | ✗ | bp::make_setter(&Data::g), "inequality constraint values") | |
| 211 | ✗ | .add_property( | |
| 212 | ✗ | "Gx", bp::make_getter(&Data::Gx, bp::return_internal_reference<>()), | |
| 213 | ✗ | bp::make_setter(&Data::Gx), | |
| 214 | "Jacobian of the inequality constraint w.r.t. the state") | ||
| 215 | ✗ | .add_property( | |
| 216 | ✗ | "Gu", bp::make_getter(&Data::Gu, bp::return_internal_reference<>()), | |
| 217 | ✗ | bp::make_setter(&Data::Gu), | |
| 218 | "Jacobian of the inequality constraint w.r.t. the control") | ||
| 219 | ✗ | .add_property( | |
| 220 | ✗ | "h", bp::make_getter(&Data::h, bp::return_internal_reference<>()), | |
| 221 | ✗ | bp::make_setter(&Data::h), "equality constraint values") | |
| 222 | ✗ | .add_property( | |
| 223 | ✗ | "Hx", bp::make_getter(&Data::Hx, bp::return_internal_reference<>()), | |
| 224 | ✗ | bp::make_setter(&Data::Hx), | |
| 225 | "Jacobian of the equality constraint w.r.t. the state") | ||
| 226 | ✗ | .add_property( | |
| 227 | ✗ | "Hu", bp::make_getter(&Data::Hu, bp::return_internal_reference<>()), | |
| 228 | ✗ | bp::make_setter(&Data::Hu), | |
| 229 | "Jacobian of the equality constraint w.r.t. the control"); | ||
| 230 | ✗ | } | |
| 231 | }; | ||
| 232 | |||
| 233 | #define CROCODDYL_ACTION_MODEL_ABSTRACT_PYTHON_BINDINGS(Scalar) \ | ||
| 234 | typedef ActionModelAbstractTpl<Scalar> Model; \ | ||
| 235 | typedef ActionModelAbstractTpl_wrap<Scalar> Model_wrap; \ | ||
| 236 | typedef StateAbstractTpl<Scalar> State; \ | ||
| 237 | typedef std::shared_ptr<Model> ActionModelPtr; \ | ||
| 238 | StdVectorPythonVisitor<std::vector<ActionModelPtr>, true>::expose( \ | ||
| 239 | "StdVec_ActionModel"); \ | ||
| 240 | bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ | ||
| 241 | bp::class_<Model_wrap, boost::noncopyable>( \ | ||
| 242 | "ActionModelAbstract", \ | ||
| 243 | "Abstract class for action models.\n\n" \ | ||
| 244 | "An action model combines dynamics and cost data. Each node, in our " \ | ||
| 245 | "optimal control problem, is described through an action model. Every " \ | ||
| 246 | "time that we want to describe a problem, we need to provide ways of " \ | ||
| 247 | "computing the dynamics, cost functions and their derivatives. These " \ | ||
| 248 | "computations are mainly carried out inside calc() and calcDiff(), " \ | ||
| 249 | "respectively.", \ | ||
| 250 | bp::init<std::shared_ptr<State>, std::size_t, \ | ||
| 251 | bp::optional<std::size_t, std::size_t, std::size_t, \ | ||
| 252 | std::size_t, std::size_t>>( \ | ||
| 253 | bp::args("self", "state", "nu", "nr", "ng", "nh", "ng_T", "nh_T"), \ | ||
| 254 | "Initialize the action model.\n\n" \ | ||
| 255 | "We can also describe autonomous systems by setting nu = 0.\n" \ | ||
| 256 | ":param state: state description,\n" \ | ||
| 257 | ":param nu: dimension of control vector,\n" \ | ||
| 258 | ":param nr: dimension of the cost-residual vector (default 1)\n" \ | ||
| 259 | ":param ng: number of inequality constraints (default 0)\n" \ | ||
| 260 | ":param nh: number of equality constraints (default 0)\n" \ | ||
| 261 | ":param ng_T: number of inequality terminal constraints (default " \ | ||
| 262 | "0)\n" \ | ||
| 263 | ":param nh_T: number of equality terminal constraints (default 0)")) \ | ||
| 264 | .def(ActionModelAbstractVisitor<Model_wrap>()) \ | ||
| 265 | .def(PrintableVisitor<Model_wrap>()) \ | ||
| 266 | .def(CopyableVisitor<Model_wrap>()); | ||
| 267 | |||
| 268 | #define CROCODDYL_ACTION_DATA_ABSTRACT_PYTHON_BINDINGS(Scalar) \ | ||
| 269 | typedef ActionDataAbstractTpl<Scalar> Data; \ | ||
| 270 | typedef ActionModelAbstractTpl<Scalar> Model; \ | ||
| 271 | typedef std::shared_ptr<Data> ActionDataPtr; \ | ||
| 272 | StdVectorPythonVisitor<std::vector<ActionDataPtr>, true>::expose( \ | ||
| 273 | "StdVec_ActionData"); \ | ||
| 274 | bp::register_ptr_to_python<std::shared_ptr<Data>>(); \ | ||
| 275 | bp::class_<Data, boost::noncopyable>( \ | ||
| 276 | "ActionDataAbstract", \ | ||
| 277 | "Abstract class for action data.\n\n" \ | ||
| 278 | "In crocoddyl, an action data contains all the required information " \ | ||
| 279 | "for processing an user-defined action model. The action data " \ | ||
| 280 | "typically is allocated onces by running model.createData() and " \ | ||
| 281 | "contains the first- and second-order derivatives of the dynamics and " \ | ||
| 282 | "cost function, respectively.", \ | ||
| 283 | bp::init<Model*>( \ | ||
| 284 | bp::args("self", "model"), \ | ||
| 285 | "Create common data shared between AMs.\n\n" \ | ||
| 286 | "The action data uses the model in order to first process it.\n" \ | ||
| 287 | ":param model: action model")) \ | ||
| 288 | .def(ActionDataAbstractVisitor<Data>()) \ | ||
| 289 | .def(CopyableVisitor<Data>()); | ||
| 290 | |||
| 291 | ✗ | void exposeActionAbstract() { | |
| 292 | ✗ | CROCODDYL_ACTION_MODEL_ABSTRACT_PYTHON_BINDINGS(float) | |
| 293 | ✗ | CROCODDYL_ACTION_DATA_ABSTRACT_PYTHON_BINDINGS(float) | |
| 294 | ✗ | } | |
| 295 | |||
| 296 | } // namespace python | ||
| 297 | } // namespace crocoddyl | ||
| 298 |