GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: bindings/python/crocoddyl/multibody/residuals/com-position.cpp Lines: 30 32 93.8 %
Date: 2024-02-13 11:12:33 Branches: 25 50 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/com-position.hpp"
10
11
#include "python/crocoddyl/multibody/multibody.hpp"
12
#include "python/crocoddyl/utils/copyable.hpp"
13
14
namespace crocoddyl {
15
namespace python {
16
17
10
void exposeResidualCoMPosition() {
18
10
  bp::register_ptr_to_python<boost::shared_ptr<ResidualModelCoMPosition> >();
19
20
10
  bp::class_<ResidualModelCoMPosition, bp::bases<ResidualModelAbstract> >(
21
      "ResidualModelCoMPosition",
22
      "This residual function defines the CoM tracking as r = c - cref, with c "
23
      "and cref as the current and reference "
24
      "CoM position, respectively.",
25
10
      bp::init<boost::shared_ptr<StateMultibody>, Eigen::Vector3d, std::size_t>(
26
20
          bp::args("self", "state", "cref", "nu"),
27
          "Initialize the CoM position residual model.\n\n"
28
          ":param state: state of the multibody system\n"
29
          ":param cref: reference CoM position\n"
30
          ":param nu: dimension of control vector"))
31
10
      .def(bp::init<boost::shared_ptr<StateMultibody>, Eigen::Vector3d>(
32
20
          bp::args("self", "state", "cref"),
33
          "Initialize the CoM position residual model.\n\n"
34
          "The default nu is obtained from state.nv.\n"
35
          ":param state: state of the multibody system\n"
36
10
          ":param cref: reference CoM position"))
37
      .def<void (ResidualModelCoMPosition::*)(
38
          const boost::shared_ptr<ResidualDataAbstract>&,
39
          const Eigen::Ref<const Eigen::VectorXd>&,
40
          const Eigen::Ref<const Eigen::VectorXd>&)>(
41
          "calc", &ResidualModelCoMPosition::calc,
42
20
          bp::args("self", "data", "x", "u"),
43
          "Compute the CoM position residual.\n\n"
44
          ":param data: residual data\n"
45
          ":param x: state point (dim. state.nx)\n"
46
10
          ":param u: control input (dim. nu)")
47
      .def<void (ResidualModelCoMPosition::*)(
48
          const boost::shared_ptr<ResidualDataAbstract>&,
49
          const Eigen::Ref<const Eigen::VectorXd>&)>(
50
20
          "calc", &ResidualModelAbstract::calc, bp::args("self", "data", "x"))
51
      .def<void (ResidualModelCoMPosition::*)(
52
          const boost::shared_ptr<ResidualDataAbstract>&,
53
          const Eigen::Ref<const Eigen::VectorXd>&,
54
          const Eigen::Ref<const Eigen::VectorXd>&)>(
55
          "calcDiff", &ResidualModelCoMPosition::calcDiff,
56
20
          bp::args("self", "data", "x", "u"),
57
          "Compute the Jacobians of the CoM position residual.\n\n"
58
          "It assumes that calc has been run first.\n"
59
          ":param data: action data\n"
60
          ":param x: state point (dim. state.nx)\n"
61

20
          ":param u: control input (dim. nu)")
62
      .def<void (ResidualModelCoMPosition::*)(
63
          const boost::shared_ptr<ResidualDataAbstract>&,
64
          const Eigen::Ref<const Eigen::VectorXd>&)>(
65
          "calcDiff", &ResidualModelAbstract::calcDiff,
66
20
          bp::args("self", "data", "x"))
67
      .def("createData", &ResidualModelCoMPosition::createData,
68
           bp::with_custodian_and_ward_postcall<0, 2>(),
69
20
           bp::args("self", "data"),
70
           "Create the CoM position residual data.\n\n"
71
           "Each residual model has its own data that needs to be allocated. "
72
           "This function\n"
73
           "returns the allocated data for a predefined residual.\n"
74
           ":param data: shared data\n"
75

20
           ":return residual data.")
76
      .add_property("reference",
77
                    bp::make_function(&ResidualModelCoMPosition::get_reference,
78
10
                                      bp::return_internal_reference<>()),
79
                    &ResidualModelCoMPosition::set_reference,
80

10
                    "reference CoM position")
81
10
      .def(CopyableVisitor<ResidualModelCoMPosition>());
82
83
10
  bp::register_ptr_to_python<boost::shared_ptr<ResidualDataCoMPosition> >();
84
85
10
  bp::class_<ResidualDataCoMPosition, bp::bases<ResidualDataAbstract> >(
86
      "ResidualDataCoMPosition", "Data for CoM position residual.\n\n",
87
10
      bp::init<ResidualModelCoMPosition*, DataCollectorAbstract*>(
88
10
          bp::args("self", "model", "data"),
89
          "Create CoM position residual data.\n\n"
90
          ":param model: CoM position residual model\n"
91
10
          ":param data: shared data")[bp::with_custodian_and_ward<
92
20
          1, 2, bp::with_custodian_and_ward<1, 3> >()])
93
      .add_property("pinocchio",
94
10
                    bp::make_getter(&ResidualDataCoMPosition::pinocchio,
95
10
                                    bp::return_internal_reference<>()),
96
10
                    "pinocchio data")
97
10
      .def(CopyableVisitor<ResidualDataCoMPosition>());
98
10
}
99
100
}  // namespace python
101
}  // namespace crocoddyl