GCC Code Coverage Report


Directory: ./
File: bindings/python/crocoddyl/multibody/actions/free-fwddyn-float.cpp
Date: 2025-04-18 16:41:15
Exec Total Coverage
Lines: 0 32 0.0%
Branches: 0 84 0.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-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/actions/free-fwddyn.hpp"
12
13 #include "python/crocoddyl/core/diff-action-base.hpp"
14 #include "python/crocoddyl/multibody/multibody.hpp"
15
16 namespace crocoddyl {
17 namespace python {
18
19 template <typename Model>
20 struct DifferentialActionModelFreeFwdDynamicsVisitor
21 : public bp::def_visitor<
22 DifferentialActionModelFreeFwdDynamicsVisitor<Model>> {
23 typedef typename Model::DifferentialActionDataAbstract Data;
24 typedef typename Model::VectorXs VectorXs;
25 template <class PyClass>
26 void visit(PyClass& cl) const {
27 cl.def("calc",
28 static_cast<void (Model::*)(
29 const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&,
30 const Eigen::Ref<const VectorXs>&)>(&Model::calc),
31 bp::args("self", "data", "x", "u"),
32 "Compute the next state and cost value.\n\n"
33 "It describes the time-continuous evolution of the multibody system "
34 "without any contact. Additionally it computes the cost value "
35 "associated to this state and control pair.\n"
36 ":param data: free forward-dynamics action data\n"
37 ":param x: time-continuous state vector\n"
38 ":param u: time-continuous control input")
39 .def("calc",
40 static_cast<void (Model::*)(const std::shared_ptr<Data>&,
41 const Eigen::Ref<const VectorXs>&)>(
42 &Model::calc),
43 bp::args("self", "data", "x"))
44 .def(
45 "calcDiff",
46 static_cast<void (Model::*)(
47 const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&,
48 const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff),
49 bp::args("self", "data", "x", "u"),
50 "Compute the derivatives of the differential multibody system "
51 "(free of contact) and its cost functions.\n\n"
52 "It computes the partial derivatives of the differential multibody "
53 "system and the cost function. It assumes that calc has been run "
54 "first. This function builds a quadratic approximation of the "
55 "action model (i.e. dynamical system and cost function).\n"
56 ":param data: free forward-dynamics action data\n"
57 ":param x: time-continuous state vector\n"
58 ":param u: time-continuous control input\n")
59 .def("calcDiff",
60 static_cast<void (Model::*)(const std::shared_ptr<Data>&,
61 const Eigen::Ref<const VectorXs>&)>(
62 &Model::calcDiff),
63 bp::args("self", "data", "x"))
64 .def("createData", &Model::createData, bp::args("self"),
65 "Create the free forward dynamics differential action data.")
66 .add_property("pinocchio",
67 bp::make_function(&Model::get_pinocchio,
68 bp::return_internal_reference<>()),
69 "multibody model (i.e. pinocchio model)")
70 .add_property(
71 "actuation",
72 bp::make_function(&Model::get_actuation,
73 bp::return_value_policy<bp::return_by_value>()),
74 "actuation model")
75 .add_property(
76 "costs",
77 bp::make_function(&Model::get_costs,
78 bp::return_value_policy<bp::return_by_value>()),
79 "total cost model")
80 .add_property(
81 "constraints",
82 bp::make_function(&Model::get_constraints,
83 bp::return_value_policy<bp::return_by_value>()),
84 "constraint model manager")
85 .add_property("armature",
86 bp::make_function(&Model::get_armature,
87 bp::return_internal_reference<>()),
88 bp::make_function(&Model::set_armature),
89 "set an armature mechanism in the joints");
90 }
91 };
92
93 template <typename Data>
94 struct DifferentialActionDataFreeFwdDynamicsVisitor
95 : public bp::def_visitor<
96 DifferentialActionDataFreeFwdDynamicsVisitor<Data>> {
97 template <class PyClass>
98 void visit(PyClass& cl) const {
99 cl.add_property(
100 "pinocchio",
101 bp::make_getter(&Data::pinocchio, bp::return_internal_reference<>()),
102 "pinocchio data")
103 .add_property("multibody",
104 bp::make_getter(&Data::multibody,
105 bp::return_internal_reference<>()),
106 "multibody data")
107 .add_property(
108 "costs",
109 bp::make_getter(&Data::costs,
110 bp::return_value_policy<bp::return_by_value>()),
111 "total cost data")
112 .add_property(
113 "constraints",
114 bp::make_getter(&Data::constraints,
115 bp::return_value_policy<bp::return_by_value>()),
116 "constraint data")
117 .add_property(
118 "Minv",
119 bp::make_getter(&Data::Minv, bp::return_internal_reference<>()),
120 "inverse of the joint-space inertia matrix")
121 .add_property(
122 "u_drift",
123 bp::make_getter(&Data::u_drift, bp::return_internal_reference<>()),
124 "force-bias vector that accounts for control, Coriolis and "
125 "gravitational effects");
126 }
127 };
128
129 #define CROCODDYL_ACTION_MODEL_FREE_FWDDYN_PYTHON_BINDINGS(Scalar) \
130 typedef DifferentialActionModelFreeFwdDynamicsTpl<Scalar> Model; \
131 typedef DifferentialActionModelAbstractTpl<Scalar> ModelBase; \
132 typedef typename Model::StateMultibody State; \
133 typedef typename Model::ActuationModelAbstract Actuation; \
134 typedef typename Model::CostModelSum Costs; \
135 typedef typename Model::ConstraintModelManager Constraints; \
136 bp::register_ptr_to_python<std::shared_ptr<Model>>(); \
137 bp::class_<Model, bp::bases<ModelBase>>( \
138 "DifferentialActionModelFreeFwdDynamics", \
139 "Differential action model for free forward dynamics in multibody " \
140 "systems.\n\n" \
141 "This class implements a the dynamics using Articulate Body Algorithm " \
142 "(ABA), or a custom implementation in case of system with armatures. " \
143 "If you want to include the armature, you need to use set_armature(). " \
144 "On the other hand, the stack of cost functions are implemented in " \
145 "CostModelSum().", \
146 bp::init<std::shared_ptr<State>, std::shared_ptr<Actuation>, \
147 std::shared_ptr<Costs>, \
148 bp::optional<std::shared_ptr<Constraints>>>( \
149 bp::args("self", "state", "actuation", "costs", "constraints"), \
150 "Initialize the free forward-dynamics action model.\n\n" \
151 ":param state: multibody state\n" \
152 ":param actuation: abstract actuation model\n" \
153 ":param costs: stack of cost functions\n" \
154 ":param constraints: stack of constraint functions")) \
155 .def(DifferentialActionModelFreeFwdDynamicsVisitor<Model>()) \
156 .def(CastVisitor<Model>()) \
157 .def(PrintableVisitor<Model>()) \
158 .def(CopyableVisitor<Model>());
159
160 #define CROCODDYL_ACTION_DATA_FREE_FWDDYN_PYTHON_BINDINGS(Scalar) \
161 typedef DifferentialActionDataFreeFwdDynamicsTpl<Scalar> Data; \
162 typedef DifferentialActionDataAbstractTpl<Scalar> DataBase; \
163 typedef DifferentialActionModelFreeFwdDynamicsTpl<Scalar> Model; \
164 bp::register_ptr_to_python<std::shared_ptr<Data>>(); \
165 bp::class_<Data, bp::bases<DataBase>>( \
166 "DifferentialActionDataFreeFwdDynamics", \
167 "Action data for the free forward dynamics system.", \
168 bp::init<Model*>(bp::args("self", "model"), \
169 "Create free forward-dynamics action data.\n\n" \
170 ":param model: free forward-dynamics action model")) \
171 .def(DifferentialActionDataFreeFwdDynamicsVisitor<Data>()) \
172 .def(CopyableVisitor<Data>());
173
174 void exposeDifferentialActionFreeFwdDynamics() {
175 CROCODDYL_ACTION_MODEL_FREE_FWDDYN_PYTHON_BINDINGS(float)
176 CROCODDYL_ACTION_DATA_FREE_FWDDYN_PYTHON_BINDINGS(float)
177 }
178
179 } // namespace python
180 } // namespace crocoddyl
181