GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: bindings/python/crocoddyl/multibody/residuals/contact-friction-cone.cpp Lines: 34 37 91.9 %
Date: 2024-02-13 11:12:33 Branches: 31 62 50.0 %

Line Branch Exec Source
1
///////////////////////////////////////////////////////////////////////////////
2
// BSD 3-Clause License
3
//
4
// Copyright (C) 2019-2023, 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/residuals/contact-friction-cone.hpp"
10
11
#include "python/crocoddyl/multibody/multibody.hpp"
12
#include "python/crocoddyl/utils/copyable.hpp"
13
#include "python/crocoddyl/utils/deprecate.hpp"
14
15
namespace crocoddyl {
16
namespace python {
17
18
10
void exposeResidualContactFrictionCone() {
19
  bp::register_ptr_to_python<
20
10
      boost::shared_ptr<ResidualModelContactFrictionCone> >();
21
22
10
  bp::class_<ResidualModelContactFrictionCone,
23
             bp::bases<ResidualModelAbstract> >(
24
      "ResidualModelContactFrictionCone",
25
      "This residual function is defined as r = A*f, where A, f describe the "
26
      "linearized friction cone and\n"
27
      "the spatial force, respectively.",
28
10
      bp::init<boost::shared_ptr<StateMultibody>, pinocchio::FrameIndex,
29
               FrictionCone, std::size_t, bp::optional<bool> >(
30
20
          bp::args("self", "state", "id", "fref", "nu", "fwddyn"),
31
          "Initialize the contact friction cone residual model.\n\n"
32
          ":param state: state of the multibody system\n"
33
          ":param id: reference frame id\n"
34
          ":param fref: frame friction cone\n"
35
          ":param nu: dimension of control vector\n"
36
          ":param fwddyn: indicate if we have a forward dynamics problem "
37
          "(True) or inverse "
38
          "dynamics problem (False) (default True)"))
39
10
      .def(bp::init<boost::shared_ptr<StateMultibody>, pinocchio::FrameIndex,
40
                    FrictionCone>(
41
20
          bp::args("self", "state", "id", "fref"),
42
          "Initialize the contact friction cone residual model.\n\n"
43
          "The default nu is obtained from state.nv. Note that this "
44
          "constructor can be used for forward-dynamics\n"
45
          "cases only.\n"
46
          ":param state: state of the multibody system\n"
47
          ":param id: reference frame id\n"
48
10
          ":param fref: frame friction cone"))
49
      .def<void (ResidualModelContactFrictionCone::*)(
50
          const boost::shared_ptr<ResidualDataAbstract>&,
51
          const Eigen::Ref<const Eigen::VectorXd>&,
52
          const Eigen::Ref<const Eigen::VectorXd>&)>(
53
          "calc", &ResidualModelContactFrictionCone::calc,
54
20
          bp::args("self", "data", "x", "u"),
55
          "Compute the contact friction cone residual.\n\n"
56
          ":param data: residual data\n"
57
          ":param x: state point (dim. state.nx)\n"
58
20
          ":param u: control input (dim. nu)")
59
      .def<void (ResidualModelContactFrictionCone::*)(
60
          const boost::shared_ptr<ResidualDataAbstract>&,
61
          const Eigen::Ref<const Eigen::VectorXd>&)>(
62

20
          "calc", &ResidualModelAbstract::calc, bp::args("self", "data", "x"))
63
      .def<void (ResidualModelContactFrictionCone::*)(
64
          const boost::shared_ptr<ResidualDataAbstract>&,
65
          const Eigen::Ref<const Eigen::VectorXd>&,
66
          const Eigen::Ref<const Eigen::VectorXd>&)>(
67
          "calcDiff", &ResidualModelContactFrictionCone::calcDiff,
68
20
          bp::args("self", "data", "x", "u"),
69
          "Compute the Jacobians of the contact friction cone residual.\n\n"
70
          "It assumes that calc has been run first.\n"
71
          ":param data: action data\n"
72
          ":param x: state point (dim. state.nx)\n"
73
10
          ":param u: control input (dim. nu)")
74
      .def<void (ResidualModelContactFrictionCone::*)(
75
          const boost::shared_ptr<ResidualDataAbstract>&,
76
          const Eigen::Ref<const Eigen::VectorXd>&)>(
77
          "calcDiff", &ResidualModelAbstract::calcDiff,
78

20
          bp::args("self", "data", "x"))
79
      .def(
80
          "createData", &ResidualModelContactFrictionCone::createData,
81
          bp::with_custodian_and_ward_postcall<0, 2>(),
82
20
          bp::args("self", "data"),
83
          "Create the contact friction cone residual data.\n\n"
84
          "Each residual model has its own data that needs to be allocated. "
85
          "This function\n"
86
          "returns the allocated data for the contact friction cone residual.\n"
87
          ":param data: shared data\n"
88

20
          ":return residual data.")
89
      .add_property(
90
10
          "id", bp::make_function(&ResidualModelContactFrictionCone::get_id),
91
20
          bp::make_function(
92
              &ResidualModelContactFrictionCone::set_id,
93

20
              deprecated<>(
94
                  "Deprecated. Do not use set_id, instead create a new model")),
95
10
          "reference frame id")
96
      .add_property(
97
          "reference",
98
          bp::make_function(&ResidualModelContactFrictionCone::get_reference,
99
10
                            bp::return_internal_reference<>()),
100
          &ResidualModelContactFrictionCone::set_reference,
101

10
          "reference contact friction cone")
102
10
      .def(CopyableVisitor<ResidualModelContactFrictionCone>());
103
104
  bp::register_ptr_to_python<
105
10
      boost::shared_ptr<ResidualDataContactFrictionCone> >();
106
107
10
  bp::class_<ResidualDataContactFrictionCone, bp::bases<ResidualDataAbstract> >(
108
      "ResidualDataContactFrictionCone",
109
      "Data for contact friction cone residual.\n\n",
110
10
      bp::init<ResidualModelContactFrictionCone*, DataCollectorAbstract*>(
111
10
          bp::args("self", "model", "data"),
112
          "Create contact friction cone residual data.\n\n"
113
          ":param model: contact friction cone residual model\n"
114
10
          ":param data: shared data")[bp::with_custodian_and_ward<
115
20
          1, 2, bp::with_custodian_and_ward<1, 3> >()])
116
      .add_property(
117
          "contact",
118
10
          bp::make_getter(&ResidualDataContactFrictionCone::contact,
119
                          bp::return_value_policy<bp::return_by_value>()),
120
20
          bp::make_setter(&ResidualDataContactFrictionCone::contact),
121
10
          "contact data associated with the current residual")
122
10
      .def(CopyableVisitor<ResidualDataContactFrictionCone>());
123
10
}
124
125
}  // namespace python
126
}  // namespace crocoddyl