GCC Code Coverage Report


Directory: ./
File: bindings/python/crocoddyl/multibody/residuals/centroidal-momentum.cpp
Date: 2025-03-26 19:23:43
Exec Total Coverage
Lines: 22 23 95.7%
Branches: 52 104 50.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2021-2025, 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
13 namespace crocoddyl {
14 namespace python {
15
16 template <typename Model>
17 struct ResidualModelCentroidalMomentumVisitor
18 : public bp::def_visitor<ResidualModelCentroidalMomentumVisitor<Model>> {
19 typedef typename Model::ResidualDataAbstract Data;
20 typedef typename Model::Base ModelBase;
21 typedef typename Model::StateMultibody State;
22 typedef typename Model::VectorXs VectorXs;
23 typedef typename Model::Vector6s Vector6s;
24 template <class PyClass>
25 40 void visit(PyClass& cl) const {
26
2/4
✓ Branch 2 taken 20 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
40 cl.def(bp::init<std::shared_ptr<State>, Vector6s>(
27 bp::args("self", "state", "href"),
28 "Initialize the centroidal momentum residual model.\n\n"
29 "The default nu is obtained from state.nv.\n"
30 ":param state: state of the multibody system\n"
31 ":param href: reference centroidal momentum"))
32
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
80 .def(
33 "calc",
34 static_cast<void (Model::*)(
35 const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&,
36 const Eigen::Ref<const VectorXs>&)>(&Model::calc),
37 bp::args("self", "data", "x", "u"),
38 "Compute the centroidal momentum residual.\n\n"
39 ":param data: residual data\n"
40 ":param x: state point (dim. state.nx)\n"
41 ":param u: control input (dim. nu)")
42
3/6
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
80 .def(
43 "calc",
44 static_cast<void (ModelBase::*)(const std::shared_ptr<Data>&,
45 const Eigen::Ref<const VectorXs>&)>(
46 &ModelBase::calc),
47 bp::args("self", "data", "x"))
48
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
80 .def(
49 "calcDiff",
50 static_cast<void (Model::*)(
51 const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&,
52 const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff),
53 bp::args("self", "data", "x", "u"),
54 "Compute the Jacobians of the centroidal momentum residual.\n\n"
55 "It assumes that calc has been run first.\n"
56 ":param data: action data\n"
57 ":param x: state point (dim. state.nx)\n"
58 ":param u: control input (dim. nu)")
59
3/6
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
80 .def(
60 "calcDiff",
61 static_cast<void (ModelBase::*)(const std::shared_ptr<Data>&,
62 const Eigen::Ref<const VectorXs>&)>(
63 &ModelBase::calcDiff),
64 bp::args("self", "data", "x"))
65
1/2
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
80 .def("createData", &ResidualModelCentroidalMomentum::createData,
66 bp::with_custodian_and_ward_postcall<0, 2>(),
67 bp::args("self", "data"),
68 "Create the centroidal momentum residual data.\n\n"
69 "Each residual model has its own data that needs to be allocated. "
70 "This function returns the allocated data for the centroidal "
71 "momentum residual.\n"
72 ":param data: shared data\n"
73 ":return residual data.")
74
3/6
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
40 .add_property("reference",
75 bp::make_function(&Model::get_reference,
76 40 bp::return_internal_reference<>()),
77 &Model::set_reference, "reference centroidal momentum");
78 40 }
79 };
80
81 template <typename Data>
82 struct ResidualDataCentroidalMomentumVisitor
83 : public bp::def_visitor<ResidualDataCentroidalMomentumVisitor<Data>> {
84 template <class PyClass>
85 40 void visit(PyClass& cl) const {
86
2/4
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
40 cl.add_property(
87 "pinocchio",
88 40 bp::make_getter(&Data::pinocchio, bp::return_internal_reference<>()),
89 "pinocchio data")
90
2/4
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
40 .add_property(
91 "dhd_dq",
92 40 bp::make_getter(&Data::dhd_dq, bp::return_internal_reference<>()),
93 "Jacobian of the centroidal momentum")
94
2/4
✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
40 .add_property(
95 "dhd_dv",
96 40 bp::make_getter(&Data::dhd_dv, bp::return_internal_reference<>()),
97 "Jacobian of the centroidal momentum");
98 40 }
99 };
100
101 #define CROCODDYL_RESIDUAL_MODEL_CENTROIDAL_MOMENTUM_PYTHON_BINDINGS(Scalar) \
102 typedef ResidualModelCentroidalMomentumTpl<Scalar> Model; \
103 typedef ResidualModelAbstractTpl<Scalar> ModelBase; \
104 typedef typename Model::StateMultibody State; \
105 typedef typename Model::Vector6s Vector6s; \
106 bp::register_ptr_to_python<std::shared_ptr<Model>>(); \
107 bp::class_<Model, bp::bases<ModelBase>>( \
108 "ResidualModelCentroidalMomentum", \
109 "This residual function defines the centroidal momentum tracking as r " \
110 "= h - href, with h and href as the current and reference centroidal " \
111 "momenta, respectively.", \
112 bp::init<std::shared_ptr<State>, Vector6s, std::size_t>( \
113 bp::args("self", "state", "href", "nu"), \
114 "Initialize the centroidal momentum residual model.\n\n" \
115 ":param state: state of the multibody system\n" \
116 ":param href: reference centroidal momentum\n" \
117 ":param nu: dimension of control vector")) \
118 .def(ResidualModelCentroidalMomentumVisitor<Model>()) \
119 .def(CastVisitor<Model>()) \
120 .def(PrintableVisitor<Model>()) \
121 .def(CopyableVisitor<Model>());
122
123 #define CROCODDYL_RESIDUAL_DATA_CENTROIDAL_MOMENTUM_PYTHON_BINDINGS(Scalar) \
124 typedef ResidualDataCentroidalMomentumTpl<Scalar> Data; \
125 typedef ResidualDataAbstractTpl<Scalar> DataBase; \
126 typedef ResidualModelCentroidalMomentumTpl<Scalar> Model; \
127 typedef Model::DataCollectorAbstract DataCollector; \
128 bp::register_ptr_to_python<std::shared_ptr<Data>>(); \
129 bp::class_<Data, bp::bases<DataBase>>( \
130 "ResidualDataCentroidalMomentum", \
131 "Data for centroidal momentum residual.\n\n", \
132 bp::init<Model*, DataCollector*>( \
133 bp::args("self", "model", "data"), \
134 "Create centroidal momentum residual data.\n\n" \
135 ":param model: centroidal momentum residual model\n" \
136 ":param data: shared data")[bp::with_custodian_and_ward< \
137 1, 2, bp::with_custodian_and_ward<1, 3>>()]) \
138 .def(ResidualDataCentroidalMomentumVisitor<Data>()) \
139 .def(CopyableVisitor<Data>());
140
141 10 void exposeResidualCentroidalMomentum() {
142
17/34
✓ Branch 3 taken 10 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 10 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 10 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 10 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 10 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 10 times.
✗ Branch 19 not taken.
✓ Branch 24 taken 10 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 10 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 10 times.
✗ Branch 31 not taken.
✓ Branch 35 taken 10 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 10 times.
✗ Branch 39 not taken.
✓ Branch 41 taken 10 times.
✗ Branch 42 not taken.
✓ Branch 44 taken 10 times.
✗ Branch 45 not taken.
✓ Branch 47 taken 10 times.
✗ Branch 48 not taken.
✓ Branch 50 taken 10 times.
✗ Branch 51 not taken.
✓ Branch 53 taken 10 times.
✗ Branch 54 not taken.
✓ Branch 56 taken 10 times.
✗ Branch 57 not taken.
20 CROCODDYL_PYTHON_SCALARS(
143 CROCODDYL_RESIDUAL_MODEL_CENTROIDAL_MOMENTUM_PYTHON_BINDINGS)
144
15/30
✓ Branch 3 taken 10 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 10 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 10 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 10 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 10 times.
✗ Branch 16 not taken.
✓ Branch 21 taken 10 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 10 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 10 times.
✗ Branch 28 not taken.
✓ Branch 32 taken 10 times.
✗ Branch 33 not taken.
✓ Branch 35 taken 10 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 10 times.
✗ Branch 39 not taken.
✓ Branch 41 taken 10 times.
✗ Branch 42 not taken.
✓ Branch 44 taken 10 times.
✗ Branch 45 not taken.
✓ Branch 47 taken 10 times.
✗ Branch 48 not taken.
✓ Branch 50 taken 10 times.
✗ Branch 51 not taken.
20 CROCODDYL_PYTHON_SCALARS(
145 CROCODDYL_RESIDUAL_DATA_CENTROIDAL_MOMENTUM_PYTHON_BINDINGS)
146 10 }
147
148 } // namespace python
149 } // namespace crocoddyl
150