GCC Code Coverage Report


Directory: ./
File: unittest/energy.cpp
Date: 2024-08-27 18:20:05
Exec Total Coverage
Lines: 0 100 0.0%
Branches: 0 688 0.0%

Line Branch Exec Source
1 //
2 // Copyright (c) 2016-2020 CNRS INRIA
3 //
4
5 #include "pinocchio/algorithm/energy.hpp"
6 #include "pinocchio/algorithm/crba.hpp"
7 #include "pinocchio/algorithm/rnea.hpp"
8 #include "pinocchio/algorithm/joint-configuration.hpp"
9 #include "pinocchio/algorithm/center-of-mass.hpp"
10
11 #include "pinocchio/multibody/sample-models.hpp"
12
13 #include <iostream>
14 #include <boost/test/unit_test.hpp>
15 #include <boost/utility/binary.hpp>
16 #include <boost/test/tools/floating_point_comparison.hpp>
17
18 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
19
20 BOOST_AUTO_TEST_CASE(test_kinetic_energy)
21 {
22 using namespace Eigen;
23 using namespace pinocchio;
24
25 Model model;
26 buildModels::humanoidRandom(model);
27 Data data(model);
28
29 const VectorXd qmax = VectorXd::Ones(model.nq);
30 VectorXd q = randomConfiguration(model, -qmax, qmax);
31 VectorXd v = VectorXd::Random(model.nv);
32
33 crba(model, data, q, Convention::WORLD);
34 data.M.triangularView<Eigen::StrictlyLower>() =
35 data.M.transpose().triangularView<Eigen::StrictlyLower>();
36
37 double kinetic_energy_ref = 0.5 * v.transpose() * data.M * v;
38 double kinetic_energy = computeKineticEnergy(model, data, q, v);
39
40 BOOST_CHECK_SMALL(kinetic_energy_ref - kinetic_energy, 1e-12);
41 }
42
43 BOOST_AUTO_TEST_CASE(test_kinetic_energy_with_armature)
44 {
45 using namespace Eigen;
46 using namespace pinocchio;
47
48 Model model;
49 buildModels::humanoidRandom(model);
50 Data data(model), data_ref(model);
51
52 model.armature = VectorXd::Random(model.nv) + VectorXd::Ones(model.nv);
53
54 const VectorXd qmax = VectorXd::Ones(model.nq);
55 VectorXd q = randomConfiguration(model, -qmax, qmax);
56 VectorXd v = VectorXd::Random(model.nv);
57
58 crba(model, data_ref, q, Convention::WORLD);
59 data_ref.M.triangularView<Eigen::StrictlyLower>() =
60 data_ref.M.transpose().triangularView<Eigen::StrictlyLower>();
61
62 double kinetic_energy_ref = 0.5 * v.transpose() * data_ref.M * v;
63 double kinetic_energy = computeKineticEnergy(model, data, q, v);
64
65 BOOST_CHECK_SMALL(
66 kinetic_energy_ref - kinetic_energy, Eigen::NumTraits<double>::dummy_precision());
67 }
68
69 BOOST_AUTO_TEST_CASE(test_potential_energy)
70 {
71 using namespace Eigen;
72 using namespace pinocchio;
73
74 Model model;
75 buildModels::humanoidRandom(model);
76 Data data(model), data_ref(model);
77
78 const VectorXd qmax = VectorXd::Ones(model.nq);
79 VectorXd q = randomConfiguration(model, -qmax, qmax);
80
81 double potential_energy = computePotentialEnergy(model, data, q);
82 centerOfMass(model, data_ref, q);
83
84 double potential_energy_ref = -data_ref.mass[0] * (data_ref.com[0].dot(model.gravity.linear()));
85
86 BOOST_CHECK_SMALL(
87 potential_energy_ref - potential_energy, Eigen::NumTraits<double>::dummy_precision());
88 }
89
90 BOOST_AUTO_TEST_CASE(test_mechanical_energy)
91 {
92 using namespace Eigen;
93 using namespace pinocchio;
94
95 Model model;
96 buildModels::humanoidRandom(model);
97 Data data(model), data_ref(model);
98
99 const VectorXd qmax = VectorXd::Ones(model.nq);
100 VectorXd q = randomConfiguration(model, -qmax, qmax);
101 VectorXd v = VectorXd::Random(model.nv);
102
103 computeKineticEnergy(model, data_ref, q, v);
104 computePotentialEnergy(model, data_ref, q);
105
106 const double mechanical_energy_ref = data_ref.kinetic_energy + data_ref.potential_energy;
107 double mechanical_energy = computeMechanicalEnergy(model, data, q, v);
108
109 BOOST_CHECK_SMALL(
110 mechanical_energy_ref - mechanical_energy, Eigen::NumTraits<double>::dummy_precision());
111 }
112
113 template<typename ConfigVectorType, typename TangentVectorType>
114 Eigen::VectorXd evalMv(
115 const pinocchio::Model & model,
116 const Eigen::MatrixBase<ConfigVectorType> & q,
117 const Eigen::MatrixBase<TangentVectorType> & v)
118 {
119 pinocchio::Data data(model);
120 pinocchio::crba(model, data, q, pinocchio::Convention::WORLD);
121 data.M.triangularView<Eigen::StrictlyLower>() =
122 data.M.transpose().triangularView<Eigen::StrictlyLower>();
123 return data.M * v;
124 }
125
126 BOOST_AUTO_TEST_CASE(test_against_rnea)
127 {
128 using namespace Eigen;
129 using namespace pinocchio;
130
131 Model model;
132 buildModels::humanoidRandom(model);
133 model.armature = VectorXd::Random(model.nv) + VectorXd::Ones(model.nv);
134 model.armature.head<6>().setZero(); // Because we do not take into account the influcent of the
135 // armature on the Coriolis terms
136 // model.gravity.setZero();
137 Data data(model), data_ref(model);
138
139 const VectorXd qmax = VectorXd::Ones(model.nq);
140 VectorXd q = randomConfiguration(model, -qmax, qmax);
141 VectorXd v = VectorXd::Random(model.nv); // v.setZero();
142 VectorXd a = VectorXd::Random(model.nv); // a.setZero();
143
144 const VectorXd tau_ref = rnea(model, data_ref, q, v, a);
145 VectorXd tau_fd = VectorXd::Zero(model.nv);
146
147 const double eps = 1e-8;
148 computeMechanicalEnergy(model, data, q, v);
149 const double mechanical_energy = data.kinetic_energy - data.potential_energy;
150 forwardKinematics(model, data, q);
151 const SE3 oM1 = data.oMi[1];
152 Data data_plus(model);
153 for (Eigen::DenseIndex k = 0; k < model.nv; ++k)
154 {
155 VectorXd q_plus = integrate(model, q, VectorXd::Unit(model.nv, k) * eps);
156 computeMechanicalEnergy(model, data_plus, q_plus, v);
157 const double mechanical_energy_plus = data_plus.kinetic_energy - data_plus.potential_energy;
158 const SE3 oM1_plus = data_plus.oMi[1];
159 const SE3 Mdiff = oM1.actInv(oM1_plus);
160 if (k < 6)
161 {
162 Force f = Force::Zero();
163 f.toVector()[k] = mechanical_energy;
164 Force f_plus = Force::Zero();
165 f_plus.toVector()[k] = mechanical_energy_plus;
166 tau_fd.head<6>() -= (Mdiff.act(f_plus) - f).toVector() / eps;
167 }
168 else
169 {
170 tau_fd[k] = -(mechanical_energy_plus - mechanical_energy) / eps;
171 }
172 }
173
174 const VectorXd Mv = evalMv(model, q, v);
175 const VectorXd q_plus = integrate(model, q, v * eps);
176 const VectorXd v_plus = v + a * eps;
177 VectorXd Mv_plus = evalMv(model, q_plus, v_plus);
178
179 forwardKinematics(model, data, q_plus);
180 const SE3 oM1_plus = data.oMi[1];
181 const SE3 Mdiff = oM1.actInv(oM1_plus);
182 Mv_plus.head<6>() =
183 Mdiff.act(Force(Mv_plus.head<6>()))
184 .toVector(); // The torque at the free flyer level is expressed in a translated frame.
185
186 tau_fd += (Mv_plus - Mv) / eps;
187 std::cout << "tau_fd: " << tau_fd.transpose() << std::endl;
188 std::cout << "tau_ref: " << tau_ref.transpose() << std::endl;
189
190 BOOST_CHECK(tau_fd.isApprox(tau_ref, sqrt(eps)));
191 }
192
193 BOOST_AUTO_TEST_SUITE_END()
194