| Directory: | ./ |
|---|---|
| File: | bindings/python/crocoddyl/multibody/friction-cone.cpp |
| Date: | 2025-03-26 19:23:43 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 23 | 23 | 100.0% |
| Branches: | 48 | 96 | 50.0% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | /////////////////////////////////////////////////////////////////////////////// | ||
| 2 | // BSD 3-Clause License | ||
| 3 | // | ||
| 4 | // Copyright (C) 2019-2025, University of Edinburgh, University of Oxford, | ||
| 5 | // Heriot-Watt University | ||
| 6 | // Copyright note valid unless otherwise stated in individual files. | ||
| 7 | // All rights reserved. | ||
| 8 | /////////////////////////////////////////////////////////////////////////////// | ||
| 9 | |||
| 10 | #include "crocoddyl/multibody/friction-cone.hpp" | ||
| 11 | |||
| 12 | #include "python/crocoddyl/multibody/multibody.hpp" | ||
| 13 | #include "python/crocoddyl/utils/deprecate.hpp" | ||
| 14 | |||
| 15 | namespace crocoddyl { | ||
| 16 | namespace python { | ||
| 17 | |||
| 18 | template <typename Model> | ||
| 19 | struct FrictionConeVisitor | ||
| 20 | : public bp::def_visitor<FrictionConeVisitor<Model>> { | ||
| 21 | typedef typename Model::Scalar Scalar; | ||
| 22 | typedef typename Model::Vector3s Vector3s; | ||
| 23 | template <class PyClass> | ||
| 24 | 40 | void visit(PyClass& cl) const { | |
| 25 |
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"), |
| 26 | "Default initialization of the friction cone.")) | ||
| 27 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
80 | .def("update", static_cast<void (Model::*)()>(&Model::update), |
| 28 | bp::args("self"), | ||
| 29 | "Update the linear inequality (matrix and bounds).\n\n" | ||
| 30 | "Run this function if you have changed one of the parameters.") | ||
| 31 |
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.
|
120 | .def("update", |
| 32 | static_cast<void (Model::*)(const Vector3s&, const Scalar, | ||
| 33 | const bool, const Scalar, | ||
| 34 | const Scalar)>(&Model::update), | ||
| 35 |
2/4✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
|
80 | deprecated<>("Deprecated. Use update()."), |
| 36 | bp::args("self", "nsurf", "mu", "inner_appr", "min_nforce", | ||
| 37 | "max_nforce"), | ||
| 38 | "Update the linear inequality (matrix and bounds).\n\n" | ||
| 39 | ":param nsurf: surface normal vector (it defines the cone " | ||
| 40 | "orientation)\n" | ||
| 41 | ":param mu: friction coefficient\n" | ||
| 42 | ":param inner_appr: inner or outer approximation (default True)\n" | ||
| 43 | ":param min_nforce: minimum normal force (default 0.)\n" | ||
| 44 | ":param max_nforce: maximum normal force (default " | ||
| 45 | "sys.float_info.max)") | ||
| 46 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
40 | .add_property( |
| 47 | "A", | ||
| 48 | 40 | bp::make_function(&Model::get_A, bp::return_internal_reference<>()), | |
| 49 | "inequality matrix") | ||
| 50 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
40 | .add_property("ub", |
| 51 | bp::make_function(&Model::get_ub, | ||
| 52 | 40 | bp::return_internal_reference<>()), | |
| 53 | "inequality upper bound") | ||
| 54 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
40 | .add_property("lb", |
| 55 | bp::make_function(&Model::get_lb, | ||
| 56 | 40 | bp::return_internal_reference<>()), | |
| 57 | "inequality lower bound") | ||
| 58 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
40 | .add_property( |
| 59 | "nf", | ||
| 60 | bp::make_function(&Model::get_nf, | ||
| 61 | 40 | bp::return_value_policy<bp::return_by_value>()), | |
| 62 | "number of facets (run update() if you have changed the value)") | ||
| 63 |
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( |
| 64 | "R", | ||
| 65 | 40 | bp::make_function(&Model::get_R, bp::return_internal_reference<>()), | |
| 66 | bp::make_function(&Model::set_R), | ||
| 67 | "rotation matrix that defines the cone orientation w.r.t. " | ||
| 68 | "the inertial frame (run update() if you " | ||
| 69 | "have changed the value)") | ||
| 70 |
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( |
| 71 | "mu", bp::make_function(&Model::get_mu), | ||
| 72 | bp::make_function(&Model::set_mu), | ||
| 73 | "friction coefficient (run update() if you have changed the value)") | ||
| 74 |
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("inner_appr", bp::make_function(&Model::get_inner_appr), |
| 75 | bp::make_function(&Model::set_inner_appr), | ||
| 76 | "type of cone approximation (run update() if you have " | ||
| 77 | "changed the value)") | ||
| 78 |
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( |
| 79 | "min_nforce", bp::make_function(&Model::get_min_nforce), | ||
| 80 | bp::make_function(&Model::set_min_nforce), | ||
| 81 | "minimum normal force (run update() if you have changed the value)") | ||
| 82 |
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("max_nforce", bp::make_function(&Model::get_max_nforce), |
| 83 | bp::make_function(&Model::set_max_nforce), | ||
| 84 | "maximum normal force (run update() if you have changed " | ||
| 85 | "the value)"); | ||
| 86 | 40 | } | |
| 87 | }; | ||
| 88 | |||
| 89 | #define CROCODDYL_FRICTION_CONE_PYTHON_BINDINGS(Scalar) \ | ||
| 90 | typedef FrictionConeTpl<Scalar> Model; \ | ||
| 91 | typedef typename Model::Matrix3s Matrix3s; \ | ||
| 92 | bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ | ||
| 93 | bp::class_<Model>( \ | ||
| 94 | "FrictionCone", "Model of the friction cone as lb <= Af <= ub", \ | ||
| 95 | bp::init<Matrix3s, Scalar, \ | ||
| 96 | bp::optional<std::size_t, bool, Scalar, Scalar>>( \ | ||
| 97 | bp::args("self", "R", "mu", "nf", "inner_appr", "min_nforce", \ | ||
| 98 | "max_nforce"), \ | ||
| 99 | "Initialize the linearize friction cone.\n\n" \ | ||
| 100 | ":param R: rotation matrix that defines the cone orientation " \ | ||
| 101 | "w.r.t. the inertial frame\n" \ | ||
| 102 | ":param mu: friction coefficient\n" \ | ||
| 103 | ":param nf: number of facets (default 4)\n" \ | ||
| 104 | ":param inner_appr: inner or outer approximation (default True)\n" \ | ||
| 105 | ":param min_nforce: minimum normal force (default 0.)\n" \ | ||
| 106 | ":param max_nforce: maximum normal force (default " \ | ||
| 107 | "sys.float_info.max)")) \ | ||
| 108 | .def(FrictionConeVisitor<Model>()) \ | ||
| 109 | .def(CastVisitor<Model>()) \ | ||
| 110 | .def(PrintableVisitor<Model>()) \ | ||
| 111 | .def(CopyableVisitor<Model>()); | ||
| 112 | |||
| 113 | 10 | void exposeFrictionCone() { | |
| 114 | #pragma GCC diagnostic push // TODO: Remove once the deprecated update call has | ||
| 115 | // been removed in a future release | ||
| 116 | #pragma GCC diagnostic ignored "-Wdeprecated-declarations" | ||
| 117 | |||
| 118 |
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_FRICTION_CONE_PYTHON_BINDINGS) |
| 119 | |||
| 120 | #pragma GCC diagnostic pop | ||
| 121 | 10 | } | |
| 122 | |||
| 123 | } // namespace python | ||
| 124 | } // namespace crocoddyl | ||
| 125 |