| Directory: | ./ |
|---|---|
| File: | unittest/compute-all-terms.cpp |
| Date: | 2025-02-12 21:03:38 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 50 | 50 | 100.0% |
| Branches: | 175 | 348 | 50.3% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | // | ||
| 2 | // Copyright (c) 2015-2021 CNRS INRIA | ||
| 3 | // | ||
| 4 | |||
| 5 | #include "pinocchio/spatial/fwd.hpp" | ||
| 6 | #include "pinocchio/spatial/se3.hpp" | ||
| 7 | #include "pinocchio/multibody/visitor.hpp" | ||
| 8 | #include "pinocchio/multibody/model.hpp" | ||
| 9 | #include "pinocchio/multibody/data.hpp" | ||
| 10 | #include "pinocchio/algorithm/crba.hpp" | ||
| 11 | #include "pinocchio/algorithm/centroidal.hpp" | ||
| 12 | #include "pinocchio/algorithm/rnea.hpp" | ||
| 13 | #include "pinocchio/algorithm/jacobian.hpp" | ||
| 14 | #include "pinocchio/algorithm/compute-all-terms.hpp" | ||
| 15 | #include "pinocchio/multibody/sample-models.hpp" | ||
| 16 | #include "pinocchio/utils/timer.hpp" | ||
| 17 | |||
| 18 | #include <boost/test/unit_test.hpp> | ||
| 19 | |||
| 20 | using namespace pinocchio; | ||
| 21 | |||
| 22 | BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) | ||
| 23 | |||
| 24 | 4 | void run_test(const Model & model, const Eigen::VectorXd & q, const Eigen::VectorXd & v) | |
| 25 | { | ||
| 26 |
1/2✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
|
4 | pinocchio::Data data(model); |
| 27 |
1/2✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
|
4 | pinocchio::Data data_other(model); |
| 28 | |||
| 29 |
1/2✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
|
4 | computeAllTerms(model, data, q, v); |
| 30 | |||
| 31 |
1/2✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
|
4 | nonLinearEffects(model, data_other, q, v); |
| 32 |
1/2✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
|
4 | crba(model, data_other, q, Convention::WORLD); |
| 33 |
1/2✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
|
4 | getJacobianComFromCrba(model, data_other); |
| 34 |
1/2✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
|
4 | computeJointJacobiansTimeVariation(model, data_other, q, v); |
| 35 |
1/2✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
|
4 | centerOfMass(model, data_other, q, v, true); |
| 36 |
1/2✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
|
4 | computeKineticEnergy(model, data_other, q, v); |
| 37 |
1/2✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
|
4 | computePotentialEnergy(model, data_other, q); |
| 38 |
1/2✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
|
4 | dccrba(model, data_other, q, v); |
| 39 |
1/2✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
|
4 | computeGeneralizedGravity(model, data_other, q); |
| 40 | |||
| 41 |
7/14✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 4 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 4 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 4 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 4 times.
|
4 | BOOST_CHECK(data.nle.isApprox(data_other.nle)); |
| 42 |
11/22✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 4 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 4 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 4 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 4 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 4 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 4 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 4 times.
✗ Branch 34 not taken.
✗ Branch 40 not taken.
✓ Branch 41 taken 4 times.
|
4 | BOOST_CHECK(Eigen::MatrixXd(data.M.triangularView<Eigen::Upper>()) |
| 43 | .isApprox(Eigen::MatrixXd(data_other.M.triangularView<Eigen::Upper>()))); | ||
| 44 |
7/14✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 4 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 4 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 4 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 4 times.
|
4 | BOOST_CHECK(data.J.isApprox(data_other.J)); |
| 45 |
7/14✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 4 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 4 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 4 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 4 times.
|
4 | BOOST_CHECK(data.dJ.isApprox(data_other.dJ)); |
| 46 |
7/14✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 4 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 4 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 4 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 4 times.
|
4 | BOOST_CHECK(data.Jcom.isApprox(data_other.Jcom)); |
| 47 |
7/14✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 4 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 4 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 4 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 4 times.
|
4 | BOOST_CHECK(data.Ag.isApprox(data_other.Ag)); |
| 48 |
7/14✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 4 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 4 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 4 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 4 times.
|
4 | BOOST_CHECK(data.dAg.isApprox(data_other.dAg)); |
| 49 |
7/14✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 4 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 4 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 4 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 4 times.
|
4 | BOOST_CHECK(data.hg.isApprox(data_other.hg)); |
| 50 |
7/14✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 4 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 4 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 4 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 4 times.
|
4 | BOOST_CHECK(data.Ig.isApprox(data_other.Ig)); |
| 51 |
7/14✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 4 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 4 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 4 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 4 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 4 times.
|
4 | BOOST_CHECK(data.g.isApprox(data_other.g)); |
| 52 | |||
| 53 |
2/2✓ Branch 0 taken 112 times.
✓ Branch 1 taken 4 times.
|
116 | for (int k = 0; k < model.njoints; ++k) |
| 54 | { | ||
| 55 |
7/14✓ Branch 1 taken 112 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 112 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 112 times.
✗ Branch 12 not taken.
✓ Branch 17 taken 112 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 112 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 112 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 112 times.
|
112 | BOOST_CHECK(data.com[(size_t)k].isApprox(data_other.com[(size_t)k])); |
| 56 |
7/14✓ Branch 1 taken 112 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 112 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 112 times.
✗ Branch 12 not taken.
✓ Branch 17 taken 112 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 112 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 112 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 112 times.
|
112 | BOOST_CHECK(data.vcom[(size_t)k].isApprox(data_other.vcom[(size_t)k])); |
| 57 |
6/12✓ Branch 1 taken 112 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 112 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 112 times.
✗ Branch 9 not taken.
✓ Branch 15 taken 112 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 112 times.
✗ Branch 19 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 112 times.
|
112 | BOOST_CHECK_CLOSE(data.mass[(size_t)k], data_other.mass[(size_t)k], 1e-12); |
| 58 | } | ||
| 59 | |||
| 60 |
6/12✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 4 times.
✗ Branch 9 not taken.
✓ Branch 13 taken 4 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 4 times.
✗ Branch 17 not taken.
✗ Branch 20 not taken.
✓ Branch 21 taken 4 times.
|
4 | BOOST_CHECK_CLOSE(data.kinetic_energy, data_other.kinetic_energy, 1e-12); |
| 61 |
6/12✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 4 times.
✗ Branch 9 not taken.
✓ Branch 13 taken 4 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 4 times.
✗ Branch 17 not taken.
✗ Branch 20 not taken.
✓ Branch 21 taken 4 times.
|
4 | BOOST_CHECK_CLOSE(data.potential_energy, data_other.potential_energy, 1e-12); |
| 62 | 4 | } | |
| 63 | |||
| 64 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_against_algo) |
| 65 | { | ||
| 66 | using namespace Eigen; | ||
| 67 | |||
| 68 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::Model model; |
| 69 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | buildModels::humanoidRandom(model); |
| 70 | |||
| 71 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | VectorXd q(VectorXd::Random(model.nq)); |
| 72 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | VectorXd v(VectorXd::Random(model.nv)); |
| 73 | |||
| 74 | // ------- | ||
| 75 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | q.setZero(); |
| 76 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | v.setZero(); |
| 77 | |||
| 78 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | run_test(model, q, v); |
| 79 | |||
| 80 | // ------- | ||
| 81 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | q.setZero(); |
| 82 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | v.setOnes(); |
| 83 | |||
| 84 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | run_test(model, q, v); |
| 85 | |||
| 86 | // ------- | ||
| 87 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | q.setOnes(); |
| 88 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | q.segment<4>(3).normalize(); |
| 89 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | v.setOnes(); |
| 90 | |||
| 91 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | run_test(model, q, v); |
| 92 | |||
| 93 | // ------- | ||
| 94 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | q.setRandom(); |
| 95 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | q.segment<4>(3).normalize(); |
| 96 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | v.setRandom(); |
| 97 | |||
| 98 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | run_test(model, q, v); |
| 99 | 2 | } | |
| 100 | |||
| 101 | BOOST_AUTO_TEST_SUITE_END() | ||
| 102 |