GCC Code Coverage Report


Directory: ./
File: unittest/crba.cpp
Date: 2025-02-12 21:03:38
Exec Total Coverage
Lines: 80 80 100.0%
Branches: 277 550 50.4%

Line Branch Exec Source
1 //
2 // Copyright (c) 2015-2023 CNRS INRIA
3 //
4
5 /*
6 * Test the CRBA algorithm. The code validates both the computation times and
7 * the value by comparing the results of the CRBA with the reconstruction of
8 * the mass matrix using the RNEA.
9 * For a strong timing benchmark, see benchmark/timings.
10 *
11 */
12
13 #ifndef EIGEN_RUNTIME_NO_MALLOC
14 #define EIGEN_RUNTIME_NO_MALLOC
15 #endif
16
17 #include "pinocchio/multibody/model.hpp"
18 #include "pinocchio/multibody/data.hpp"
19 #include "pinocchio/algorithm/crba.hpp"
20 #include "pinocchio/algorithm/centroidal.hpp"
21 #include "pinocchio/algorithm/rnea.hpp"
22 #include "pinocchio/algorithm/jacobian.hpp"
23 #include "pinocchio/algorithm/center-of-mass.hpp"
24 #include "pinocchio/algorithm/joint-configuration.hpp"
25 #include "pinocchio/multibody/sample-models.hpp"
26 #include "pinocchio/utils/timer.hpp"
27
28 #include <iostream>
29
30 #include <boost/test/unit_test.hpp>
31 #include <boost/utility/binary.hpp>
32
33 template<typename JointModel>
34 static void addJointAndBody(
35 pinocchio::Model & model,
36 const pinocchio::JointModelBase<JointModel> & joint,
37 const std::string & parent_name,
38 const std::string & name,
39 const pinocchio::SE3 placement = pinocchio::SE3::Random(),
40 bool setRandomLimits = true)
41 {
42 using namespace pinocchio;
43 typedef typename JointModel::ConfigVector_t CV;
44 typedef typename JointModel::TangentVector_t TV;
45
46 Model::JointIndex idx;
47
48 if (setRandomLimits)
49 idx = model.addJoint(
50 model.getJointId(parent_name), joint, SE3::Random(), name + "_joint",
51 TV::Random() + TV::Constant(1), TV::Random() + TV::Constant(1),
52 CV::Random() - CV::Constant(1), CV::Random() + CV::Constant(1));
53 else
54 idx = model.addJoint(model.getJointId(parent_name), joint, placement, name + "_joint");
55
56 model.addJointFrame(idx);
57
58 model.appendBodyToJoint(idx, Inertia::Random(), SE3::Identity());
59 model.addBodyFrame(name + "_body", idx);
60 }
61
62 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
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_crba)
65 {
66
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Model model;
67
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::buildModels::humanoidRandom(model);
68
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Data data(model);
69
70 #ifdef NDEBUG
71 #ifdef _INTENSE_TESTING_
72 const size_t NBT = 1000 * 1000;
73 #else
74 const size_t NBT = 10;
75 #endif
76
77 Eigen::VectorXd q = Eigen::VectorXd::Zero(model.nq);
78
79 PinocchioTicToc timer(PinocchioTicToc::US);
80 timer.tic();
81 SMOOTH(NBT)
82 {
83 pinocchio::crba(model, data, q, pinocchio::Convention::WORLD);
84 }
85 timer.toc(std::cout, NBT);
86
87 #else
88 2 const size_t NBT = 1;
89 using namespace Eigen;
90 using namespace pinocchio;
91
92
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Eigen::MatrixXd M(model.nv, model.nv);
93
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Eigen::VectorXd q = Eigen::VectorXd::Ones(model.nq);
94
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();
95
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Eigen::VectorXd v = Eigen::VectorXd::Zero(model.nv);
96
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Eigen::VectorXd a = Eigen::VectorXd::Zero(model.nv);
97
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 data.M.fill(0);
98
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::crba(model, data, q, Convention::WORLD);
99
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 data.M.triangularView<Eigen::StrictlyLower>() =
100
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.M.transpose().triangularView<Eigen::StrictlyLower>();
101
102 /* Joint inertia from iterative crba. */
103
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 const Eigen::VectorXd bias = rnea(model, data, q, v, a);
104
2/2
✓ Branch 0 taken 32 times.
✓ Branch 1 taken 1 times.
66 for (int i = 0; i < model.nv; ++i)
105 {
106
5/10
✓ Branch 1 taken 32 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 32 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 32 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 32 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 32 times.
✗ Branch 14 not taken.
64 M.col(i) = rnea(model, data, q, v, Eigen::VectorXd::Unit(model.nv, i)) - bias;
107 }
108
109 // std::cout << "Mcrb = [ " << data.M << " ];" << std::endl;
110 // std::cout << "Mrne = [ " << M << " ]; " << std::endl;
111
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(M.isApprox(data.M, 1e-12));
112
113
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 std::cout << "(the time score in debug mode is not relevant) ";
114
115
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 q = Eigen::VectorXd::Zero(model.nq);
116
117
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 PinocchioTicToc timer(PinocchioTicToc::US);
118
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 timer.tic();
119
2/2
✓ Branch 0 taken 1 times.
✓ Branch 1 taken 1 times.
4 SMOOTH(NBT)
120 {
121
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::crba(model, data, q, Convention::WORLD);
122 }
123
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 timer.toc(std::cout, NBT);
124
125 #endif // ifndef NDEBUG
126 2 }
127
128
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_minimal_crba)
129 {
130
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Model model;
131
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::buildModels::humanoidRandom(model);
132
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 pinocchio::Data data(model), data_ref(model);
133
134
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.lowerPositionLimit.head<7>().fill(-1.);
135
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 model.upperPositionLimit.head<7>().fill(1.);
136
137 Eigen::VectorXd q =
138
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 randomConfiguration(model, model.lowerPositionLimit, model.upperPositionLimit);
139
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Eigen::VectorXd v(Eigen::VectorXd::Random(model.nv));
140
141
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::crba(model, data_ref, q, pinocchio::Convention::LOCAL);
142
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 data_ref.M.triangularView<Eigen::StrictlyLower>() =
143
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>();
144
145
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::crba(model, data, q, pinocchio::Convention::WORLD);
146
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 data.M.triangularView<Eigen::StrictlyLower>() =
147
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.M.transpose().triangularView<Eigen::StrictlyLower>();
148
149
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.M.isApprox(data_ref.M));
150
151
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 ccrba(model, data_ref, q, v);
152
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeJointJacobians(model, data_ref, q);
153
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.Ag.isApprox(data_ref.Ag));
154
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));
155
156 // Check double call
157 {
158
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Data data2(model);
159
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::crba(model, data2, q, pinocchio::Convention::LOCAL);
160
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::crba(model, data2, q, pinocchio::Convention::LOCAL);
161
162
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 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
2 BOOST_CHECK(data2.Ycrb[0] == data.Ycrb[0]);
163 2 }
164 2 }
165
166
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_roto_inertia_effects)
167 {
168
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 pinocchio::Model model, model_ref;
169
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::buildModels::humanoidRandom(model);
170
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 model_ref = model;
171
172
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(model == model_ref);
173
174
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 pinocchio::Data data(model), data_ref(model_ref);
175
176
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 = Eigen::VectorXd::Random(model.nv) + Eigen::VectorXd::Constant(model.nv, 1.);
177
178
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Eigen::VectorXd q = randomConfiguration(model);
179
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::crba(model_ref, data_ref, q, pinocchio::Convention::WORLD);
180
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 data_ref.M.triangularView<Eigen::StrictlyLower>() =
181
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>();
182
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 data_ref.M.diagonal() += model.armature;
183
184
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::crba(model, data, q, pinocchio::Convention::WORLD);
185
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 data.M.triangularView<Eigen::StrictlyLower>() =
186
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.M.transpose().triangularView<Eigen::StrictlyLower>();
187
188
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.M.isApprox(data_ref.M));
189 2 }
190
191 #ifndef NDEBUG
192
193
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_crba_malloc)
194 {
195 using namespace pinocchio;
196
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Model model;
197
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::buildModels::humanoidRandom(model);
198
199
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
8 model.addJoint(
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.
4 size_t(model.njoints - 1), pinocchio::JointModelRevoluteUnaligned(SE3::Vector3::UnitX()),
201
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
4 SE3::Random(), "revolute_unaligned");
202
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Data data(model);
203
204
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 const Eigen::VectorXd q = pinocchio::neutral(model);
205 2 Eigen::internal::set_is_malloc_allowed(false);
206
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 crba(model, data, q);
207 2 Eigen::internal::set_is_malloc_allowed(true);
208 2 }
209
210 #endif
211
212 BOOST_AUTO_TEST_SUITE_END()
213