GCC Code Coverage Report


Directory: ./
File: bindings/python/crocoddyl/multibody/wrench-cone-float.cpp
Date: 2025-04-18 16:41:15
Exec Total Coverage
Lines: 0 25 0.0%
Branches: 0 80 0.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2020-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 // Auto-generated file for float
11 #include "crocoddyl/multibody/wrench-cone.hpp"
12
13 #include "python/crocoddyl/multibody/multibody.hpp"
14 #include "python/crocoddyl/utils/copyable.hpp"
15 #include "python/crocoddyl/utils/deprecate.hpp"
16 #include "python/crocoddyl/utils/printable.hpp"
17
18 namespace crocoddyl {
19 namespace python {
20
21 template <typename Model>
22 struct WrenchConeVisitor : public bp::def_visitor<WrenchConeVisitor<Model>> {
23 typedef typename Model::Scalar Scalar;
24 typedef typename Model::Matrix3s Matrix3s;
25 typedef typename Model::Vector2s Vector2s;
26 template <class PyClass>
27 void visit(PyClass& cl) const {
28 cl.def(bp::init<>(bp::args("self"),
29 "Default initialization of the wrench cone."))
30 .def("update", static_cast<void (Model::*)()>(&Model::update),
31 bp::args("self"),
32 "Update the linear inequality (matrix and bounds).\n\n"
33 "Run this function if you have changed one of the parameters.")
34 .def("update",
35 static_cast<void (Model::*)(const Matrix3s&, const Scalar,
36 const Vector2s&, const Scalar,
37 const Scalar)>(&Model::update),
38 deprecated<>("Deprecated. Use update()."),
39 bp::args("self", "R", "mu", "box", "min_nforce", "max_nforce"),
40 "Update the linear inequality (matrix and bounds).\n\n"
41 ":param R: rotation matrix that defines the cone orientation\n"
42 ":param mu: friction coefficient\n"
43 ":param box: dimension of the foot surface dim = (length, width)\n"
44 ":param min_nforce: minimum normal force (default 0.)\n"
45 ":param max_nforce: maximum normal force (default "
46 "sys.float_info.max)")
47 .add_property(
48 "A",
49 bp::make_function(&Model::get_A, bp::return_internal_reference<>()),
50 "inequality matrix")
51 .add_property("ub",
52 bp::make_function(&Model::get_ub,
53 bp::return_internal_reference<>()),
54 "inequality upper bound")
55 .add_property("lb",
56 bp::make_function(&Model::get_lb,
57 bp::return_internal_reference<>()),
58 "inequality lower bound")
59 .add_property(
60 "nf",
61 bp::make_function(&Model::get_nf,
62 bp::return_value_policy<bp::return_by_value>()),
63 "number of facets")
64 .add_property(
65 "R",
66 bp::make_function(&Model::get_R, bp::return_internal_reference<>()),
67 bp::make_function(&Model::set_R), "rotation matrix")
68 .add_property("box",
69 bp::make_function(&Model::get_box,
70 bp::return_internal_reference<>()),
71 bp::make_function(&Model::set_box),
72 "box size used to define the sole")
73 .add_property("mu", bp::make_function(&Model::get_mu),
74 bp::make_function(&Model::set_mu), "friction coefficient")
75 .add_property("inner_appr", bp::make_function(&Model::get_inner_appr),
76 bp::make_function(&Model::set_inner_appr),
77 "type of friction cone approximation")
78 .add_property(
79 "min_nforce",
80 bp::make_function(&Model::get_min_nforce,
81 bp::return_value_policy<bp::return_by_value>()),
82 bp::make_function(&Model::set_min_nforce), "minimum normal force")
83 .add_property(
84 "max_nforce",
85 bp::make_function(&Model::get_max_nforce,
86 bp::return_value_policy<bp::return_by_value>()),
87 bp::make_function(&Model::set_max_nforce), "maximum normal force");
88 }
89 };
90
91 #define CROCODDYL_WRENCH_CONE_PYTHON_BINDINGS(Scalar) \
92 typedef WrenchConeTpl<Scalar> Model; \
93 typedef typename Model::Matrix3s Matrix3s; \
94 typedef typename Model::Vector2s Vector2s; \
95 bp::register_ptr_to_python<std::shared_ptr<Model>>(); \
96 bp::class_<Model>( \
97 "WrenchCone", "Model of the wrench cone as lb <= Af <= ub", \
98 bp::init<Matrix3s, Scalar, Vector2s, \
99 bp::optional<std::size_t, bool, Scalar, Scalar>>( \
100 bp::args("self", "R", "mu", "box", "nf", "inner_appr", "min_nforce", \
101 "max_nforce"), \
102 "Initialize the linearize wrench cone.\n\n" \
103 ":param R: rotation matrix that defines the cone orientation\n" \
104 ":param mu: friction coefficient\n" \
105 ":param box: dimension of the foot surface dim = (length, width)\n" \
106 ":param nf: number of facets (default 4)\n" \
107 ":param inner_appr: inner or outer approximation (default True)\n" \
108 ":param min_nforce: minimum normal force (default 0.)\n" \
109 ":param max_nforce: maximum normal force (default " \
110 "sys.float_info.max)")) \
111 .def(WrenchConeVisitor<Model>()) \
112 .def(CastVisitor<Model>()) \
113 .def(PrintableVisitor<Model>()) \
114 .def(CopyableVisitor<Model>());
115
116 void exposeWrenchCone() {
117 #pragma GCC diagnostic push // TODO: Remove once the deprecated update call has
118 // been removed in a future release
119 #pragma GCC diagnostic ignored "-Wdeprecated-declarations"
120
121 CROCODDYL_WRENCH_CONE_PYTHON_BINDINGS(float)
122
123 #pragma GCC diagnostic pop
124 }
125
126 } // namespace python
127 } // namespace crocoddyl
128