GCC Code Coverage Report


Directory: ./
File: unittest/centroidal.cpp
Date: 2025-04-30 16:14:33
Exec Total Coverage
Lines: 285 286 99.7%
Branches: 980 1956 50.1%

Line Branch Exec Source
1 //
2 // Copyright (c) 2015-2019 CNRS INRIA
3 //
4
5 #include "pinocchio/algorithm/crba.hpp"
6 #include "pinocchio/algorithm/centroidal.hpp"
7 #include "pinocchio/algorithm/rnea.hpp"
8 #include "pinocchio/algorithm/jacobian.hpp"
9 #include "pinocchio/algorithm/center-of-mass.hpp"
10 #include "pinocchio/algorithm/joint-configuration.hpp"
11
12 #include "pinocchio/multibody/sample-models.hpp"
13
14 #include "pinocchio/utils/timer.hpp"
15
16 #include <iostream>
17
18 #include <boost/test/unit_test.hpp>
19 #include <boost/utility/binary.hpp>
20
21 #include "utils/model-generator.hpp"
22
23 template<typename JointModel>
24 2 static void addJointAndBody(
25 pinocchio::Model & model,
26 const pinocchio::JointModelBase<JointModel> & joint,
27 const std::string & parent_name,
28 const std::string & name,
29 const pinocchio::SE3 placement = pinocchio::SE3::Random(),
30 bool setRandomLimits = true)
31 {
32 using namespace pinocchio;
33 typedef typename JointModel::ConfigVector_t CV;
34 typedef typename JointModel::TangentVector_t TV;
35
36 Model::JointIndex idx;
37
38
1/2
✓ Branch 0 taken 2 times.
✗ Branch 1 not taken.
2 if (setRandomLimits)
39
21/42
✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 2 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 2 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 2 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 2 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 2 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 2 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 2 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 2 times.
✗ Branch 32 not taken.
✓ Branch 34 taken 2 times.
✗ Branch 35 not taken.
✓ Branch 37 taken 2 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 2 times.
✗ Branch 41 not taken.
✓ Branch 43 taken 2 times.
✗ Branch 44 not taken.
✓ Branch 46 taken 2 times.
✗ Branch 47 not taken.
✓ Branch 49 taken 2 times.
✗ Branch 50 not taken.
✓ Branch 52 taken 2 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 2 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 2 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 2 times.
✗ Branch 62 not taken.
2 idx = model.addJoint(
40 model.getJointId(parent_name), joint, SE3::Random(), name + "_joint",
41 TV::Random() + TV::Constant(1), TV::Random() + TV::Constant(1),
42 CV::Random() - CV::Constant(1), CV::Random() + CV::Constant(1));
43 else
44 idx = model.addJoint(model.getJointId(parent_name), joint, placement, name + "_joint");
45
46
1/2
✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
2 model.addJointFrame(idx);
47
48
3/6
✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2 times.
✗ Branch 8 not taken.
2 model.appendBodyToJoint(idx, Inertia::Random(), SE3::Identity());
49
3/6
✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2 times.
✗ Branch 8 not taken.
2 model.addBodyFrame(name + "_body", idx);
50 2 }
51
52 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
53
54
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_ccrba)
55 {
56
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Model model;
57
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::buildModels::humanoidRandom(model);
58
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);
59
60
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.);
61
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.);
62
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Eigen::VectorXd q = randomConfiguration(model);
63
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::Ones(model.nv);
64
65
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::crba(model, data_ref, q, pinocchio::Convention::LOCAL);
66
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 data_ref.M.triangularView<Eigen::StrictlyLower>() =
67
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>();
68
69
2/4
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
2 data_ref.Ycrb[0] = data_ref.liMi[1].act(data_ref.Ycrb[1]);
70
71
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Data data_ref_other(model);
72
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::crba(model, data_ref_other, q, pinocchio::Convention::WORLD);
73
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 data_ref_other.M.triangularView<Eigen::StrictlyLower>() =
74
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_other.M.transpose().triangularView<Eigen::StrictlyLower>();
75
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_ref_other.M.isApprox(data_ref.M));
76
77
3/6
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 pinocchio::SE3 cMo(pinocchio::SE3::Matrix3::Identity(), -data_ref.Ycrb[0].lever());
78
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 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 28 not taken.
✓ Branch 29 taken 1 times.
2 BOOST_CHECK(data_ref.Ycrb[0].isApprox(data_ref_other.oYcrb[0]));
79
80
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 ccrba(model, data, q, v);
81
9/18
✓ 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 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1 times.
2 BOOST_CHECK(data.com[0].isApprox(-cMo.translation(), 1e-12));
82
9/18
✓ 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 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
✗ Branch 33 not taken.
✓ Branch 34 taken 1 times.
2 BOOST_CHECK(data.oYcrb[0].matrix().isApprox(data_ref.Ycrb[0].matrix(), 1e-12));
83
84
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 pinocchio::Inertia Ig_ref(cMo.act(data.oYcrb[0]));
85
9/18
✓ 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 31 not taken.
✓ Branch 32 taken 1 times.
2 BOOST_CHECK(data.Ig.matrix().isApprox(Ig_ref.matrix(), 1e-12));
86
87
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 pinocchio::SE3 oM1(data_ref.liMi[1]);
88
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::SE3 cM1(cMo * oM1);
89
90 pinocchio::Data::Matrix6x Ag_ref(
91
6/12
✓ 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.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
2 cM1.inverse().toActionMatrix().transpose() * data_ref.M.topRows<6>());
92
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.Ag.isApprox(Ag_ref, 1e-12));
93 2 }
94
95
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_ccrba_mimic)
96 {
97
2/2
✓ Branch 0 taken 6 times.
✓ Branch 1 taken 1 times.
14 for (int i = 0; i < pinocchio::MimicTestCases::N_CASES; i++)
98 {
99
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 const pinocchio::MimicTestCases mimic_test_case(i);
100 12 const pinocchio::Model & model_mimic = mimic_test_case.model_mimic;
101 12 const pinocchio::Model & model_full = mimic_test_case.model_full;
102 12 const Eigen::MatrixXd & G = mimic_test_case.G;
103
104
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 pinocchio::Data data_mimic(model_mimic);
105
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 pinocchio::Data data_ref_mimic(model_mimic);
106
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 pinocchio::Data data_full(model_full);
107
108
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 Eigen::VectorXd q = pinocchio::randomConfiguration(model_mimic);
109
2/4
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 6 times.
✗ Branch 5 not taken.
12 Eigen::VectorXd v = Eigen::VectorXd::Random(model_mimic.nv);
110
2/4
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 6 times.
✗ Branch 5 not taken.
12 Eigen::VectorXd a = Eigen::VectorXd::Random(model_mimic.nv);
111
112
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 Eigen::VectorXd q_full(model_full.nq);
113
2/4
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 6 times.
✗ Branch 5 not taken.
12 Eigen::VectorXd v_full = G * v;
114
2/4
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 6 times.
✗ Branch 5 not taken.
12 Eigen::VectorXd a_full = G * a;
115
116
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 mimic_test_case.toFull(q, q_full);
117
118
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 pinocchio::crba(model_mimic, data_ref_mimic, q, pinocchio::Convention::LOCAL);
119
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 data_ref_mimic.M.triangularView<Eigen::StrictlyLower>() =
120
3/6
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 6 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 6 times.
✗ Branch 8 not taken.
24 data_ref_mimic.M.transpose().triangularView<Eigen::StrictlyLower>();
121
122
2/4
✓ Branch 3 taken 6 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 6 times.
✗ Branch 8 not taken.
12 data_ref_mimic.Ycrb[0] = data_ref_mimic.liMi[1].act(data_ref_mimic.Ycrb[1]);
123
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 pinocchio::Data data_ref_other(model_mimic);
124
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 pinocchio::crba(model_mimic, data_ref_other, q, pinocchio::Convention::WORLD);
125
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 data_ref_other.M.triangularView<Eigen::StrictlyLower>() =
126
3/6
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 6 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 6 times.
✗ Branch 8 not taken.
24 data_ref_other.M.transpose().triangularView<Eigen::StrictlyLower>();
127
128
3/6
✓ Branch 3 taken 6 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 6 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 6 times.
✗ Branch 10 not taken.
12 pinocchio::SE3 cMo(pinocchio::SE3::Matrix3::Identity(), -data_ref_mimic.Ycrb[0].lever());
129
7/14
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 6 times.
✗ Branch 12 not taken.
✓ Branch 17 taken 6 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 6 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 6 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 6 times.
12 BOOST_CHECK(data_ref_mimic.Ycrb[0].isApprox(data_ref_other.oYcrb[0]));
130
131
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 ccrba(model_mimic, data_mimic, q, v);
132
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 ccrba(model_full, data_full, q_full, v_full);
133
7/14
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 6 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 6 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 6 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 6 times.
✗ Branch 23 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 6 times.
12 BOOST_CHECK(data_mimic.com[0].isApprox(data_full.com[0], 1e-12));
134
9/18
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 6 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 6 times.
✗ Branch 16 not taken.
✓ Branch 19 taken 6 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 6 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 6 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 6 times.
✗ Branch 29 not taken.
✗ Branch 33 not taken.
✓ Branch 34 taken 6 times.
12 BOOST_CHECK(data_mimic.oYcrb[0].matrix().isApprox(data_full.oYcrb[0].matrix(), 1e-12));
135
136
9/18
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 6 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 6 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 6 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 6 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 6 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 6 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 6 times.
12 BOOST_CHECK(data_mimic.com[0].isApprox(-cMo.translation(), 1e-12));
137
9/18
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 6 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 6 times.
✗ Branch 16 not taken.
✓ Branch 19 taken 6 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 6 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 6 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 6 times.
✗ Branch 29 not taken.
✗ Branch 33 not taken.
✓ Branch 34 taken 6 times.
12 BOOST_CHECK(data_mimic.oYcrb[0].matrix().isApprox(data_ref_mimic.Ycrb[0].matrix(), 1e-12));
138
139
1/2
✓ Branch 2 taken 6 times.
✗ Branch 3 not taken.
12 pinocchio::Inertia Ig_ref(cMo.act(data_mimic.oYcrb[0]));
140
9/18
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 6 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 6 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 6 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 6 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 6 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 6 times.
✗ Branch 27 not taken.
✗ Branch 31 not taken.
✓ Branch 32 taken 6 times.
12 BOOST_CHECK(data_mimic.Ig.matrix().isApprox(Ig_ref.matrix(), 1e-12));
141
142
1/2
✓ Branch 2 taken 6 times.
✗ Branch 3 not taken.
12 pinocchio::SE3 oM1(data_ref_other.liMi[1]);
143
1/2
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
12 pinocchio::SE3 cM1(cMo * oM1);
144 pinocchio::Data::Matrix6x Ag_ref(
145
6/12
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 6 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 6 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 6 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 6 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 6 times.
✗ Branch 17 not taken.
12 cM1.inverse().toActionMatrix().transpose() * data_ref_other.M.topRows<6>());
146
7/14
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 6 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 6 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 6 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 6 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 6 times.
12 BOOST_CHECK(data_mimic.Ag.isApprox(Ag_ref, 1e-12));
147 12 }
148 2 }
149
150
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_centroidal_mapping)
151 {
152
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Model model;
153
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::buildModels::humanoidRandom(model);
154
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);
155
156
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.);
157
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.);
158
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Eigen::VectorXd q = randomConfiguration(model);
159
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);
160
161
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeCentroidalMap(model, data, q);
162
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 ccrba(model, data_ref, q, v);
163
164
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));
165
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));
166
167
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeJointJacobians(model, data_ref, q);
168
169
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));
170 2 }
171
172
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_dccrb)
173 {
174 using namespace pinocchio;
175
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
176
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 buildModels::humanoidRandom(model);
177
5/10
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
2 addJointAndBody(model, JointModelSpherical(), "larm6_joint", "larm7");
178
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Data data(model), data_ref(model);
179
180
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.);
181
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.);
182
183 Eigen::VectorXd q =
184
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 randomConfiguration(model, model.lowerPositionLimit, model.upperPositionLimit);
185
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);
186
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::Random(model.nv);
187
188
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 const Eigen::VectorXd g = rnea(model, data_ref, q, 0 * v, 0 * a);
189
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 rnea(model, data_ref, q, v, a);
190
191
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::crba(model, data_ref, q, pinocchio::Convention::LOCAL);
192
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 data_ref.M.triangularView<Eigen::StrictlyLower>() =
193
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>();
194
195
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 SE3 cMo(SE3::Identity());
196
2/4
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
2 data_ref.Ycrb[0] = data_ref.liMi[1].act(data_ref.Ycrb[1]);
197
3/6
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
2 cMo.translation() = -data_ref.Ycrb[0].lever();
198
199
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 SE3 oM1(data_ref.liMi[1]);
200
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 SE3 cM1(cMo * oM1);
201
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 Data::Matrix6x Ag_ref(cM1.toDualActionMatrix() * data_ref.M.topRows<6>());
202
203
5/10
✓ 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.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
2 Force hdot_ref(cM1.act(Force(data_ref.tau.head<6>() - g.head<6>())));
204
205
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 ccrba(model, data_ref, q, v);
206
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 dccrba(model, data, q, v);
207
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(Ag_ref));
208
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));
209
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.hg.isApprox(data_ref.hg));
210
211
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 centerOfMass(model, data_ref, q, v, a);
212
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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
2 BOOST_CHECK(data_ref.com[0].isApprox(data_ref.Ycrb[0].lever()));
213
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 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 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 1 times.
✗ Branch 32 not taken.
✗ Branch 36 not taken.
✓ Branch 37 taken 1 times.
2 BOOST_CHECK(data_ref.vcom[0].isApprox(data.hg.linear() / data_ref.M(0, 0)));
214
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 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 28 not taken.
✓ Branch 29 taken 1 times.
2 BOOST_CHECK(data_ref.vcom[0].isApprox(data.vcom[0]));
215
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 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 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 1 times.
✗ Branch 32 not taken.
✗ Branch 36 not taken.
✓ Branch 37 taken 1 times.
2 BOOST_CHECK(data_ref.acom[0].isApprox(hdot_ref.linear() / data_ref.M(0, 0)));
216
217
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 Force hdot(data.Ag * a + data.dAg * v);
218
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(hdot.isApprox(hdot_ref));
219
220
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 dccrba(model, data, q, 0 * v);
221
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.dAg.isZero());
222
223 // Check that dYcrb is equal to doYcrb
224 {
225 // Compute dYcrb
226
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 Data data_ref(model), data_ref_plus(model), data(model);
227
228 2 const double alpha = 1e-8;
229
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Eigen::VectorXd q_plus(model.nq);
230
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);
231
232
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 forwardKinematics(model, data_ref, q);
233
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::crba(model, data_ref, q, pinocchio::Convention::LOCAL);
234
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::crba(model, data_ref_plus, q_plus, pinocchio::Convention::LOCAL);
235
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 forwardKinematics(model, data_ref_plus, q_plus);
236
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 dccrba(model, data, q, v);
237
238
2/2
✓ Branch 0 taken 28 times.
✓ Branch 1 taken 1 times.
58 for (size_t i = 1; i < (size_t)model.njoints; ++i)
239 {
240
2/4
✓ Branch 3 taken 28 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 28 times.
✗ Branch 7 not taken.
56 Inertia::Matrix6 dYcrb = (data_ref_plus.oMi[i].act(data_ref_plus.Ycrb[i]).matrix()
241
3/6
✓ Branch 3 taken 28 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 28 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 28 times.
✗ Branch 10 not taken.
112 - data_ref.oMi[i].act(data_ref.Ycrb[i]).matrix())
242
2/4
✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 28 times.
✗ Branch 5 not taken.
56 / alpha;
243
7/14
✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 28 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 28 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 28 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 28 times.
56 BOOST_CHECK(data.doYcrb[i].isApprox(dYcrb, sqrt(alpha)));
244 }
245 2 }
246
247 {
248
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data(model);
249
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 ccrba(model, data_ref, q, v);
250
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 SE3 oMc_ref(SE3::Identity());
251
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 oMc_ref.translation() = data_ref.com[0];
252
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 Data::Matrix6x Ag_ref = oMc_ref.toDualActionMatrix() * data_ref.Ag;
253
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::crba(model, data_ref, q, pinocchio::Convention::LOCAL);
254 const Data::Matrix6x Ag_ref_from_M =
255
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 data_ref.oMi[1].toDualActionMatrix() * data_ref.M.topRows<6>();
256
257 2 const double alpha = 1e-8;
258
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Eigen::VectorXd q_plus(model.nq);
259
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);
260
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 ccrba(model, data_ref, q_plus, v);
261
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 SE3 oMc_ref_plus(SE3::Identity());
262
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 oMc_ref_plus.translation() = data_ref.com[0];
263
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 Data::Matrix6x Ag_plus_ref = oMc_ref_plus.toDualActionMatrix() * data_ref.Ag;
264
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::crba(model, data_ref, q_plus, pinocchio::Convention::LOCAL);
265 const Data::Matrix6x Ag_plus_ref_from_M =
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 data_ref.oMi[1].toDualActionMatrix() * data_ref.M.topRows<6>();
267
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 Data::Matrix6x dAg_ref = (Ag_plus_ref - Ag_ref) / alpha;
268
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 Data::Matrix6x dAg_ref_from_M = (Ag_plus_ref_from_M - Ag_ref_from_M) / alpha;
269
270
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 dccrba(model, data, q, v);
271
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 SE3 oMc(SE3::Identity());
272
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 oMc.translation() = data.com[0];
273
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 Data::Matrix6x dAg = oMc.toDualActionMatrix() * data.dAg;
274
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(oMc.isApprox(oMc_ref));
275
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(dAg_ref.isApprox(dAg_ref_from_M, sqrt(alpha)));
276 2 }
277
278 // Check for dAg/dt
279 {
280
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data(model);
281
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 ccrba(model, data_ref, q, v);
282
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 const Data::Matrix6x Ag_ref = data_ref.Ag;
283
284 2 const double alpha = 1e-8;
285
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Eigen::VectorXd q_plus(model.nq);
286
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);
287
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 ccrba(model, data_ref, q_plus, v);
288
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 const Data::Matrix6x Ag_plus_ref = data_ref.Ag;
289
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 Data::Matrix6x dAg_ref = (Ag_plus_ref - Ag_ref) / alpha;
290
291
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 dccrba(model, data, q, v);
292
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.dAg.isApprox(dAg_ref, sqrt(alpha)));
293 2 }
294
295 // Compute tensor dAg/dq
296 {
297
3/6
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
4 std::vector<Data::Matrix6x> dAgdq((size_t)model.nv, Data::Matrix6x::Zero(6, model.nv));
298
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Data data(model), data_fd(model);
299
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Eigen::VectorXd v_fd(Eigen::VectorXd::Zero(model.nv));
300
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 ccrba(model, data_fd, q, v);
301
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 SE3 oMc_ref(SE3::Identity());
302
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 oMc_ref.translation() = data_fd.com[0];
303
304
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 Data::Matrix6x Ag0 = oMc_ref.toDualActionMatrix() * data_fd.Ag;
305
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 const Force hg0 = oMc_ref.act(data_fd.hg);
306
307
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data::Matrix6x Ag_fd(6, model.nv);
308
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Force hg_fd;
309 2 const double alpha = 1e-8;
310
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Eigen::VectorXd q_plus(model.nq);
311
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data::Matrix6x dhdq(6, model.nv);
312
2/2
✓ Branch 0 taken 35 times.
✓ Branch 1 taken 1 times.
72 for (int k = 0; k < model.nv; ++k)
313 {
314
1/2
✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
70 v_fd[k] = alpha;
315
1/2
✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
70 q_plus = integrate(model, q, v_fd);
316
1/2
✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
70 ccrba(model, data_fd, q_plus, v);
317
1/2
✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
70 SE3 oMc_fd(SE3::Identity());
318
2/4
✓ Branch 2 taken 35 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 35 times.
✗ Branch 6 not taken.
70 oMc_fd.translation() = data_fd.com[0];
319
3/6
✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 35 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 35 times.
✗ Branch 8 not taken.
70 Ag_fd = oMc_fd.toDualActionMatrix() * data_fd.Ag;
320
2/4
✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 35 times.
✗ Branch 5 not taken.
70 hg_fd = oMc_fd.act(data_fd.hg);
321
3/6
✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 35 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 35 times.
✗ Branch 9 not taken.
70 dAgdq[(size_t)k] = (Ag_fd - Ag0) / alpha;
322
5/10
✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 35 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 35 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 35 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 35 times.
✗ Branch 14 not taken.
70 dhdq.col(k) = (hg_fd - hg0).toVector() / alpha;
323
1/2
✓ Branch 1 taken 35 times.
✗ Branch 2 not taken.
70 v_fd[k] = 0.;
324 }
325
326
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data::Matrix6x dAg_ref(6, model.nv);
327
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 dAg_ref.setZero();
328
2/2
✓ Branch 0 taken 35 times.
✓ Branch 1 taken 1 times.
72 for (int k = 0; k < model.nv; ++k)
329 {
330
3/6
✓ Branch 2 taken 35 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 35 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 35 times.
✗ Branch 9 not taken.
70 dAg_ref.col(k) = dAgdq[(size_t)k] * v;
331 }
332
333
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(dhdq.isApprox(dAg_ref, sqrt(alpha)));
334
9/18
✓ 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 31 not taken.
✓ Branch 32 taken 1 times.
2 BOOST_CHECK((dAg_ref * v).isApprox(dhdq * v, sqrt(alpha)));
335 2 }
336 2 }
337
338
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_centroidal_mapping_time_derivative)
339 {
340
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::Model model;
341
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 pinocchio::buildModels::humanoidRandom(model);
342
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);
343
344
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.);
345
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.);
346
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Eigen::VectorXd q = randomConfiguration(model);
347
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);
348
349
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeCentroidalMapTimeVariation(model, data, q, v);
350
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 dccrba(model, data_ref, q, v);
351
352
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));
353
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));
354
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));
355
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.dAg.isApprox(data_ref.dAg));
356
357
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeJointJacobiansTimeVariation(model, data_ref, q, v);
358
359
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));
360
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));
361 2 }
362
363
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_computeCentroidalMomentum_computeCentroidalMomentumTimeVariation)
364 {
365 using namespace pinocchio;
366
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Model model;
367
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 buildModels::humanoidRandom(model);
368
5/10
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
2 addJointAndBody(model, JointModelSpherical(), "larm6_joint", "larm7");
369
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 Data data(model), data_fk1(model), data_fk2(model), data_ref(model);
370
371
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.);
372
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.);
373
374 Eigen::VectorXd q =
375
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 randomConfiguration(model, model.lowerPositionLimit, model.upperPositionLimit);
376
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);
377
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::Random(model.nv);
378
379
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 ccrba(model, data_ref, q, v);
380
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 forwardKinematics(model, data_ref, q, v);
381
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 centerOfMass(model, data_ref, q, v, false);
382
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeCentroidalMomentum(model, data, q, v);
383
384
6/12
✓ 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 24 not taken.
✓ Branch 25 taken 1 times.
2 BOOST_CHECK(data.mass[0] == data_ref.mass[0]);
385
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 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 28 not taken.
✓ Branch 29 taken 1 times.
2 BOOST_CHECK(data.com[0].isApprox(data_ref.com[0]));
386
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.hg.isApprox(data_ref.hg));
387
2/2
✓ Branch 0 taken 28 times.
✓ Branch 1 taken 1 times.
58 for (size_t k = 1; k < (size_t)model.njoints; ++k)
388 {
389
6/12
✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 28 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 28 times.
✗ Branch 20 not taken.
✗ Branch 24 not taken.
✓ Branch 25 taken 28 times.
56 BOOST_CHECK(data.mass[k] == data_ref.mass[k]);
390
7/14
✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 17 taken 28 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 28 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 28 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 28 times.
56 BOOST_CHECK(data.com[k].isApprox(data_ref.com[k]));
391
7/14
✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 17 taken 28 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 28 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 28 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 28 times.
56 BOOST_CHECK(data.v[k].isApprox(data_ref.v[k]));
392 }
393
394 // Check other signature
395
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 forwardKinematics(model, data_fk1, q, v);
396
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeCentroidalMomentum(model, data_fk1);
397
398
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_fk1.hg.isApprox(data.hg));
399
400
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeCentroidalMomentumTimeVariation(model, data, q, v, a);
401
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 model.gravity.setZero();
402
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 rnea(model, data_ref, q, v, a);
403
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 dccrba(model, data_ref, q, v);
404
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 const Force hgdot(data_ref.Ag * a + data_ref.dAg * v);
405
406
6/12
✓ 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 24 not taken.
✓ Branch 25 taken 1 times.
2 BOOST_CHECK(data.mass[0] == data_ref.mass[0]);
407
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 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 28 not taken.
✓ Branch 29 taken 1 times.
2 BOOST_CHECK(data.com[0].isApprox(data_ref.com[0]));
408
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.hg.isApprox(data_ref.hg));
409
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.dhg.isApprox(hgdot));
410
2/2
✓ Branch 0 taken 28 times.
✓ Branch 1 taken 1 times.
58 for (size_t k = 1; k < (size_t)model.njoints; ++k)
411 {
412
6/12
✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 28 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 28 times.
✗ Branch 20 not taken.
✗ Branch 24 not taken.
✓ Branch 25 taken 28 times.
56 BOOST_CHECK(data.mass[k] == data_ref.mass[k]);
413
7/14
✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 17 taken 28 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 28 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 28 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 28 times.
56 BOOST_CHECK(data.com[k].isApprox(data_ref.com[k]));
414
7/14
✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 17 taken 28 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 28 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 28 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 28 times.
56 BOOST_CHECK(data.v[k].isApprox(data_ref.v[k]));
415
7/14
✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 17 taken 28 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 28 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 28 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 28 times.
56 BOOST_CHECK(data.a[k].isApprox(data_ref.a_gf[k]));
416
7/14
✓ Branch 1 taken 28 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 28 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 28 times.
✗ Branch 12 not taken.
✓ Branch 17 taken 28 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 28 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 28 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 28 times.
56 BOOST_CHECK(data.f[k].isApprox(data_ref.f[k]));
417 }
418
419 // Check other signature
420
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 forwardKinematics(model, data_fk2, q, v, a);
421
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 computeCentroidalMomentumTimeVariation(model, data_fk2);
422
423
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_fk2.hg.isApprox(data.hg));
424
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_fk2.dhg.isApprox(data.dhg));
425
426 // Check against finite differences
427
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Data data_fd(model);
428 2 const double eps = 1e-8;
429
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::VectorXd v_plus = v + eps * a;
430
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 Eigen::VectorXd q_plus = integrate(model, q, eps * v);
431
432
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 const Force hg = computeCentroidalMomentum(model, data_fd, q, v);
433
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 const SE3::Vector3 com = data_fd.com[0];
434
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 const Force hg_plus = computeCentroidalMomentum(model, data_fd, q_plus, v_plus);
435
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 const SE3::Vector3 com_plus = data_fd.com[0];
436
437
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 SE3 transform(SE3::Identity());
438
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 transform.translation() = com_plus - com;
439
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 dhg_ref = (transform.act(hg_plus) - hg) / eps;
440
441
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.dhg.isApprox(dhg_ref, sqrt(eps)));
442 2 }
443
444 BOOST_AUTO_TEST_SUITE_END()
445