| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | /////////////////////////////////////////////////////////////////////////////// | ||
| 2 | // BSD 3-Clause License | ||
| 3 | // | ||
| 4 | // Copyright (C) 2019-2025, LAAS-CNRS, University of Edinburgh | ||
| 5 | // 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 "crocoddyl/core/actions/lqr.hpp" | ||
| 12 | |||
| 13 | #include "python/crocoddyl/core/action-base.hpp" | ||
| 14 | #include "python/crocoddyl/core/core.hpp" | ||
| 15 | #include "python/crocoddyl/utils/deprecate.hpp" | ||
| 16 | |||
| 17 | namespace crocoddyl { | ||
| 18 | namespace python { | ||
| 19 | |||
| 20 | template <typename Model> | ||
| 21 | struct ActionModelLQRVisitor | ||
| 22 | : public bp::def_visitor<ActionModelLQRVisitor<Model>> { | ||
| 23 | typedef typename Model::ActionDataAbstract Data; | ||
| 24 | typedef typename Model::Base ModelBase; | ||
| 25 | typedef typename Model::MatrixXs MatrixXs; | ||
| 26 | typedef typename Model::VectorXs VectorXs; | ||
| 27 | ✗ | BOOST_PYTHON_FUNCTION_OVERLOADS(ActionModelLQR_Random_wrap, Model::Random, 2, | |
| 28 | 4) | ||
| 29 | template <class PyClass> | ||
| 30 | ✗ | void visit(PyClass& cl) const { | |
| 31 | ✗ | cl.def(bp::init<MatrixXs, MatrixXs, MatrixXs, MatrixXs, MatrixXs, VectorXs, | |
| 32 | VectorXs, VectorXs>( | ||
| 33 | bp::args("self", "A", "B", "Q", "R", "N", "f", "q", "r"), | ||
| 34 | "Initialize the differential LQR action model.\n\n" | ||
| 35 | ":param A: state matrix\n" | ||
| 36 | ":param B: input matrix\n" | ||
| 37 | ":param Q: state weight matrix\n" | ||
| 38 | ":param R: input weight matrix\n" | ||
| 39 | ":param N: state-input weight matrix\n" | ||
| 40 | ":param f: dynamics drift\n" | ||
| 41 | ":param q: state weight vector\n" | ||
| 42 | ":param r: input weight vector")) | ||
| 43 | ✗ | .def(bp::init<MatrixXs, MatrixXs, MatrixXs, MatrixXs, MatrixXs, | |
| 44 | MatrixXs, MatrixXs, VectorXs, VectorXs, VectorXs, | ||
| 45 | VectorXs, VectorXs>( | ||
| 46 | bp::args("self", "A", "B", "Q", "R", "N", "G", "H", "f", "q", "r", | ||
| 47 | "g", "h"), | ||
| 48 | "Initialize the LQR action model.\n\n" | ||
| 49 | ":param A: state matrix\n" | ||
| 50 | ":param B: input matrix\n" | ||
| 51 | ":param Q: state weight matrix\n" | ||
| 52 | ":param R: input weight matrix\n" | ||
| 53 | ":param N: state-input weight matrix\n" | ||
| 54 | ":param G: state-input inequality constraint matrix\n" | ||
| 55 | ":param H: state-input equality constraint matrix\n" | ||
| 56 | ":param f: dynamics drift\n" | ||
| 57 | ":param q: state weight vector\n" | ||
| 58 | ":param r: input weight vector\n" | ||
| 59 | ":param g: state-input equality constraint bias\n" | ||
| 60 | ":param h: state-input inequality constraint bias")) | ||
| 61 | ✗ | .def(bp::init<std::size_t, std::size_t, bp::optional<bool>>( | |
| 62 | bp::args("self", "nx", "nu", "driftFree"), | ||
| 63 | "Initialize the LQR action model.\n\n" | ||
| 64 | ":param nx: dimension of the state vector\n" | ||
| 65 | ":param nu: dimension of the control vector\n" | ||
| 66 | ":param driftFree: enable/disable the bias term of the linear " | ||
| 67 | "dynamics (default True)")) | ||
| 68 | ✗ | .def( | |
| 69 | "calc", | ||
| 70 | static_cast<void (Model::*)( | ||
| 71 | const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, | ||
| 72 | const Eigen::Ref<const VectorXs>&)>(&Model::calc), | ||
| 73 | bp::args("self", "data", "x", "u"), | ||
| 74 | "Compute the next state and cost value.\n\n" | ||
| 75 | "It describes the time-discrete evolution of the LQR system. " | ||
| 76 | "Additionally it computes the cost value associated to this " | ||
| 77 | "discrete state and control pair.\n" | ||
| 78 | ":param data: action data\n" | ||
| 79 | ":param x: state point (dim. state.nx)\n" | ||
| 80 | ":param u: control input (dim. nu)") | ||
| 81 | ✗ | .def("calc", | |
| 82 | static_cast<void (Model::*)(const std::shared_ptr<Data>&, | ||
| 83 | const Eigen::Ref<const VectorXs>&)>( | ||
| 84 | &Model::calc), | ||
| 85 | bp::args("self", "data", "x")) | ||
| 86 | ✗ | .def( | |
| 87 | "calcDiff", | ||
| 88 | static_cast<void (Model::*)( | ||
| 89 | const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, | ||
| 90 | const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff), | ||
| 91 | bp::args("self", "data", "x", "u"), | ||
| 92 | "Compute the derivatives of the LQR dynamics and cost " | ||
| 93 | "functions.\n\n" | ||
| 94 | "It computes the partial derivatives of the LQR system and the " | ||
| 95 | "cost function. It assumes that calc has been run first. This " | ||
| 96 | "function builds a quadratic approximation of the action model " | ||
| 97 | "(i.e. dynamical system and cost function).\n" | ||
| 98 | ":param data: action data\n" | ||
| 99 | ":param x: state point (dim. state.nx)\n" | ||
| 100 | ":param u: control input (dim. nu)") | ||
| 101 | ✗ | .def("calcDiff", | |
| 102 | static_cast<void (Model::*)(const std::shared_ptr<Data>&, | ||
| 103 | const Eigen::Ref<const VectorXs>&)>( | ||
| 104 | &Model::calcDiff), | ||
| 105 | bp::args("self", "data", "x")) | ||
| 106 | ✗ | .def("createData", &Model::createData, bp::args("self"), | |
| 107 | "Create the LQR action data.") | ||
| 108 | ✗ | .def("Random", &Model::Random, | |
| 109 | ✗ | ActionModelLQR_Random_wrap( | |
| 110 | bp::args("nx", "nu", "ng", "nh"), | ||
| 111 | "Create a random LQR model.\n\n" | ||
| 112 | ":param nx: state dimension\n" | ||
| 113 | ":param nu: control dimension\n" | ||
| 114 | ":param ng: inequality constraint dimension (default 0)\n" | ||
| 115 | ":param nh: equality constraint dimension (default 0)")) | ||
| 116 | ✗ | .staticmethod("Random") | |
| 117 | ✗ | .def("setLQR", &Model::set_LQR, | |
| 118 | bp::args("self", "A", "B", "Q", "R", "N", "G", "H", "f", "q", "r", | ||
| 119 | "g", "h"), | ||
| 120 | "Modify the LQR action model.\n\n" | ||
| 121 | ":param A: state matrix\n" | ||
| 122 | ":param B: input matrix\n" | ||
| 123 | ":param Q: state weight matrix\n" | ||
| 124 | ":param R: input weight matrix\n" | ||
| 125 | ":param N: state-input weight matrix\n" | ||
| 126 | ":param G: state-input inequality constraint matrix\n" | ||
| 127 | ":param H: state-input equality constraint matrix\n" | ||
| 128 | ":param f: dynamics drift\n" | ||
| 129 | ":param q: state weight vector\n" | ||
| 130 | ":param r: input weight vector\n" | ||
| 131 | ":param g: state-input inequality constraint bias\n" | ||
| 132 | ":param h: state-input equality constraint bias") | ||
| 133 | ✗ | .add_property( | |
| 134 | "A", | ||
| 135 | ✗ | bp::make_function(&Model::get_A, bp::return_internal_reference<>()), | |
| 136 | "state matrix") | ||
| 137 | ✗ | .add_property( | |
| 138 | "B", | ||
| 139 | ✗ | bp::make_function(&Model::get_B, bp::return_internal_reference<>()), | |
| 140 | "input matrix") | ||
| 141 | ✗ | .add_property( | |
| 142 | "f", | ||
| 143 | ✗ | bp::make_function(&Model::get_f, bp::return_internal_reference<>()), | |
| 144 | "dynamics drift") | ||
| 145 | ✗ | .add_property( | |
| 146 | "Q", | ||
| 147 | ✗ | bp::make_function(&Model::get_Q, bp::return_internal_reference<>()), | |
| 148 | "state weight matrix") | ||
| 149 | ✗ | .add_property( | |
| 150 | "R", | ||
| 151 | ✗ | bp::make_function(&Model::get_R, bp::return_internal_reference<>()), | |
| 152 | "input weight matrix") | ||
| 153 | ✗ | .add_property( | |
| 154 | "N", | ||
| 155 | ✗ | bp::make_function(&Model::get_N, bp::return_internal_reference<>()), | |
| 156 | "state-input weight matrix") | ||
| 157 | ✗ | .add_property( | |
| 158 | "G", | ||
| 159 | ✗ | bp::make_function(&Model::get_G, bp::return_internal_reference<>()), | |
| 160 | "state-input inequality constraint matrix") | ||
| 161 | ✗ | .add_property( | |
| 162 | "H", | ||
| 163 | ✗ | bp::make_function(&Model::get_H, bp::return_internal_reference<>()), | |
| 164 | "state-input equality constraint matrix") | ||
| 165 | ✗ | .add_property( | |
| 166 | "q", | ||
| 167 | ✗ | bp::make_function(&Model::get_q, bp::return_internal_reference<>()), | |
| 168 | "state weight vector") | ||
| 169 | ✗ | .add_property( | |
| 170 | "r", | ||
| 171 | ✗ | bp::make_function(&Model::get_r, bp::return_internal_reference<>()), | |
| 172 | "input weight vector") | ||
| 173 | ✗ | .add_property( | |
| 174 | "g", | ||
| 175 | ✗ | bp::make_function(&Model::get_g, bp::return_internal_reference<>()), | |
| 176 | "state-input inequality constraint bias") | ||
| 177 | ✗ | .add_property( | |
| 178 | "h", | ||
| 179 | ✗ | bp::make_function(&Model::get_h, bp::return_internal_reference<>()), | |
| 180 | "state-input equality constraint bias") | ||
| 181 | ✗ | .add_property( | |
| 182 | "ng", bp::make_function(&Model::get_ng), "number of equality constraints") | ||
| 183 | ✗ | .add_property( | |
| 184 | "nh", bp::make_function(&Model::get_nh), "number of inequality constraints") | ||
| 185 | ✗ | .add_property( | |
| 186 | "ng_T", bp::make_function(&Model::get_ng_T), "number of equality terminal constraints") | ||
| 187 | ✗ | .add_property( | |
| 188 | "nh_T", bp::make_function(&Model::get_nh_T), "number of inequality terminal constraints") | ||
| 189 | // deprecated function | ||
| 190 | ✗ | .add_property( | |
| 191 | "Fx", | ||
| 192 | bp::make_function(&Model::get_A, | ||
| 193 | ✗ | deprecated<bp::return_internal_reference<>>( | |
| 194 | "Deprecated. Use set_LQR.")), | ||
| 195 | &Model::set_Fx, "state matrix") | ||
| 196 | ✗ | .add_property( | |
| 197 | "Fu", | ||
| 198 | bp::make_function(&Model::get_B, | ||
| 199 | ✗ | deprecated<bp::return_internal_reference<>>( | |
| 200 | "Deprecated. Use B.")), | ||
| 201 | bp::make_function(&Model::set_Fu, | ||
| 202 | ✗ | deprecated<>("Deprecated. Use set_LQR.")), | |
| 203 | "input matrix") | ||
| 204 | ✗ | .add_property( | |
| 205 | "f0", | ||
| 206 | bp::make_function(&Model::get_f, | ||
| 207 | ✗ | deprecated<bp::return_internal_reference<>>( | |
| 208 | "Deprecated. Use f.")), | ||
| 209 | bp::make_function(&Model::set_f0, | ||
| 210 | ✗ | deprecated<>("Deprecated. Use set_LQR.")), | |
| 211 | "dynamics drift") | ||
| 212 | ✗ | .add_property( | |
| 213 | "lx", | ||
| 214 | bp::make_function(&Model::get_q, | ||
| 215 | ✗ | deprecated<bp::return_internal_reference<>>( | |
| 216 | "Deprecated. Use q.")), | ||
| 217 | bp::make_function(&Model::set_lx, | ||
| 218 | ✗ | deprecated<>("Deprecated. Use set_LQR.")), | |
| 219 | "state weight vector") | ||
| 220 | ✗ | .add_property( | |
| 221 | "lu", | ||
| 222 | bp::make_function(&Model::get_r, | ||
| 223 | ✗ | deprecated<bp::return_internal_reference<>>( | |
| 224 | "Deprecated. Use r.")), | ||
| 225 | bp::make_function(&Model::set_lu, | ||
| 226 | ✗ | deprecated<>("Deprecated. Use set_LQR.")), | |
| 227 | "input weight vector") | ||
| 228 | ✗ | .add_property( | |
| 229 | "Lxx", | ||
| 230 | bp::make_function(&Model::get_Q, | ||
| 231 | ✗ | deprecated<bp::return_internal_reference<>>( | |
| 232 | "Deprecated. Use Q.")), | ||
| 233 | bp::make_function(&Model::set_Lxx, | ||
| 234 | ✗ | deprecated<>("Deprecated. Use set_LQR.")), | |
| 235 | "state weight matrix") | ||
| 236 | ✗ | .add_property( | |
| 237 | "Lxu", | ||
| 238 | bp::make_function(&Model::get_N, | ||
| 239 | ✗ | deprecated<bp::return_internal_reference<>>( | |
| 240 | "Deprecated. Use N.")), | ||
| 241 | bp::make_function(&Model::set_Lxu, | ||
| 242 | ✗ | deprecated<>("Deprecated. Use set_LQR.")), | |
| 243 | "state-input weight matrix") | ||
| 244 | ✗ | .add_property( | |
| 245 | "Luu", | ||
| 246 | bp::make_function(&Model::get_R, | ||
| 247 | ✗ | deprecated<bp::return_internal_reference<>>( | |
| 248 | "Deprecated. Use R.")), | ||
| 249 | bp::make_function(&Model::set_Luu, | ||
| 250 | ✗ | deprecated<>("Deprecated. Use set_LQR.")), | |
| 251 | "input weight matrix"); | ||
| 252 | ✗ | } | |
| 253 | }; | ||
| 254 | |||
| 255 | #define CROCODDYL_ACTION_MODEL_LQR_PYTHON_BINDINGS(Scalar) \ | ||
| 256 | typedef ActionModelLQRTpl<Scalar> Model; \ | ||
| 257 | typedef ActionModelAbstractTpl<Scalar> ModelBase; \ | ||
| 258 | typedef typename ModelBase::VectorXs MatrixXs; \ | ||
| 259 | bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ | ||
| 260 | bp::class_<Model, bp::bases<ModelBase>>( \ | ||
| 261 | "ActionModelLQR", \ | ||
| 262 | "LQR action model.\n\n" \ | ||
| 263 | "A linear-quadratic regulator (LQR) action has a transition model of " \ | ||
| 264 | "the form\n" \ | ||
| 265 | " xnext(x,u) = A x + B u + f.\n" \ | ||
| 266 | "Its cost function is quadratic of the form:\n" \ | ||
| 267 | " 1/2 [x,u].T [Q N; N.T R] [x,u] + [q,r].T [x,u],\n" \ | ||
| 268 | "and the linear equality and inequality constraints has the form:\n" \ | ||
| 269 | " g(x,u) = G [x,u] + g<=0\n" \ | ||
| 270 | " h(x,u) = H [x,u] + h.", \ | ||
| 271 | bp::init<MatrixXs, MatrixXs, MatrixXs, MatrixXs, MatrixXs>( \ | ||
| 272 | bp::args("self", "A", "B", "Q", "R", "N"), \ | ||
| 273 | "Initialize the LQR action model.\n\n" \ | ||
| 274 | ":param A: state matrix\n" \ | ||
| 275 | ":param B: input matrix\n" \ | ||
| 276 | ":param Q: state weight matrix\n" \ | ||
| 277 | ":param R: input weight matrix\n" \ | ||
| 278 | ":param N: state-input weight matrix")) \ | ||
| 279 | .def(ActionModelLQRVisitor<Model>()) \ | ||
| 280 | .def(CastVisitor<Model>()) \ | ||
| 281 | .def(PrintableVisitor<Model>()) \ | ||
| 282 | .def(CopyableVisitor<Model>()); | ||
| 283 | |||
| 284 | #define CROCODDYL_ACTION_DATA_LQR_PYTHON_BINDINGS(Scalar) \ | ||
| 285 | typedef ActionDataLQRTpl<Scalar> Data; \ | ||
| 286 | typedef ActionDataAbstractTpl<Scalar> DataBase; \ | ||
| 287 | typedef ActionModelLQRTpl<Scalar> Model; \ | ||
| 288 | bp::register_ptr_to_python<std::shared_ptr<Data>>(); \ | ||
| 289 | bp::class_<Data, bp::bases<DataBase>>( \ | ||
| 290 | "ActionDataLQR", "Action data for the LQR system.", \ | ||
| 291 | bp::init<Model*>(bp::args("self", "model"), \ | ||
| 292 | "Create LQR data.\n\n" \ | ||
| 293 | ":param model: LQR action model")) \ | ||
| 294 | .def(CopyableVisitor<Data>()); | ||
| 295 | |||
| 296 | ✗ | void exposeActionLQR() { | |
| 297 | // TODO: Remove once the deprecated update call has been removed in a future | ||
| 298 | // release | ||
| 299 | #pragma GCC diagnostic push | ||
| 300 | #pragma GCC diagnostic ignored "-Wdeprecated-declarations" | ||
| 301 | |||
| 302 | ✗ | CROCODDYL_ACTION_MODEL_LQR_PYTHON_BINDINGS(float) | |
| 303 | ✗ | CROCODDYL_ACTION_DATA_LQR_PYTHON_BINDINGS(float) | |
| 304 | |||
| 305 | #pragma GCC diagnostic pop | ||
| 306 | ✗ | } | |
| 307 | |||
| 308 | } // namespace python | ||
| 309 | } // namespace crocoddyl | ||
| 310 |