GCC Code Coverage Report


Directory: ./
File: bindings/python/crocoddyl/multibody/actions/free-invdyn-double.cpp
Date: 2025-04-18 16:41:15
Exec Total Coverage
Lines: 0 31 0.0%
Branches: 0 120 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 double
10 #include "crocoddyl/multibody/actions/free-invdyn.hpp"
11
12 #include "python/crocoddyl/core/diff-action-base.hpp"
13 #include "python/crocoddyl/multibody/multibody.hpp"
14
15 namespace crocoddyl {
16 namespace python {
17
18 template <typename Model>
19 struct DifferentialActionModelFreeInvDynamicsVisitor
20 : public bp::def_visitor<
21 DifferentialActionModelFreeInvDynamicsVisitor<Model>> {
22 typedef typename Model::DifferentialActionDataAbstract Data;
23 typedef typename Model::VectorXs VectorXs;
24 template <class PyClass>
25 void visit(PyClass& cl) const {
26 cl.def("calc",
27 static_cast<void (Model::*)(
28 const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&,
29 const Eigen::Ref<const VectorXs>&)>(&Model::calc),
30 bp::args("self", "data", "x", "u"),
31 "Compute the next state and cost value.\n\n"
32 ":param data: free inverse-dynamics data\n"
33 ":param x: state point (dim. state.nx)\n"
34 ":param u: control input (dim. nu)")
35 .def("calc",
36 static_cast<void (Model::*)(const std::shared_ptr<Data>&,
37 const Eigen::Ref<const VectorXs>&)>(
38 &Model::calc),
39 bp::args("self", "data", "x"))
40 .def(
41 "calcDiff",
42 static_cast<void (Model::*)(
43 const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&,
44 const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff),
45 bp::args("self", "data", "x", "u"),
46 "Compute the derivatives of the differential multibody system "
47 "(free of contact) and its cost functions.\n\n"
48 "It computes the partial derivatives of the differential multibody "
49 "system and the cost function. It assumes that calc has been run "
50 "first. This function builds a quadratic approximation of the\n"
51 "action model (i.e. dynamical system and cost function).\n"
52 ":param data: free inverse-dynamics data\n"
53 ":param x: state point (dim. state.nx)\n"
54 ":param u: control input (dim. nu)")
55 .def("calcDiff",
56 static_cast<void (Model::*)(const std::shared_ptr<Data>&,
57 const Eigen::Ref<const VectorXs>&)>(
58 &Model::calcDiff),
59 bp::args("self", "data", "x"))
60 .def("createData", &Model::createData, bp::args("self"),
61 "Create the free inverse-dynamics differential action data.")
62 .add_property(
63 "actuation",
64 bp::make_function(&Model::get_actuation,
65 bp::return_value_policy<bp::return_by_value>()),
66 "actuation model")
67 .add_property(
68 "costs",
69 bp::make_function(&Model::get_costs,
70 bp::return_value_policy<bp::return_by_value>()),
71 "total cost model")
72 .add_property(
73 "constraints",
74 bp::make_function(&Model::get_constraints,
75 bp::return_value_policy<bp::return_by_value>()),
76 "constraint model manager");
77 }
78 };
79
80 template <typename Model>
81 struct DifferentialActionModelFreeInvDynamicsResidualModelActuationVisitor
82 : public bp::def_visitor<
83 DifferentialActionModelFreeInvDynamicsResidualModelActuationVisitor<
84 Model>> {
85 typedef typename Model::ResidualDataAbstract Data;
86 typedef typename Model::VectorXs VectorXs;
87 template <class PyClass>
88 void visit(PyClass& cl) const {
89 cl.def("calc",
90 static_cast<void (Model::*)(
91 const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&,
92 const Eigen::Ref<const VectorXs>&)>(&Model::calc),
93 bp::args("self", "data", "x", "u"),
94 "Compute the actuation residual.\n\n"
95 ":param data: residual data\n"
96 ":param x: state point (dim. state.nx)\n"
97 ":param u: control input (dim. nu)")
98 .def("calc",
99 static_cast<void (Model::*)(const std::shared_ptr<Data>&,
100 const Eigen::Ref<const VectorXs>&)>(
101 &Model::calc),
102 bp::args("self", "data", "x"))
103 .def(
104 "calcDiff",
105 static_cast<void (Model::*)(
106 const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&,
107 const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff),
108 bp::args("self", "data", "x", "u"),
109 "Compute the Jacobians of the actuation residual.\n\n"
110 "It assumes that calc has been run first.\n"
111 ":param data: action data\n"
112 ":param x: state point (dim. state.nx)\n"
113 ":param u: control input (dim. nu)\n")
114 .def("calcDiff",
115 static_cast<void (Model::*)(const std::shared_ptr<Data>&,
116 const Eigen::Ref<const VectorXs>&)>(
117 &Model::calcDiff),
118 bp::args("self", "data", "x"))
119 .def("createData", &Model::createData,
120 bp::with_custodian_and_ward_postcall<0, 2>(),
121 bp::args("self", "data"),
122 "Create the actuation residual data.\n\n"
123 "Each residual model has its own data that needs to be allocated. "
124 "This function\n"
125 "returns the allocated data for the actuation residual.\n"
126 ":param data: shared data\n"
127 ":return residual data.");
128 }
129 };
130
131 template <typename Data>
132 struct DifferentialActionDataFreeInvDynamicsVisitor
133 : public bp::def_visitor<
134 DifferentialActionDataFreeInvDynamicsVisitor<Data>> {
135 template <class PyClass>
136 void visit(PyClass& cl) const {
137 cl.add_property(
138 "pinocchio",
139 bp::make_getter(&Data::pinocchio, bp::return_internal_reference<>()),
140 "pinocchio data")
141 .add_property("multibody",
142 bp::make_getter(&Data::multibody,
143 bp::return_internal_reference<>()),
144 "multibody data")
145 .add_property(
146 "costs",
147 bp::make_getter(&Data::costs,
148 bp::return_value_policy<bp::return_by_value>()),
149 "total cost data")
150 .add_property(
151 "constraints",
152 bp::make_getter(&Data::constraints,
153 bp::return_value_policy<bp::return_by_value>()),
154 "constraint data");
155 }
156 };
157
158 #define CROCODDYL_ACTION_MODEL_FREE_INVDYN_PYTHON_BINDINGS(Scalar) \
159 typedef DifferentialActionModelFreeInvDynamicsTpl<Scalar> Model; \
160 typedef DifferentialActionModelAbstractTpl<Scalar> ModelBase; \
161 typedef typename Model::StateMultibody State; \
162 typedef typename Model::ActuationModelAbstract Actuation; \
163 typedef typename Model::CostModelSum Costs; \
164 typedef typename Model::ConstraintModelManager Constraints; \
165 bp::register_ptr_to_python<std::shared_ptr<Model>>(); \
166 bp::scope model_outer = \
167 bp::class_<Model, bp::bases<ModelBase>>( \
168 "DifferentialActionModelFreeInvDynamics", \
169 "Differential action model for free inverse dynamics in multibody " \
170 "systems.\n\n" \
171 "This class implements the dynamics using Recursive Newton Euler " \
172 "Algorithm (RNEA) as an equality constraint. The stack of cost and " \
173 "constraint functions are implemented in ConstraintModelManager() " \
174 "and CostModelSum(), respectively.", \
175 bp::init<std::shared_ptr<State>, std::shared_ptr<Actuation>, \
176 std::shared_ptr<Costs>, \
177 bp::optional<std::shared_ptr<Constraints>>>( \
178 bp::args("self", "state", "actuation", "costs", "constraints"), \
179 "Initialize the free inverse-dynamics action model.\n\n" \
180 "It describes the kinematic evolution of the multibody system " \
181 "and computes the needed torques using inverse dynamics.\n" \
182 ":param state: multibody state\n" \
183 ":param actuation: abstract actuation model\n" \
184 ":param costs: stack of cost functions\n" \
185 ":param constraints: stack of constraint functions")) \
186 .def(DifferentialActionModelFreeInvDynamicsVisitor<Model>()) \
187 .def(CastVisitor<Model>()) \
188 .def(PrintableVisitor<Model>()) \
189 .def(CopyableVisitor<Model>()); \
190 typedef typename Model::ResidualModelActuation ResidualModelActuation; \
191 typedef typename ResidualModelActuation::Base ResidualModelBase; \
192 bp::register_ptr_to_python<std::shared_ptr<ResidualModelActuation>>(); \
193 bp::class_<ResidualModelActuation, bp::bases<ResidualModelBase>>( \
194 "ResidualModelActuation", \
195 "This residual function enforces the torques of under-actuated joints " \
196 "(e.g., floating-base joints) to be zero. We compute these torques and " \
197 "their derivatives using RNEA inside " \
198 "DifferentialActionModelFreeInvDynamics.", \
199 bp::init<std::shared_ptr<State>, std::size_t>( \
200 bp::args("self", "state", "nu"), \
201 "Initialize the actuation residual model.\n\n" \
202 ":param state: state description\n" \
203 ":param nu: dimension of the joint torques")) \
204 .def( \
205 DifferentialActionModelFreeInvDynamicsResidualModelActuationVisitor< \
206 ResidualModelActuation>()) \
207 .def(CopyableVisitor<ResidualModelActuation>());
208
209 #define CROCODDYL_ACTION_DATA_FREE_INVDYN_PYTHON_BINDINGS(Scalar) \
210 typedef DifferentialActionDataFreeInvDynamicsTpl<Scalar> Data; \
211 typedef DifferentialActionDataAbstractTpl<Scalar> DataBase; \
212 typedef DifferentialActionModelFreeInvDynamicsTpl<Scalar> Model; \
213 bp::register_ptr_to_python<std::shared_ptr<Data>>(); \
214 bp::scope data_outer = \
215 bp::class_<Data, bp::bases<DataBase>>( \
216 "DifferentialActionDataFreeInvDynamics", \
217 "Action data for the free inverse-dynamics system.", \
218 bp::init<Model*>( \
219 bp::args("self", "model"), \
220 "Create free inverse-dynamics action data.\n\n" \
221 ":param model: free inverse-dynamics action model")) \
222 .def(DifferentialActionDataFreeInvDynamicsVisitor<Data>()) \
223 .def(CopyableVisitor<Data>()); \
224 typedef typename Model::ResidualModelActuation ResidualModelActuation; \
225 typedef typename Data::ResidualDataActuation ResidualDataActuation; \
226 typedef typename ResidualDataActuation::Base ResidualDataBase; \
227 typedef \
228 typename ResidualModelActuation::DataCollectorAbstract DataCollector; \
229 bp::register_ptr_to_python<std::shared_ptr<ResidualDataActuation>>(); \
230 bp::class_<ResidualDataActuation, bp::bases<ResidualDataBase>>( \
231 "ResidualDataActuation", "Data for actuation residual.\n\n", \
232 bp::init<ResidualModelActuation*, DataCollector*>( \
233 bp::args("self", "model", "data"), \
234 "Create actuation residual data.\n\n" \
235 ":param model: actuation residual model\n" \
236 ":param data: shared data")[bp::with_custodian_and_ward< \
237 1, 2, bp::with_custodian_and_ward<1, 3>>()]) \
238 .def(CopyableVisitor<ResidualDataActuation>());
239
240 void exposeDifferentialActionFreeInvDynamics() {
241 CROCODDYL_ACTION_MODEL_FREE_INVDYN_PYTHON_BINDINGS(double)
242 CROCODDYL_ACTION_DATA_FREE_INVDYN_PYTHON_BINDINGS(double)
243 }
244
245 } // namespace python
246 } // namespace crocoddyl
247