GCC Code Coverage Report


Directory: ./
File: unittest/rnea-derivatives.cpp
Date: 2024-08-27 18:20:05
Exec Total Coverage
Lines: 0 318 0.0%
Branches: 0 2068 0.0%

Line Branch Exec Source
1 //
2 // Copyright (c) 2017-2020 CNRS INRIA
3 //
4
5 #include "pinocchio/multibody/model.hpp"
6 #include "pinocchio/multibody/data.hpp"
7 #include "pinocchio/algorithm/jacobian.hpp"
8 #include "pinocchio/algorithm/joint-configuration.hpp"
9 #include "pinocchio/algorithm/kinematics.hpp"
10 #include "pinocchio/algorithm/kinematics-derivatives.hpp"
11 #include "pinocchio/algorithm/rnea.hpp"
12 #include "pinocchio/algorithm/rnea-derivatives.hpp"
13 #include "pinocchio/algorithm/crba.hpp"
14 #include "pinocchio/multibody/sample-models.hpp"
15
16 #include <iostream>
17
18 #include <boost/test/unit_test.hpp>
19 #include <boost/utility/binary.hpp>
20
21 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
22
23 BOOST_AUTO_TEST_CASE(test_generalized_gravity_derivatives)
24 {
25 using namespace Eigen;
26 using namespace pinocchio;
27
28 Model model;
29 buildModels::humanoidRandom(model);
30
31 Data data(model), data_fd(model);
32
33 model.lowerPositionLimit.head<3>().fill(-1.);
34 model.upperPositionLimit.head<3>().fill(1.);
35 VectorXd q = randomConfiguration(model);
36 VectorXd v(VectorXd::Zero(model.nv));
37 VectorXd a(VectorXd::Zero(model.nv));
38
39 // Check againt non-derivative algo
40 MatrixXd g_partial_dq(model.nv, model.nv);
41 g_partial_dq.setZero();
42 computeGeneralizedGravityDerivatives(model, data, q, g_partial_dq);
43
44 VectorXd g0 = computeGeneralizedGravity(model, data_fd, q);
45 BOOST_CHECK(data.g.isApprox(g0));
46
47 MatrixXd g_partial_dq_fd(model.nv, model.nv);
48 g_partial_dq_fd.setZero();
49
50 VectorXd v_eps(Eigen::VectorXd::Zero(model.nv));
51 VectorXd q_plus(model.nq);
52 VectorXd g_plus(model.nv);
53 const double alpha = 1e-8;
54 for (int k = 0; k < model.nv; ++k)
55 {
56 v_eps[k] += alpha;
57 q_plus = integrate(model, q, v_eps);
58 g_plus = computeGeneralizedGravity(model, data_fd, q_plus);
59
60 g_partial_dq_fd.col(k) = (g_plus - g0) / alpha;
61 v_eps[k] -= alpha;
62 }
63
64 BOOST_CHECK(g_partial_dq.isApprox(g_partial_dq_fd, sqrt(alpha)));
65 }
66
67 BOOST_AUTO_TEST_CASE(test_generalized_gravity_derivatives_fext)
68 {
69 using namespace Eigen;
70 using namespace pinocchio;
71
72 Model model;
73 buildModels::humanoidRandom(model);
74
75 Data data(model), data_fd(model);
76
77 model.lowerPositionLimit.head<3>().fill(-1.);
78 model.upperPositionLimit.head<3>().fill(1.);
79 VectorXd q = randomConfiguration(model);
80
81 typedef PINOCCHIO_ALIGNED_STD_VECTOR(Force) ForceVector;
82 ForceVector fext((size_t)model.njoints);
83 for (ForceVector::iterator it = fext.begin(); it != fext.end(); ++it)
84 (*it).setRandom();
85
86 // Check againt non-derivative algo
87 MatrixXd static_vec_partial_dq(model.nv, model.nv);
88 static_vec_partial_dq.setZero();
89 computeStaticTorqueDerivatives(model, data, q, fext, static_vec_partial_dq);
90
91 VectorXd tau0 = computeStaticTorque(model, data_fd, q, fext);
92 BOOST_CHECK(data.tau.isApprox(tau0));
93
94 MatrixXd static_vec_partial_dq_fd(model.nv, model.nv);
95
96 VectorXd v_eps(Eigen::VectorXd::Zero(model.nv));
97 VectorXd q_plus(model.nq);
98 VectorXd tau_plus(model.nv);
99 const double alpha = 1e-8;
100 for (int k = 0; k < model.nv; ++k)
101 {
102 v_eps[k] += alpha;
103 q_plus = integrate(model, q, v_eps);
104 tau_plus = computeStaticTorque(model, data_fd, q_plus, fext);
105
106 static_vec_partial_dq_fd.col(k) = (tau_plus - tau0) / alpha;
107 v_eps[k] = 0.;
108 }
109
110 BOOST_CHECK(static_vec_partial_dq.isApprox(static_vec_partial_dq_fd, sqrt(alpha)));
111 }
112
113 BOOST_AUTO_TEST_CASE(test_rnea_derivatives)
114 {
115 using namespace Eigen;
116 using namespace pinocchio;
117
118 Model model;
119 buildModels::humanoidRandom(model);
120 model.armature = VectorXd::Random(model.nv) + VectorXd::Ones(model.nv);
121
122 Data data(model), data_fd(model), data_ref(model);
123
124 model.lowerPositionLimit.head<3>().fill(-1.);
125 model.upperPositionLimit.head<3>().fill(1.);
126 VectorXd q = randomConfiguration(model);
127 VectorXd v(VectorXd::Random(model.nv));
128 VectorXd a(VectorXd::Random(model.nv));
129
130 /// Check againt computeGeneralizedGravityDerivatives
131 MatrixXd rnea_partial_dq(model.nv, model.nv);
132 rnea_partial_dq.setZero();
133 MatrixXd rnea_partial_dv(model.nv, model.nv);
134 rnea_partial_dv.setZero();
135 MatrixXd rnea_partial_da(model.nv, model.nv);
136 rnea_partial_da.setZero();
137 computeRNEADerivatives(
138 model, data, q, VectorXd::Zero(model.nv), VectorXd::Zero(model.nv), rnea_partial_dq,
139 rnea_partial_dv, rnea_partial_da);
140 rnea(model, data_ref, q, VectorXd::Zero(model.nv), VectorXd::Zero(model.nv));
141 for (Model::JointIndex k = 1; k < (Model::JointIndex)model.njoints; ++k)
142 {
143 BOOST_CHECK(data.of[k].isApprox(data.oMi[k].act(data_ref.f[k])));
144 }
145
146 MatrixXd g_partial_dq(model.nv, model.nv);
147 g_partial_dq.setZero();
148 computeGeneralizedGravityDerivatives(model, data_ref, q, g_partial_dq);
149
150 BOOST_CHECK(data.dFdq.isApprox(data_ref.dFdq));
151 BOOST_CHECK(rnea_partial_dq.isApprox(g_partial_dq));
152 BOOST_CHECK(data.tau.isApprox(data_ref.g));
153
154 VectorXd tau0 = rnea(model, data_fd, q, VectorXd::Zero(model.nv), VectorXd::Zero(model.nv));
155 MatrixXd rnea_partial_dq_fd(model.nv, model.nv);
156 rnea_partial_dq_fd.setZero();
157
158 VectorXd v_eps(VectorXd::Zero(model.nv));
159 VectorXd q_plus(model.nq);
160 VectorXd tau_plus(model.nv);
161 const double alpha = 1e-8;
162 for (int k = 0; k < model.nv; ++k)
163 {
164 v_eps[k] += alpha;
165 q_plus = integrate(model, q, v_eps);
166 tau_plus = rnea(model, data_fd, q_plus, VectorXd::Zero(model.nv), VectorXd::Zero(model.nv));
167
168 rnea_partial_dq_fd.col(k) = (tau_plus - tau0) / alpha;
169 v_eps[k] -= alpha;
170 }
171 BOOST_CHECK(rnea_partial_dq.isApprox(rnea_partial_dq_fd, sqrt(alpha)));
172
173 // Check with q and a non zero
174 tau0 = rnea(model, data_fd, q, 0 * v, a);
175 rnea_partial_dq_fd.setZero();
176
177 for (int k = 0; k < model.nv; ++k)
178 {
179 v_eps[k] += alpha;
180 q_plus = integrate(model, q, v_eps);
181 tau_plus = rnea(model, data_fd, q_plus, VectorXd::Zero(model.nv), a);
182
183 rnea_partial_dq_fd.col(k) = (tau_plus - tau0) / alpha;
184 v_eps[k] -= alpha;
185 }
186
187 rnea_partial_dq.setZero();
188 computeRNEADerivatives(
189 model, data, q, VectorXd::Zero(model.nv), a, rnea_partial_dq, rnea_partial_dv, rnea_partial_da);
190 forwardKinematics(model, data_ref, q, VectorXd::Zero(model.nv), a);
191
192 for (Model::JointIndex k = 1; k < (Model::JointIndex)model.njoints; ++k)
193 {
194 BOOST_CHECK(data.a[k].isApprox(data_ref.a[k]));
195 BOOST_CHECK(data.v[k].isApprox(data_ref.v[k]));
196 BOOST_CHECK(data.oMi[k].isApprox(data_ref.oMi[k]));
197 BOOST_CHECK(data.oh[k].isApprox(Force::Zero()));
198 }
199
200 BOOST_CHECK(data.tau.isApprox(tau0));
201 BOOST_CHECK(rnea_partial_dq.isApprox(rnea_partial_dq_fd, sqrt(alpha)));
202
203 // Check with q and v non zero
204 const Motion gravity(model.gravity);
205 model.gravity.setZero();
206 tau0 = rnea(model, data_fd, q, v, VectorXd::Zero(model.nv));
207 rnea_partial_dq_fd.setZero();
208
209 for (int k = 0; k < model.nv; ++k)
210 {
211 v_eps[k] += alpha;
212 q_plus = integrate(model, q, v_eps);
213 tau_plus = rnea(model, data_fd, q_plus, v, VectorXd::Zero(model.nv));
214
215 rnea_partial_dq_fd.col(k) = (tau_plus - tau0) / alpha;
216 v_eps[k] -= alpha;
217 }
218
219 VectorXd v_plus(v);
220 MatrixXd rnea_partial_dv_fd(model.nv, model.nv);
221 rnea_partial_dv_fd.setZero();
222
223 for (int k = 0; k < model.nv; ++k)
224 {
225 v_plus[k] += alpha;
226 tau_plus = rnea(model, data_fd, q, v_plus, VectorXd::Zero(model.nv));
227
228 rnea_partial_dv_fd.col(k) = (tau_plus - tau0) / alpha;
229 v_plus[k] -= alpha;
230 }
231
232 rnea_partial_dq.setZero();
233 rnea_partial_dv.setZero();
234 computeRNEADerivatives(
235 model, data, q, v, VectorXd::Zero(model.nv), rnea_partial_dq, rnea_partial_dv, rnea_partial_da);
236 forwardKinematics(model, data_ref, q, v, VectorXd::Zero(model.nv));
237
238 for (Model::JointIndex k = 1; k < (Model::JointIndex)model.njoints; ++k)
239 {
240 BOOST_CHECK(data.a[k].isApprox(data_ref.a[k]));
241 BOOST_CHECK(data.v[k].isApprox(data_ref.v[k]));
242 BOOST_CHECK(data.oMi[k].isApprox(data_ref.oMi[k]));
243 }
244
245 BOOST_CHECK(data.tau.isApprox(tau0));
246 BOOST_CHECK(rnea_partial_dq.isApprox(rnea_partial_dq_fd, sqrt(alpha)));
247 BOOST_CHECK(rnea_partial_dv.isApprox(rnea_partial_dv_fd, sqrt(alpha)));
248
249 // std::cout << "rnea_partial_dv:\n" << rnea_partial_dv.block<10,10>(0,0) << std::endl;
250 // std::cout << "rnea_partial_dv ref:\n" << rnea_partial_dv_fd.block<10,10>(0,0) << std::endl;
251 // std::cout << "rnea_partial_dv:\n" << rnea_partial_dv.topRows<10>() << std::endl;
252 // std::cout << "rnea_partial_dv ref:\n" << rnea_partial_dv_fd.topRows<10>() << std::endl;
253 // Check with q, v and a non zero
254 model.gravity = gravity;
255 v_plus = v;
256 tau0 = rnea(model, data_fd, q, v, a);
257 rnea_partial_dq_fd.setZero();
258
259 for (int k = 0; k < model.nv; ++k)
260 {
261 v_eps[k] += alpha;
262 q_plus = integrate(model, q, v_eps);
263 tau_plus = rnea(model, data_fd, q_plus, v, a);
264
265 rnea_partial_dq_fd.col(k) = (tau_plus - tau0) / alpha;
266 v_eps[k] -= alpha;
267 }
268
269 rnea_partial_dv_fd.setZero();
270 for (int k = 0; k < model.nv; ++k)
271 {
272 v_plus[k] += alpha;
273 tau_plus = rnea(model, data_fd, q, v_plus, a);
274
275 rnea_partial_dv_fd.col(k) = (tau_plus - tau0) / alpha;
276 v_plus[k] -= alpha;
277 }
278
279 rnea_partial_dq.setZero();
280 rnea_partial_dv.setZero();
281 computeRNEADerivatives(model, data, q, v, a, rnea_partial_dq, rnea_partial_dv, rnea_partial_da);
282 forwardKinematics(model, data_ref, q, v, a);
283
284 for (Model::JointIndex k = 1; k < (Model::JointIndex)model.njoints; ++k)
285 {
286 BOOST_CHECK(data.a[k].isApprox(data_ref.a[k]));
287 BOOST_CHECK(data.v[k].isApprox(data_ref.v[k]));
288 BOOST_CHECK(data.oMi[k].isApprox(data_ref.oMi[k]));
289 }
290
291 computeJointJacobiansTimeVariation(model, data_ref, q, v);
292 BOOST_CHECK(data.dJ.isApprox(data_ref.dJ));
293 crba(model, data_ref, q, Convention::WORLD);
294 data_ref.M.triangularView<Eigen::StrictlyLower>() =
295 data_ref.M.transpose().triangularView<Eigen::StrictlyLower>();
296
297 rnea_partial_da.triangularView<Eigen::StrictlyLower>() =
298 rnea_partial_da.transpose().triangularView<Eigen::StrictlyLower>();
299 BOOST_CHECK(rnea_partial_da.isApprox(data_ref.M));
300
301 BOOST_CHECK(data.tau.isApprox(tau0));
302 BOOST_CHECK(rnea_partial_dq.isApprox(rnea_partial_dq_fd, sqrt(alpha)));
303 BOOST_CHECK(rnea_partial_dv.isApprox(rnea_partial_dv_fd, sqrt(alpha)));
304
305 Data data2(model);
306 computeRNEADerivatives(model, data2, q, v, a);
307 data2.M.triangularView<Eigen::StrictlyLower>() =
308 data2.M.transpose().triangularView<Eigen::StrictlyLower>();
309
310 BOOST_CHECK(rnea_partial_dq.isApprox(data2.dtau_dq));
311 BOOST_CHECK(rnea_partial_dv.isApprox(data2.dtau_dv));
312 BOOST_CHECK(rnea_partial_da.isApprox(data2.M));
313 }
314
315 BOOST_AUTO_TEST_CASE(test_rnea_derivatives_fext)
316 {
317 using namespace Eigen;
318 using namespace pinocchio;
319
320 Model model;
321 buildModels::humanoidRandom(model);
322 typedef Model::Force Force;
323
324 Data data(model), data_fd(model), data_ref(model);
325
326 model.lowerPositionLimit.head<3>().fill(-1.);
327 model.upperPositionLimit.head<3>().fill(1.);
328 VectorXd q = randomConfiguration(model);
329 VectorXd v(VectorXd::Random(model.nv));
330 VectorXd a(VectorXd::Random(model.nv));
331
332 typedef PINOCCHIO_ALIGNED_STD_VECTOR(Force) ForceVector;
333 ForceVector fext((size_t)model.njoints);
334 for (ForceVector::iterator it = fext.begin(); it != fext.end(); ++it)
335 (*it).setRandom();
336
337 /// Check againt computeGeneralizedGravityDerivatives
338 MatrixXd rnea_partial_dq(model.nv, model.nv);
339 rnea_partial_dq.setZero();
340 MatrixXd rnea_partial_dv(model.nv, model.nv);
341 rnea_partial_dv.setZero();
342 MatrixXd rnea_partial_da(model.nv, model.nv);
343 rnea_partial_da.setZero();
344
345 computeRNEADerivatives(
346 model, data, q, v, a, fext, rnea_partial_dq, rnea_partial_dv, rnea_partial_da);
347 rnea(model, data_ref, q, v, a, fext);
348
349 BOOST_CHECK(data.tau.isApprox(data_ref.tau));
350
351 computeRNEADerivatives(model, data_ref, q, v, a);
352 BOOST_CHECK(rnea_partial_dv.isApprox(data_ref.dtau_dv));
353 BOOST_CHECK(rnea_partial_da.isApprox(data_ref.M));
354
355 MatrixXd rnea_partial_dq_fd(model.nv, model.nv);
356 rnea_partial_dq_fd.setZero();
357 MatrixXd rnea_partial_dv_fd(model.nv, model.nv);
358 rnea_partial_dv_fd.setZero();
359 MatrixXd rnea_partial_da_fd(model.nv, model.nv);
360 rnea_partial_da_fd.setZero();
361
362 VectorXd v_eps(VectorXd::Zero(model.nv));
363 VectorXd q_plus(model.nq);
364 VectorXd tau_plus(model.nv);
365 const double eps = 1e-8;
366
367 const VectorXd tau_ref = rnea(model, data_ref, q, v, a, fext);
368 for (int k = 0; k < model.nv; ++k)
369 {
370 v_eps[k] = eps;
371 q_plus = integrate(model, q, v_eps);
372 tau_plus = rnea(model, data_fd, q_plus, v, a, fext);
373
374 rnea_partial_dq_fd.col(k) = (tau_plus - tau_ref) / eps;
375
376 v_eps[k] = 0.;
377 }
378 BOOST_CHECK(rnea_partial_dq.isApprox(rnea_partial_dq_fd, sqrt(eps)));
379
380 VectorXd v_plus(v);
381 for (int k = 0; k < model.nv; ++k)
382 {
383 v_plus[k] += eps;
384
385 tau_plus = rnea(model, data_fd, q, v_plus, a, fext);
386
387 rnea_partial_dv_fd.col(k) = (tau_plus - tau_ref) / eps;
388
389 v_plus[k] -= eps;
390 }
391 BOOST_CHECK(rnea_partial_dv.isApprox(rnea_partial_dv_fd, sqrt(eps)));
392
393 VectorXd a_plus(a);
394 for (int k = 0; k < model.nv; ++k)
395 {
396 a_plus[k] += eps;
397
398 tau_plus = rnea(model, data_fd, q, v, a_plus, fext);
399
400 rnea_partial_da_fd.col(k) = (tau_plus - tau_ref) / eps;
401
402 a_plus[k] -= eps;
403 }
404
405 rnea_partial_da.triangularView<Eigen::Lower>() =
406 rnea_partial_da.transpose().triangularView<Eigen::Lower>();
407 BOOST_CHECK(rnea_partial_da.isApprox(rnea_partial_da_fd, sqrt(eps)));
408
409 // test the shortcut
410 Data data_shortcut(model);
411 computeRNEADerivatives(model, data_shortcut, q, v, a, fext);
412 BOOST_CHECK(data_shortcut.dtau_dq.isApprox(rnea_partial_dq));
413 BOOST_CHECK(data_shortcut.dtau_dv.isApprox(rnea_partial_dv));
414 data_shortcut.M.triangularView<Eigen::Lower>() =
415 data_shortcut.M.transpose().triangularView<Eigen::Lower>();
416 BOOST_CHECK(data_shortcut.M.isApprox(rnea_partial_da));
417 }
418
419 BOOST_AUTO_TEST_CASE(test_rnea_derivatives_vs_kinematics_derivatives)
420 {
421 using namespace Eigen;
422 using namespace pinocchio;
423
424 Model model;
425 buildModels::humanoidRandom(model);
426
427 Data data(model), data_ref(model);
428
429 model.lowerPositionLimit.head<3>().fill(-1.);
430 model.upperPositionLimit.head<3>().fill(1.);
431 VectorXd q = randomConfiguration(model);
432 VectorXd v(VectorXd::Random(model.nv));
433 VectorXd a(VectorXd::Random(model.nv));
434
435 /// Check againt computeGeneralizedGravityDerivatives
436 MatrixXd rnea_partial_dq(model.nv, model.nv);
437 rnea_partial_dq.setZero();
438 MatrixXd rnea_partial_dv(model.nv, model.nv);
439 rnea_partial_dv.setZero();
440 MatrixXd rnea_partial_da(model.nv, model.nv);
441 rnea_partial_da.setZero();
442
443 computeRNEADerivatives(model, data, q, v, a, rnea_partial_dq, rnea_partial_dv, rnea_partial_da);
444 computeForwardKinematicsDerivatives(model, data_ref, q, v, a);
445
446 BOOST_CHECK(data.J.isApprox(data_ref.J));
447 BOOST_CHECK(data.dJ.isApprox(data_ref.dJ));
448
449 for (size_t k = 1; k < (size_t)model.njoints; ++k)
450 {
451 BOOST_CHECK(data.oMi[k].isApprox(data_ref.oMi[k]));
452 BOOST_CHECK(data.ov[k].isApprox(data_ref.ov[k]));
453 BOOST_CHECK(data.oa[k].isApprox(data_ref.oa[k]));
454 }
455 }
456
457 BOOST_AUTO_TEST_CASE(test_multiple_calls)
458 {
459 using namespace Eigen;
460 using namespace pinocchio;
461
462 Model model;
463 buildModels::humanoidRandom(model);
464
465 Data data1(model), data2(model);
466
467 model.lowerPositionLimit.head<3>().fill(-1.);
468 model.upperPositionLimit.head<3>().fill(1.);
469 VectorXd q = randomConfiguration(model);
470 VectorXd v(VectorXd::Random(model.nv));
471 VectorXd a(VectorXd::Random(model.nv));
472
473 computeRNEADerivatives(model, data1, q, v, a);
474 data2 = data1;
475
476 for (int k = 0; k < 20; ++k)
477 {
478 computeRNEADerivatives(model, data1, q, v, a);
479 }
480
481 BOOST_CHECK(data1.J.isApprox(data2.J));
482 BOOST_CHECK(data1.dJ.isApprox(data2.dJ));
483 BOOST_CHECK(data1.dVdq.isApprox(data2.dVdq));
484 BOOST_CHECK(data1.dAdq.isApprox(data2.dAdq));
485 BOOST_CHECK(data1.dAdv.isApprox(data2.dAdv));
486
487 BOOST_CHECK(data1.dFdq.isApprox(data2.dFdq));
488 BOOST_CHECK(data1.dFdv.isApprox(data2.dFdv));
489 BOOST_CHECK(data1.dFda.isApprox(data2.dFda));
490
491 BOOST_CHECK(data1.dtau_dq.isApprox(data2.dtau_dq));
492 BOOST_CHECK(data1.dtau_dv.isApprox(data2.dtau_dv));
493 BOOST_CHECK(data1.M.isApprox(data2.M));
494 }
495
496 BOOST_AUTO_TEST_CASE(test_get_coriolis)
497 {
498 using namespace Eigen;
499 using namespace pinocchio;
500
501 Model model;
502 buildModels::humanoidRandom(model);
503
504 model.lowerPositionLimit.head<3>().fill(-1.);
505 model.upperPositionLimit.head<3>().fill(1.);
506
507 Data data_ref(model);
508 Data data(model);
509
510 VectorXd q = randomConfiguration(model);
511 VectorXd v = VectorXd::Random(model.nv);
512 VectorXd tau = VectorXd::Random(model.nv);
513
514 computeCoriolisMatrix(model, data_ref, q, v);
515
516 computeRNEADerivatives(model, data, q, v, tau);
517 getCoriolisMatrix(model, data);
518
519 BOOST_CHECK(data.J.isApprox(data_ref.J));
520 BOOST_CHECK(data.dJ.isApprox(data_ref.dJ));
521 BOOST_CHECK(data.Ag.isApprox(data_ref.Ag));
522 for (JointIndex k = 1; k < model.joints.size(); ++k)
523 {
524 BOOST_CHECK(data.B[k].isApprox(data_ref.B[k]));
525 BOOST_CHECK(data.oYcrb[k].isApprox(data_ref.oYcrb[k]));
526 }
527
528 BOOST_CHECK(data.C.isApprox(data_ref.C));
529 }
530
531 BOOST_AUTO_TEST_SUITE_END()
532