GCC Code Coverage Report


Directory: ./
File: bindings/python/crocoddyl/multibody/residuals/contact-control-gravity-float.cpp
Date: 2025-04-18 16:41:15
Exec Total Coverage
Lines: 0 17 0.0%
Branches: 0 58 0.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2020-2025, LAAS-CNRS, University of Edinburgh,
5 // Heriot-Watt University
6 // Copyright note valid unless otherwise stated in individual files.
7 // All rights reserved.
8 ///////////////////////////////////////////////////////////////////////////////
9
10 // Auto-generated file for float
11 #include "crocoddyl/multibody/residuals/contact-control-gravity.hpp"
12
13 #include "python/crocoddyl/multibody/multibody.hpp"
14
15 namespace crocoddyl {
16 namespace python {
17
18 template <typename Model>
19 struct ResidualModelContactControlGravVisitor
20 : public bp::def_visitor<ResidualModelContactControlGravVisitor<Model>> {
21 typedef typename Model::ResidualDataAbstract Data;
22 typedef typename Model::Base ModelBase;
23 typedef typename Model::StateMultibody State;
24 typedef typename Model::VectorXs VectorXs;
25 template <class PyClass>
26 void visit(PyClass& cl) const {
27 cl.def(bp::init<std::shared_ptr<State>>(
28 bp::args("self", "state"),
29 "Initialize the contact control-gravity residual model.\n\n"
30 "The default nu is obtained from state.nv.\n"
31 ":param state: state description"))
32 .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 contact control-gravity 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 .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 .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 Jacobias of the contact control-gravity residual.\n\n"
55 ":param data: action data\n"
56 ":param x: state point (dim. state.nx)\n"
57 ":param u: control input (dim. nu)")
58 .def(
59 "calcDiff",
60 static_cast<void (ModelBase::*)(const std::shared_ptr<Data>&,
61 const Eigen::Ref<const VectorXs>&)>(
62 &ModelBase::calcDiff),
63 bp::args("self", "data", "x"))
64 .def("createData", &Model::createData,
65 bp::with_custodian_and_ward_postcall<0, 2>(),
66 bp::args("self", "data"),
67 "Create the contact control-gravity residual data.\n\n"
68 "Each residual model has its own data that needs to be allocated. "
69 "This function returns the allocated data for a predefined "
70 "residual.\n"
71 ":param data: shared data\n"
72 ":return residual data.");
73 }
74 };
75
76 template <typename Data>
77 struct ResidualDataContactControlGravVisitor
78 : public bp::def_visitor<ResidualDataContactControlGravVisitor<Data>> {
79 template <class PyClass>
80 void visit(PyClass& cl) const {
81 cl.add_property("pinocchio", bp::make_getter(&Data::pinocchio),
82 "Pinocchio data used for internal computations")
83 .add_property("actuation",
84 bp::make_getter(&Data::actuation,
85 bp::return_internal_reference<>()),
86 "actuation model")
87 .add_property(
88 "fext",
89 bp::make_getter(&Data::fext, bp::return_internal_reference<>()),
90 "external spatial forces");
91 }
92 };
93
94 #define CROCODDYL_RESIDUAL_MODEL_CONTACT_CONTROL_GRAV_PYTHON_BINDINGS(Scalar) \
95 typedef ResidualModelContactControlGravTpl<Scalar> Model; \
96 typedef ResidualModelAbstractTpl<Scalar> ModelBase; \
97 typedef typename Model::StateMultibody State; \
98 bp::register_ptr_to_python<std::shared_ptr<Model>>(); \
99 bp::class_<Model, bp::bases<ModelBase>>( \
100 "ResidualModelContactControlGrav", \
101 "This residual function defines a residual vector as r = u - " \
102 "g(q,fext), with u as the control, q as the position, fext as the " \
103 "external forces and g as the gravity vector in contact", \
104 bp::init<std::shared_ptr<State>, std::size_t>( \
105 bp::args("self", "state", "nu"), \
106 "Initialize the contact control-gravity residual model.\n\n" \
107 ":param state: state description\n" \
108 ":param nu: dimension of the control vector")) \
109 .def(ResidualModelContactControlGravVisitor<Model>()) \
110 .def(CastVisitor<Model>()) \
111 .def(PrintableVisitor<Model>()) \
112 .def(CopyableVisitor<Model>());
113
114 #define CROCODDYL_RESIDUAL_DATA_CONTACT_CONTROL_GRAV_PYTHON_BINDINGS(Scalar) \
115 typedef ResidualDataContactControlGravTpl<Scalar> Data; \
116 typedef ResidualDataAbstractTpl<Scalar> DataBase; \
117 typedef ResidualModelContactControlGravTpl<Scalar> Model; \
118 typedef Model::DataCollectorAbstract DataCollector; \
119 bp::register_ptr_to_python<std::shared_ptr<Data>>(); \
120 bp::class_<Data, bp::bases<DataBase>>( \
121 "ResidualDataContactControlGrav", \
122 "Data for control gravity residual in contact.\n\n", \
123 bp::init<Model*, DataCollector*>( \
124 bp::args("self", "model", "data"), \
125 "Create contact control-gravity gravity contact residual data.\n\n" \
126 ":param model: control gravity residual model in contact\n" \
127 ":param data: shared data")[bp::with_custodian_and_ward< \
128 1, 2, bp::with_custodian_and_ward<1, 3>>()]) \
129 .def(ResidualDataContactControlGravVisitor<Data>()) \
130 .def(CopyableVisitor<Data>());
131
132 void exposeResidualContactControlGrav() {
133 CROCODDYL_RESIDUAL_MODEL_CONTACT_CONTROL_GRAV_PYTHON_BINDINGS(float)
134 CROCODDYL_RESIDUAL_DATA_CONTACT_CONTROL_GRAV_PYTHON_BINDINGS(float)
135 }
136
137 } // namespace python
138 } // namespace crocoddyl
139