GCC Code Coverage Report


Directory: ./
File: unittest/rnea.cpp
Date: 2025-02-12 21:03:38
Exec Total Coverage
Lines: 184 184 100.0%
Branches: 597 1188 50.3%

Line Branch Exec Source
1 //
2 // Copyright (c) 2015-2020 CNRS INRIA
3 //
4
5 /*
6 * Unittest of the RNE algorithm. The code simply test that the algorithm does
7 * not cause any serious errors. The numerical values are not cross validated
8 * in any way.
9 *
10 */
11
12 #include "pinocchio/spatial/fwd.hpp"
13 #include "pinocchio/multibody/model.hpp"
14 #include "pinocchio/multibody/data.hpp"
15 #include "pinocchio/algorithm/rnea.hpp"
16 #include "pinocchio/algorithm/jacobian.hpp"
17 #include "pinocchio/algorithm/center-of-mass.hpp"
18 #include "pinocchio/algorithm/joint-configuration.hpp"
19 #include "pinocchio/algorithm/crba.hpp"
20 #include "pinocchio/algorithm/centroidal.hpp"
21 #include "pinocchio/multibody/sample-models.hpp"
22 #include "pinocchio/utils/timer.hpp"
23
24 #include <iostream>
25
26 // #define __SSE3__
27 #include <fenv.h>
28
29 #ifdef __SSE3__
30 #include <pmmintrin.h>
31 #endif
32
33 #include <boost/test/unit_test.hpp>
34 #include <boost/utility/binary.hpp>
35
36 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
37
38
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_rnea)
39 {
40 #ifdef __SSE3__
41 _MM_SET_DENORMALS_ZERO_MODE(_MM_DENORMALS_ZERO_ON);
42 #endif
43 using namespace Eigen;
44 using namespace pinocchio;
45
46
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Model model;
47
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 buildModels::humanoidRandom(model);
48
49
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.lowerPositionLimit.head<3>().fill(-1.);
50
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.upperPositionLimit.head<3>().fill(1.);
51
52
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Data data(model);
53
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 data.v[0] = Motion::Zero();
54
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 data.a[0] = -model.gravity;
55
56
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 VectorXd q = randomConfiguration(model);
57
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);
58
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 VectorXd a = VectorXd::Random(model.nv);
59
60 #ifdef NDEBUG
61 const size_t NBT = 10000;
62 #else
63 2 const size_t NBT = 1;
64
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 std::cout << "(the time score in debug mode is not relevant) ";
65 #endif
66
67
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 PinocchioTicToc timer(PinocchioTicToc::US);
68
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 timer.tic();
69
2/2
✓ Branch 0 taken 1 times.
✓ Branch 1 taken 1 times.
4 SMOOTH(NBT)
70 {
71
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 rnea(model, data, q, v, a);
72 }
73
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 timer.toc(std::cout, NBT);
74 2 }
75
76
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_nle_vs_rnea)
77 {
78 using namespace Eigen;
79 using namespace pinocchio;
80
81
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Model model;
82
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 buildModels::humanoidRandom(model);
83
84
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.lowerPositionLimit.head<3>().fill(-1.);
85
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.upperPositionLimit.head<3>().fill(1.);
86
87
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Data data_nle(model);
88
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Data data_rnea(model);
89
90
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 VectorXd q = randomConfiguration(model);
91
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);
92
93
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 VectorXd tau_nle(VectorXd::Zero(model.nv));
94
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 VectorXd tau_rnea(VectorXd::Zero(model.nv));
95
96 // -------
97
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 q.tail(model.nq - 7).setZero();
98
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 v.setZero();
99
100
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 tau_nle = nonLinearEffects(model, data_nle, q, v);
101
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
2 tau_rnea = rnea(model, data_rnea, q, v, VectorXd::Zero(model.nv));
102
103
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
2 BOOST_CHECK(tau_nle.isApprox(tau_rnea, 1e-12));
104
105 // -------
106
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 q.tail(model.nq - 7).setZero();
107
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 v.setOnes();
108
109
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 tau_nle = nonLinearEffects(model, data_nle, q, v);
110
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
2 tau_rnea = rnea(model, data_rnea, q, v, VectorXd::Zero(model.nv));
111
112
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
2 BOOST_CHECK(tau_nle.isApprox(tau_rnea, 1e-12));
113
114 // -------
115
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 q.tail(model.nq - 7).setOnes();
116
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 v.setOnes();
117
118
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 tau_nle = nonLinearEffects(model, data_nle, q, v);
119
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
2 tau_rnea = rnea(model, data_rnea, q, v, VectorXd::Zero(model.nv));
120
121
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
2 BOOST_CHECK(tau_nle.isApprox(tau_rnea, 1e-12));
122
123 // -------
124
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q = randomConfiguration(model);
125
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 v.setRandom();
126
127
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 tau_nle = nonLinearEffects(model, data_nle, q, v);
128
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
2 tau_rnea = rnea(model, data_rnea, q, v, VectorXd::Zero(model.nv));
129
130
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
2 BOOST_CHECK(tau_nle.isApprox(tau_rnea, 1e-12));
131 2 }
132
133
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_rnea_with_fext)
134 {
135 using namespace Eigen;
136 using namespace pinocchio;
137
138
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
139
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 buildModels::humanoidRandom(model);
140
141
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.lowerPositionLimit.head<3>().fill(-1.);
142
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.upperPositionLimit.head<3>().fill(1.);
143
144
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data_rnea_fext(model);
145
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data_rnea(model);
146
147
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 VectorXd q = randomConfiguration(model);
148
149
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));
150
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 VectorXd a(VectorXd::Random(model.nv));
151
152
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
2 PINOCCHIO_ALIGNED_STD_VECTOR(Force) fext(model.joints.size(), Force::Zero());
153
154
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 JointIndex rf = model.getJointId("rleg6_joint");
155
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Force Frf = Force::Random();
156
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 fext[rf] = Frf;
157
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 JointIndex lf = model.getJointId("lleg6_joint");
158
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Force Flf = Force::Random();
159
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 fext[lf] = Flf;
160
161
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 rnea(model, data_rnea, q, v, a);
162
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 VectorXd tau_ref(data_rnea.tau);
163
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Data::Matrix6x Jrf(Data::Matrix6x::Zero(6, model.nv));
164
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeJointJacobian(model, data_rnea, q, rf, Jrf);
165
4/8
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
2 tau_ref -= Jrf.transpose() * Frf.toVector();
166
167
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Data::Matrix6x Jlf(Data::Matrix6x::Zero(6, model.nv));
168
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeJointJacobian(model, data_rnea, q, lf, Jlf);
169
4/8
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
2 tau_ref -= Jlf.transpose() * Flf.toVector();
170
171
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 rnea(model, data_rnea_fext, q, v, a, fext);
172
173
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
2 BOOST_CHECK(tau_ref.isApprox(data_rnea_fext.tau));
174 2 }
175
176
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_rnea_with_armature)
177 {
178 using namespace Eigen;
179 using namespace pinocchio;
180
181
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
182
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 buildModels::humanoidRandom(model);
183
4/8
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
2 model.armature = VectorXd::Random(model.nv) + VectorXd::Ones(model.nv);
184
185
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.lowerPositionLimit.head<3>().fill(-1.);
186
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.upperPositionLimit.head<3>().fill(1.);
187
188
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data(model);
189
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data_ref(model);
190
191
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 VectorXd q = randomConfiguration(model);
192
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));
193
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 VectorXd a(VectorXd::Random(model.nv));
194
195
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 crba(model, data_ref, q, Convention::WORLD);
196
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 data_ref.M.triangularView<StrictlyLower>() =
197
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
4 data_ref.M.transpose().triangularView<StrictlyLower>();
198
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 const VectorXd nle = nonLinearEffects(model, data_ref, q, v);
199
200
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
2 const VectorXd tau_ref = data_ref.M * a + nle;
201
202
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 rnea(model, data, q, v, a);
203
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
2 BOOST_CHECK(tau_ref.isApprox(data.tau));
204 2 }
205
206
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_compute_gravity)
207 {
208 using namespace Eigen;
209 using namespace pinocchio;
210
211
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
212
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 buildModels::humanoidRandom(model);
213
214
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.lowerPositionLimit.head<3>().fill(-1.);
215
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.upperPositionLimit.head<3>().fill(1.);
216
217
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data_rnea(model);
218
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data(model);
219
220
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 VectorXd q = randomConfiguration(model);
221
222
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
2 rnea(model, data_rnea, q, VectorXd::Zero(model.nv), VectorXd::Zero(model.nv));
223
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeGeneralizedGravity(model, data, q);
224
225
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
2 BOOST_CHECK(data_rnea.tau.isApprox(data.g));
226
227 // Compare with Jcom
228
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 crba(model, data_rnea, q, Convention::WORLD);
229
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Data::Matrix3x Jcom = getJacobianComFromCrba(model, data_rnea);
230
231
4/8
✓ 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.
2 VectorXd g_ref(-data_rnea.mass[0] * Jcom.transpose() * Model::gravity981);
232
233
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
2 BOOST_CHECK(g_ref.isApprox(data.g));
234 2 }
235
236
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_compute_static_torque)
237 {
238 using namespace Eigen;
239 using namespace pinocchio;
240
241
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
242
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 buildModels::humanoidRandom(model);
243
244
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.lowerPositionLimit.head<3>().fill(-1.);
245
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.upperPositionLimit.head<3>().fill(1.);
246
247
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data_rnea(model);
248
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data(model);
249
250
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 VectorXd q = randomConfiguration(model);
251
252 typedef PINOCCHIO_ALIGNED_STD_VECTOR(Force) ForceVector;
253
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 ForceVector fext((size_t)model.njoints);
254
2/2
✓ Branch 4 taken 28 times.
✓ Branch 5 taken 1 times.
58 for (ForceVector::iterator it = fext.begin(); it != fext.end(); ++it)
255
1/2
✓ Branch 2 taken 28 times.
✗ Branch 3 not taken.
56 (*it).setRandom();
256
257
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
2 rnea(model, data_rnea, q, VectorXd::Zero(model.nv), VectorXd::Zero(model.nv), fext);
258
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeStaticTorque(model, data, q, fext);
259
260
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
2 BOOST_CHECK(data_rnea.tau.isApprox(data.tau));
261
262 // Compare with Jcom + Jacobian of joint
263
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 crba(model, data_rnea, q, Convention::WORLD);
264
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Data::Matrix3x Jcom = getJacobianComFromCrba(model, data_rnea);
265
266
4/8
✓ 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.
2 VectorXd static_torque_ref = -data_rnea.mass[0] * Jcom.transpose() * Model::gravity981;
267
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeJointJacobians(model, data_rnea, q);
268
269
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data::Matrix6x J_local(6, model.nv);
270
2/2
✓ Branch 0 taken 27 times.
✓ Branch 1 taken 1 times.
56 for (JointIndex joint_id = 1; joint_id < (JointIndex)(model.njoints); ++joint_id)
271 {
272
1/2
✓ Branch 1 taken 27 times.
✗ Branch 2 not taken.
54 J_local.setZero();
273
1/2
✓ Branch 1 taken 27 times.
✗ Branch 2 not taken.
54 getJointJacobian(model, data_rnea, joint_id, LOCAL, J_local);
274
4/8
✓ Branch 2 taken 27 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 27 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 27 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 27 times.
✗ Branch 12 not taken.
54 static_torque_ref -= J_local.transpose() * fext[joint_id].toVector();
275 }
276
277
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
2 BOOST_CHECK(static_torque_ref.isApprox(data.tau));
278 2 }
279
280
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_compute_coriolis)
281 {
282 using namespace Eigen;
283 using namespace pinocchio;
284
285 2 const double prec = Eigen::NumTraits<double>::dummy_precision();
286
287
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
288
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 buildModels::humanoidRandom(model);
289
290
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.lowerPositionLimit.head<3>().fill(-1.);
291
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.upperPositionLimit.head<3>().fill(1.);
292
293
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data_ref(model);
294
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data(model);
295
296
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 VectorXd q = randomConfiguration(model);
297
298
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));
299
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 computeCoriolisMatrix(model, data, q, Eigen::VectorXd::Zero(model.nv));
300
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
2 BOOST_CHECK(data.C.isZero(prec));
301
302
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 model.gravity.setZero();
303
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 rnea(model, data_ref, q, v, VectorXd::Zero(model.nv));
304
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeJointJacobiansTimeVariation(model, data_ref, q, v);
305
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeCoriolisMatrix(model, data, q, v);
306
307
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
2 BOOST_CHECK(data.dJ.isApprox(data_ref.dJ));
308
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
2 BOOST_CHECK(data.J.isApprox(data_ref.J));
309
310
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 VectorXd tau = data.C * v;
311
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
2 BOOST_CHECK(tau.isApprox(data_ref.tau, prec));
312
313
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 dccrba(model, data_ref, q, v);
314
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 crba(model, data_ref, q, Convention::WORLD);
315
316 2 const Data::Vector3 & com = data_ref.com[0];
317
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 Motion vcom(data_ref.vcom[0], Data::Vector3::Zero());
318
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 SE3 cM1(data.oMi[1]);
319
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 cM1.translation() -= com;
320
321
10/20
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 1 times.
✗ Branch 30 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 1 times.
2 BOOST_CHECK((cM1.toDualActionMatrix() * data_ref.M.topRows<6>()).isApprox(data_ref.Ag, prec));
322
323
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
2 Force dh_ref = cM1.act(Force(data_ref.tau.head<6>()));
324
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Force dh(data_ref.dAg * v);
325
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
2 BOOST_CHECK(dh.isApprox(dh_ref, prec));
326
327 {
328
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Data data_ref(model), data_ref_plus(model);
329
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
2 Eigen::MatrixXd dM(data.C + data.C.transpose());
330
331 2 const double alpha = 1e-8;
332
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Eigen::VectorXd q_plus(model.nq);
333
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 q_plus = integrate(model, q, alpha * v);
334
335
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 crba(model, data_ref, q, Convention::WORLD);
336
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 data_ref.M.triangularView<Eigen::StrictlyLower>() =
337
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
4 data_ref.M.transpose().triangularView<Eigen::StrictlyLower>();
338
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 crba(model, data_ref_plus, q_plus, Convention::WORLD);
339
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 data_ref_plus.M.triangularView<Eigen::StrictlyLower>() =
340
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
4 data_ref_plus.M.transpose().triangularView<Eigen::StrictlyLower>();
341
342
3/6
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
2 Eigen::MatrixXd dM_ref = (data_ref_plus.M - data_ref.M) / alpha;
343
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
2 BOOST_CHECK(dM.isApprox(dM_ref, sqrt(alpha)));
344 2 }
345 2 }
346
347 BOOST_AUTO_TEST_SUITE_END()
348