| Directory: | ./ |
|---|---|
| File: | bindings/python/crocoddyl/multibody/cop-support.cpp |
| Date: | 2025-03-26 19:23:43 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 17 | 17 | 100.0% |
| Branches: | 33 | 66 | 50.0% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | /////////////////////////////////////////////////////////////////////////////// | ||
| 2 | // BSD 3-Clause License | ||
| 3 | // | ||
| 4 | // Copyright (C) 2021-2025, University of Edinburgh, Heriot-Watt University | ||
| 5 | // Copyright note valid unless otherwise stated in individual files. | ||
| 6 | // All rights reserved. | ||
| 7 | /////////////////////////////////////////////////////////////////////////////// | ||
| 8 | |||
| 9 | #include "crocoddyl/multibody/cop-support.hpp" | ||
| 10 | |||
| 11 | #include "python/crocoddyl/multibody/multibody.hpp" | ||
| 12 | |||
| 13 | namespace crocoddyl { | ||
| 14 | namespace python { | ||
| 15 | |||
| 16 | template <typename Model> | ||
| 17 | struct CoPSupportVisitor : public bp::def_visitor<CoPSupportVisitor<Model>> { | ||
| 18 | template <class PyClass> | ||
| 19 | 40 | void visit(PyClass& cl) const { | |
| 20 |
2/4✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
|
40 | cl.def(bp::init<>(bp::args("self"), |
| 21 | "Default initialization of the CoP support.")) | ||
| 22 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
80 | .def("update", &Model::update, bp::args("self"), |
| 23 | "Update the linear inequality (matrix and bounds).\n\n" | ||
| 24 | "Run this function if you have changed one of the parameters.") | ||
| 25 |
3/6✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
|
40 | .add_property( |
| 26 | "A", | ||
| 27 | 40 | bp::make_function(&Model::get_A, bp::return_internal_reference<>()), | |
| 28 | "inequality matrix") | ||
| 29 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
40 | .add_property("ub", |
| 30 | bp::make_function(&Model::get_ub, | ||
| 31 | 40 | bp::return_internal_reference<>()), | |
| 32 | "inequality upper bound") | ||
| 33 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
40 | .add_property("lb", |
| 34 | bp::make_function(&Model::get_lb, | ||
| 35 | 40 | bp::return_internal_reference<>()), | |
| 36 | "inequality lower bound") | ||
| 37 |
3/6✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
|
80 | .add_property( |
| 38 | "R", | ||
| 39 | 40 | bp::make_function(&Model::get_R, bp::return_internal_reference<>()), | |
| 40 | bp::make_function(&Model::set_R), "rotation matrix") | ||
| 41 |
3/6✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
|
80 | .add_property("box", |
| 42 | bp::make_function(&Model::get_box, | ||
| 43 | 40 | bp::return_internal_reference<>()), | |
| 44 | bp::make_function(&Model::set_box), | ||
| 45 | "box size used to define the sole"); | ||
| 46 | 40 | } | |
| 47 | }; | ||
| 48 | |||
| 49 | #define CROCODDYL_COP_SUPPORT_PYTHON_BINDINGS(Scalar) \ | ||
| 50 | typedef CoPSupportTpl<Scalar> Model; \ | ||
| 51 | typedef typename Model::Matrix3s Matrix3s; \ | ||
| 52 | typedef typename Model::Vector2s Vector2s; \ | ||
| 53 | bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ | ||
| 54 | bp::class_<Model>( \ | ||
| 55 | "CoPSupport", "Model of the CoP support as lb <= Af <= ub", \ | ||
| 56 | bp::init<Matrix3s, Vector2s>( \ | ||
| 57 | bp::args("self", "R", "box"), \ | ||
| 58 | "Initialize the CoP support.\n\n" \ | ||
| 59 | ":param R: rotation matrix that defines the cone orientation\n" \ | ||
| 60 | ":param box: dimension of the foot surface dim = (length, " \ | ||
| 61 | "width)\n")) \ | ||
| 62 | .def(CoPSupportVisitor<Model>()) \ | ||
| 63 | .def(CastVisitor<Model>()) \ | ||
| 64 | .def(PrintableVisitor<Model>()) \ | ||
| 65 | .def(CopyableVisitor<Model>()); | ||
| 66 | |||
| 67 | 10 | void exposeCoPSupport() { | |
| 68 | #pragma GCC diagnostic push // TODO: Remove once the deprecated update call has | ||
| 69 | // been removed in a future release | ||
| 70 | #pragma GCC diagnostic ignored "-Wdeprecated-declarations" | ||
| 71 | |||
| 72 |
17/34✓ Branch 3 taken 10 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 10 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 10 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 10 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 10 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 10 times.
✗ Branch 19 not taken.
✓ Branch 24 taken 10 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 10 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 10 times.
✗ Branch 31 not taken.
✓ Branch 35 taken 10 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 10 times.
✗ Branch 39 not taken.
✓ Branch 41 taken 10 times.
✗ Branch 42 not taken.
✓ Branch 44 taken 10 times.
✗ Branch 45 not taken.
✓ Branch 47 taken 10 times.
✗ Branch 48 not taken.
✓ Branch 50 taken 10 times.
✗ Branch 51 not taken.
✓ Branch 53 taken 10 times.
✗ Branch 54 not taken.
✓ Branch 56 taken 10 times.
✗ Branch 57 not taken.
|
20 | CROCODDYL_PYTHON_SCALARS(CROCODDYL_COP_SUPPORT_PYTHON_BINDINGS) |
| 73 | |||
| 74 | #pragma GCC diagnostic pop | ||
| 75 | 10 | } | |
| 76 | |||
| 77 | } // namespace python | ||
| 78 | } // namespace crocoddyl | ||
| 79 |