GCC Code Coverage Report


Directory: ./
File: bindings/python/crocoddyl/multibody/wrench-cone.cpp
Date: 2025-02-24 23:41:29
Exec Total Coverage
Lines: 43 47 91.5%
Branches: 39 78 50.0%

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