GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: bindings/python/crocoddyl/multibody/residuals/centroidal-momentum.cpp Lines: 36 38 94.7 %
Date: 2024-02-13 11:12:33 Branches: 29 58 50.0 %

Line Branch Exec Source
1
///////////////////////////////////////////////////////////////////////////////
2
// BSD 3-Clause License
3
//
4
// Copyright (C) 2021-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/centroidal-momentum.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 exposeResidualCentroidalMomentum() {
19
  typedef Eigen::Matrix<double, 6, 1> Vector6d;
20
21
  bp::register_ptr_to_python<
22
10
      boost::shared_ptr<ResidualModelCentroidalMomentum> >();
23
24
10
  bp::class_<ResidualModelCentroidalMomentum,
25
             bp::bases<ResidualModelAbstract> >(
26
      "ResidualModelCentroidalMomentum",
27
      "This residual function defines the centroidal momentum tracking as r = "
28
      "h - href, with h and href as the\n"
29
      "current and reference centroidal momenta, respectively.",
30
10
      bp::init<boost::shared_ptr<StateMultibody>, Vector6d, std::size_t>(
31
20
          bp::args("self", "state", "href", "nu"),
32
          "Initialize the centroidal momentum residual model.\n\n"
33
          ":param state: state of the multibody system\n"
34
          ":param href: reference centroidal momentum\n"
35
          ":param nu: dimension of control vector"))
36
10
      .def(bp::init<boost::shared_ptr<StateMultibody>, Vector6d>(
37
20
          bp::args("self", "state", "href"),
38
          "Initialize the centroidal momentum residual model.\n\n"
39
          "The default nu is obtained from state.nv.\n"
40
          ":param state: state of the multibody system\n"
41
10
          ":param href: reference centroidal momentum"))
42
      .def<void (ResidualModelCentroidalMomentum::*)(
43
          const boost::shared_ptr<ResidualDataAbstract>&,
44
          const Eigen::Ref<const Eigen::VectorXd>&,
45
          const Eigen::Ref<const Eigen::VectorXd>&)>(
46
          "calc", &ResidualModelCentroidalMomentum::calc,
47
20
          bp::args("self", "data", "x", "u"),
48
          "Compute the centroidal momentum residual.\n\n"
49
          ":param data: residual data\n"
50
          ":param x: state point (dim. state.nx)\n"
51
10
          ":param u: control input (dim. nu)")
52
      .def<void (ResidualModelCentroidalMomentum::*)(
53
          const boost::shared_ptr<ResidualDataAbstract>&,
54
          const Eigen::Ref<const Eigen::VectorXd>&)>(
55
20
          "calc", &ResidualModelAbstract::calc, bp::args("self", "data", "x"))
56
      .def<void (ResidualModelCentroidalMomentum::*)(
57
          const boost::shared_ptr<ResidualDataAbstract>&,
58
          const Eigen::Ref<const Eigen::VectorXd>&,
59
          const Eigen::Ref<const Eigen::VectorXd>&)>(
60
          "calcDiff", &ResidualModelCentroidalMomentum::calcDiff,
61
20
          bp::args("self", "data", "x", "u"),
62
          "Compute the Jacobians of the centroidal momentum residual.\n\n"
63
          "It assumes that calc has been run first.\n"
64
          ":param data: action data\n"
65
          ":param x: state point (dim. state.nx)\n"
66

20
          ":param u: control input (dim. nu)")
67
      .def<void (ResidualModelCentroidalMomentum::*)(
68
          const boost::shared_ptr<ResidualDataAbstract>&,
69
          const Eigen::Ref<const Eigen::VectorXd>&)>(
70
          "calcDiff", &ResidualModelAbstract::calcDiff,
71
20
          bp::args("self", "data", "x"))
72
      .def("createData", &ResidualModelCentroidalMomentum::createData,
73
           bp::with_custodian_and_ward_postcall<0, 2>(),
74
20
           bp::args("self", "data"),
75
           "Create the centroidal momentum residual data.\n\n"
76
           "Each residual model has its own data that needs to be allocated. "
77
           "This function\n"
78
           "returns the allocated data for the centroidal momentum residual.\n"
79
           ":param data: shared data\n"
80

20
           ":return residual data.")
81
      .add_property(
82
          "reference",
83
          bp::make_function(&ResidualModelCentroidalMomentum::get_reference,
84
10
                            bp::return_internal_reference<>()),
85
          &ResidualModelCentroidalMomentum::set_reference,
86

10
          "reference centroidal momentum")
87
10
      .def(CopyableVisitor<ResidualModelCentroidalMomentum>());
88
89
  bp::register_ptr_to_python<
90
10
      boost::shared_ptr<ResidualDataCentroidalMomentum> >();
91
92
10
  bp::class_<ResidualDataCentroidalMomentum, bp::bases<ResidualDataAbstract> >(
93
      "ResidualDataCentroidalMomentum",
94
      "Data for centroidal momentum residual.\n\n",
95
10
      bp::init<ResidualModelCentroidalMomentum*, DataCollectorAbstract*>(
96
10
          bp::args("self", "model", "data"),
97
          "Create centroidal momentum residual data.\n\n"
98
          ":param model: centroidal momentum residual model\n"
99
10
          ":param data: shared data")[bp::with_custodian_and_ward<
100
20
          1, 2, bp::with_custodian_and_ward<1, 3> >()])
101
      .add_property("pinocchio",
102
10
                    bp::make_getter(&ResidualDataCentroidalMomentum::pinocchio,
103
10
                                    bp::return_internal_reference<>()),
104
10
                    "pinocchio data")
105
      .add_property("dhd_dq",
106
10
                    bp::make_getter(&ResidualDataCentroidalMomentum::dhd_dq,
107
10
                                    bp::return_internal_reference<>()),
108
10
                    "Jacobian of the centroidal momentum")
109
      .add_property("dhd_dv",
110
10
                    bp::make_getter(&ResidualDataCentroidalMomentum::dhd_dv,
111
10
                                    bp::return_internal_reference<>()),
112
10
                    "Jacobian of the centroidal momentum")
113
10
      .def(CopyableVisitor<ResidualDataCentroidalMomentum>());
114
10
}
115
116
}  // namespace python
117
}  // namespace crocoddyl