GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: bindings/python/crocoddyl/multibody/friction-cone.cpp Lines: 42 43 97.7 %
Date: 2024-02-13 11:12:33 Branches: 36 72 50.0 %

Line Branch Exec Source
1
///////////////////////////////////////////////////////////////////////////////
2
// BSD 3-Clause License
3
//
4
// Copyright (C) 2019-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/friction-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 exposeFrictionCone() {
21
10
  bp::register_ptr_to_python<boost::shared_ptr<FrictionCone> >();
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
10
  bp::class_<FrictionCone>(
28
      "FrictionCone", "Model of the friction cone as lb <= Af <= ub",
29
10
      bp::init<Eigen::Matrix3d, double,
30
               bp::optional<std::size_t, bool, double, double> >(
31
20
          bp::args("self", "R", "mu", "nf", "inner_appr", "min_nforce",
32
                   "max_nforce"),
33
          "Initialize the linearize friction cone.\n\n"
34
          ":param R: rotation matrix that defines the cone orientation w.r.t. "
35
          "the inertial frame\n"
36
          ":param mu: friction coefficient\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

20
      .def(bp::init<>(bp::args("self"),
43
10
                      "Default initialization of the friction cone."))
44
      .def<void (FrictionCone::*)()>(
45
20
          "update", &FrictionCone::update, bp::args("self"),
46
          "Update the linear inequality (matrix and bounds).\n\n"
47
20
          "Run this function if you have changed one of the parameters.")
48
      .def<void (FrictionCone::*)(const Eigen::Vector3d&, const double,
49
                                  const bool, const double, const double)>(
50
          "update", &FrictionCone::update,
51

20
          deprecated<>("Deprecated. Use update()."),
52
20
          bp::args("self", "nsurf", "mu", "inner_appr", "min_nforce",
53
                   "max_nforce"),
54
          "Update the linear inequality (matrix and bounds).\n\n"
55
          ":param nsurf: surface normal vector (it defines the cone "
56
          "orientation)\n"
57
          ":param mu: friction coefficient\n"
58
          ":param inner_appr: inner or outer approximation (default True)\n"
59
          ":param min_nforce: minimum normal force (default 0.)\n"
60
          ":param max_nforce: maximum normal force (default "
61
10
          "sys.float_info.max)")
62
      .add_property("A",
63
10
                    bp::make_function(&FrictionCone::get_A,
64
10
                                      bp::return_internal_reference<>()),
65

20
                    "inequality matrix")
66
      .add_property("ub",
67
10
                    bp::make_function(&FrictionCone::get_ub,
68
10
                                      bp::return_internal_reference<>()),
69
10
                    "inequality upper bound")
70
      .add_property("lb",
71
10
                    bp::make_function(&FrictionCone::get_lb,
72
10
                                      bp::return_internal_reference<>()),
73
10
                    "inequality lower bound")
74
      .add_property(
75
          "nf",
76
10
          bp::make_function(&FrictionCone::get_nf,
77
10
                            bp::return_value_policy<bp::return_by_value>()),
78
10
          "number of facets (run update() if you have changed the value)")
79
      .add_property("R",
80
10
                    bp::make_function(&FrictionCone::get_R,
81
                                      bp::return_internal_reference<>()),
82
20
                    bp::make_function(&FrictionCone::set_R),
83
                    "rotation matrix that defines the cone orientation w.r.t. "
84
                    "the inertial frame (run update() if you "
85
10
                    "have changed the value)")
86
      .add_property(
87
10
          "mu", bp::make_function(&FrictionCone::get_mu),
88
20
          bp::make_function(&FrictionCone::set_mu),
89
10
          "friction coefficient (run update() if you have changed the value)")
90
      .add_property("inner_appr",
91
10
                    bp::make_function(&FrictionCone::get_inner_appr),
92
20
                    bp::make_function(&FrictionCone::set_inner_appr),
93
                    "type of cone approximation (run update() if you have "
94
10
                    "changed the value)")
95
      .add_property(
96
10
          "min_nforce", bp::make_function(&FrictionCone::get_min_nforce),
97
20
          bp::make_function(&FrictionCone::set_min_nforce),
98
10
          "minimum normal force (run update() if you have changed the value)")
99
      .add_property(
100
10
          "max_nforce", bp::make_function(&FrictionCone::get_max_nforce),
101
20
          bp::make_function(&FrictionCone::set_max_nforce),
102
10
          "maximum normal force (run update() if you have changed the value)")
103
10
      .def(CopyableVisitor<FrictionCone>())
104
10
      .def(PrintableVisitor<FrictionCone>());
105
106
#pragma GCC diagnostic pop
107
10
}
108
109
}  // namespace python
110
}  // namespace crocoddyl