GCC Code Coverage Report


Directory: ./
File: bindings/python/crocoddyl/multibody/actions/impulse-fwddyn.cpp
Date: 2025-02-24 23:41:29
Exec Total Coverage
Lines: 63 64 98.4%
Branches: 48 96 50.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-2023, LAAS-CNRS, University of Edinburgh,
5 // University of Oxford, Heriot-Watt University
6 // Copyright note valid unless otherwise stated in individual files.
7 // All rights reserved.
8 ///////////////////////////////////////////////////////////////////////////////
9
10 #include "crocoddyl/multibody/actions/impulse-fwddyn.hpp"
11
12 #include "python/crocoddyl/core/action-base.hpp"
13 #include "python/crocoddyl/multibody/multibody.hpp"
14 #include "python/crocoddyl/utils/copyable.hpp"
15
16 namespace crocoddyl {
17 namespace python {
18
19 10 void exposeActionImpulseFwdDynamics() {
20 10 bp::register_ptr_to_python<std::shared_ptr<ActionModelImpulseFwdDynamics> >();
21
22
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::class_<ActionModelImpulseFwdDynamics, bp::bases<ActionModelAbstract> >(
23 "ActionModelImpulseFwdDynamics",
24 "Action model for impulse forward dynamics in multibody systems.\n\n"
25 "The impulse is modelled as holonomic constraits in the contact frame. "
26 "There\n"
27 "is also a custom implementation in case of system with armatures. If "
28 "you want to\n"
29 "include the armature, you need to use set_armature(). On the other "
30 "hand, the\n"
31 "stack of cost functions are implemented in CostModelSum().",
32
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::init<std::shared_ptr<StateMultibody>,
33 std::shared_ptr<ImpulseModelMultiple>,
34 std::shared_ptr<CostModelSum>,
35 bp::optional<double, double, bool> >(
36 20 bp::args("self", "state", " impulses", "costs", "r_coeff",
37 "inv_damping", "enable_force"),
38 "Initialize the impulse forward-dynamics action model.\n\n"
39 "The damping factor is needed when the contact Jacobian is not "
40 "full-rank. Otherwise,\n"
41 "a good damping factor could be 1e-12. In addition, if you have cost "
42 "based on forces,\n"
43 "you need to enable the computation of the force Jacobians (i.e. "
44 "enable_force=True)."
45 ":param state: multibody state\n"
46 ":param impulses: multiple impulse model\n"
47 ":param costs: stack of cost functions\n"
48 ":param r_coeff: restitution coefficient (default 0.)\n"
49 ":param inv_damping: Damping factor for cholesky decomposition of "
50 "JMinvJt (default 0.)\n"
51 ":param enable_force: Enable the computation of force Jacobians "
52 "(default False)"))
53
2/4
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
10 .def(bp::init<std::shared_ptr<StateMultibody>,
54 std::shared_ptr<ImpulseModelMultiple>,
55 std::shared_ptr<CostModelSum>,
56 std::shared_ptr<ConstraintModelManager>,
57 bp::optional<double, double, bool> >(
58
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::args("self", "state", "impulses", "costs", "constraints",
59 "r_coeff", "inv_damping", "enable_force"),
60 "Initialize the constrained forward-dynamics action model.\n\n"
61 "The damping factor is needed when the contact Jacobian is not "
62 "full-rank. Otherwise,\n"
63 "a good damping factor could be 1e-12. In addition, if you have cost "
64 "based on forces,\n"
65 "you need to enable the computation of the force Jacobians (i.e. "
66 "enable_force=True)."
67 ":param state: multibody state\n"
68 ":param impulses: multiple impulse model\n"
69 ":param costs: stack of cost functions\n"
70 ":param constraints: stack of constraint functions\n"
71 ":param r_coeff: restitution coefficient (default 0.)\n"
72 ":param inv_damping: Damping factor for cholesky decomposition of "
73 "JMinvJt (default 0.)\n"
74 ":param enable_force: Enable the computation of force Jacobians "
75 "(default False)"))
76 .def<void (ActionModelImpulseFwdDynamics::*)(
77 const std::shared_ptr<ActionDataAbstract>&,
78 const Eigen::Ref<const Eigen::VectorXd>&,
79 20 const Eigen::Ref<const Eigen::VectorXd>&)>(
80 "calc", &ActionModelImpulseFwdDynamics::calc,
81
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::args("self", "data", "x", "u"),
82 "Compute the next state and cost value.\n\n"
83 "It describes the time-continuous evolution of the multibody system "
84 "with impulse. The\n"
85 "impulses are modelled as holonomic constraints.\n"
86 "Additionally it computes the cost value associated to this state "
87 "and control pair.\n"
88 ":param data: impulse forward-dynamics action data\n"
89 ":param x: time-continuous state vector\n"
90 ":param u: time-continuous control input")
91 .def<void (ActionModelImpulseFwdDynamics::*)(
92 const std::shared_ptr<ActionDataAbstract>&,
93
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 const Eigen::Ref<const Eigen::VectorXd>&)>(
94
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 "calc", &ActionModelAbstract::calc, bp::args("self", "data", "x"))
95 .def<void (ActionModelImpulseFwdDynamics::*)(
96 const std::shared_ptr<ActionDataAbstract>&,
97 const Eigen::Ref<const Eigen::VectorXd>&,
98
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 const Eigen::Ref<const Eigen::VectorXd>&)>(
99 "calcDiff", &ActionModelImpulseFwdDynamics::calcDiff,
100
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::args("self", "data", "x", "u"),
101 "Compute the derivatives of the differential multibody system and "
102 "its cost\n"
103 "functions.\n\n"
104 "It computes the partial derivatives of the differential multibody "
105 "system and the\n"
106 "cost function. It assumes that calc has been run first.\n"
107 "This function builds a quadratic approximation of the\n"
108 "action model (i.e. dynamical system and cost function).\n"
109 ":param data: impulse forward-dynamics action data\n"
110 ":param x: time-continuous state vector\n"
111 ":param u: time-continuous control input\n"
112 "")
113 .def<void (ActionModelImpulseFwdDynamics::*)(
114 const std::shared_ptr<ActionDataAbstract>&,
115
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 const Eigen::Ref<const Eigen::VectorXd>&)>(
116 "calcDiff", &ActionModelAbstract::calcDiff,
117
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::args("self", "data", "x"))
118
2/4
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
20 .def("createData", &ActionModelImpulseFwdDynamics::createData,
119
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::args("self"),
120 "Create the impulse forward dynamics differential action data.")
121
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property(
122 "pinocchio",
123
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_function(&ActionModelImpulseFwdDynamics::get_pinocchio,
124 10 bp::return_internal_reference<>()),
125 "multibody model (i.e. pinocchio model)")
126
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property(
127 "impulses",
128
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_function(&ActionModelImpulseFwdDynamics::get_impulses,
129 10 bp::return_value_policy<bp::return_by_value>()),
130 "multiple contact model")
131
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property(
132 "costs",
133
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_function(&ActionModelImpulseFwdDynamics::get_costs,
134 10 bp::return_value_policy<bp::return_by_value>()),
135 "total cost model")
136
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property(
137 "constraints",
138
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_function(&ActionModelImpulseFwdDynamics::get_constraints,
139 10 bp::return_value_policy<bp::return_by_value>()),
140 "constraint model manager")
141
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property(
142 "armature",
143
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_function(&ActionModelImpulseFwdDynamics::get_armature,
144 bp::return_internal_reference<>()),
145
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::make_function(&ActionModelImpulseFwdDynamics::set_armature),
146 "set an armature mechanism in the joints")
147
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property(
148 "r_coeff",
149
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_function(
150 &ActionModelImpulseFwdDynamics::get_restitution_coefficient),
151
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::make_function(
152 &ActionModelImpulseFwdDynamics::set_restitution_coefficient),
153 "Restitution coefficient that describes elastic impacts")
154
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property(
155 "JMinvJt_damping",
156
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_function(&ActionModelImpulseFwdDynamics::get_damping_factor),
157
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::make_function(&ActionModelImpulseFwdDynamics::set_damping_factor),
158 "Damping factor for cholesky decomposition of JMinvJt")
159
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .def(CopyableVisitor<ActionModelImpulseFwdDynamics>());
160
161 10 bp::register_ptr_to_python<std::shared_ptr<ActionDataImpulseFwdDynamics> >();
162
163
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::class_<ActionDataImpulseFwdDynamics, bp::bases<ActionDataAbstract> >(
164 "ActionDataImpulseFwdDynamics",
165 "Action data for the impulse forward dynamics system.",
166
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::init<ActionModelImpulseFwdDynamics*>(
167 20 bp::args("self", "model"),
168 "Create impulse forward-dynamics action data.\n\n"
169 ":param model: impulse forward-dynamics action model"))
170
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property("pinocchio",
171
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_getter(&ActionDataImpulseFwdDynamics::pinocchio,
172 10 bp::return_internal_reference<>()),
173 "pinocchio data")
174
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property("multibody",
175
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_getter(&ActionDataImpulseFwdDynamics::multibody,
176 10 bp::return_internal_reference<>()),
177 "multibody data")
178
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property(
179 "costs",
180
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_getter(&ActionDataImpulseFwdDynamics::costs,
181 10 bp::return_value_policy<bp::return_by_value>()),
182 "total cost data")
183
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property(
184 "constraints",
185
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_getter(&ActionDataImpulseFwdDynamics::constraints,
186 10 bp::return_value_policy<bp::return_by_value>()),
187 "constraint data")
188
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property("Kinv",
189
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_getter(&ActionDataImpulseFwdDynamics::Kinv,
190 10 bp::return_internal_reference<>()),
191 "inverse of the KKT matrix")
192
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property("df_dx",
193
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_getter(&ActionDataImpulseFwdDynamics::df_dx,
194 10 bp::return_internal_reference<>()),
195 "Jacobian of the contact impulse")
196
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .def(CopyableVisitor<ActionDataImpulseFwdDynamics>());
197 10 }
198
199 } // namespace python
200 } // namespace crocoddyl
201