GCC Code Coverage Report


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