GCC Code Coverage Report


Directory: ./
File: tests/logarithm.cc
Date: 2025-05-05 12:19:30
Exec Total Coverage
Lines: 98 107 91.6%
Branches: 391 808 48.4%

Line Branch Exec Source
1 // Copyright (c) 2016, Joseph Mirabel
2 // Authors: Joseph Mirabel (joseph.mirabel@laas.fr)
3 //
4
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are
7 // met:
8 //
9 // 1. Redistributions of source code must retain the above copyright
10 // notice, this list of conditions and the following disclaimer.
11 //
12 // 2. Redistributions in binary form must reproduce the above copyright
13 // notice, this list of conditions and the following disclaimer in the
14 // documentation and/or other materials provided with the distribution.
15 //
16 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
17 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
18 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
19 // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
20 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
21 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
22 // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23 // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
24 // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
26 // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
27 // DAMAGE.
28
29 #define BOOST_TEST_MODULE hpp_constraints
30 #include <boost/test/included/unit_test.hpp>
31 #include <hpp/constraints/tools.hh>
32 #include <pinocchio/fwd.hpp>
33 #include <pinocchio/spatial/explog.hpp>
34 #include <pinocchio/spatial/motion.hpp>
35
36 using namespace hpp::constraints;
37
38 421 matrix3_t exponential(const vector3_t& aa) {
39
2/4
✓ Branch 1 taken 421 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 421 times.
✗ Branch 5 not taken.
421 matrix3_t R, xCross;
40
1/2
✓ Branch 1 taken 421 times.
✗ Branch 2 not taken.
421 xCross.setZero();
41
2/4
✓ Branch 1 taken 421 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 421 times.
✗ Branch 5 not taken.
421 xCross(1, 0) = +aa(2);
42
2/4
✓ Branch 1 taken 421 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 421 times.
✗ Branch 5 not taken.
421 xCross(0, 1) = -aa(2);
43
2/4
✓ Branch 1 taken 421 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 421 times.
✗ Branch 5 not taken.
421 xCross(2, 0) = -aa(1);
44
2/4
✓ Branch 1 taken 421 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 421 times.
✗ Branch 5 not taken.
421 xCross(0, 2) = +aa(1);
45
2/4
✓ Branch 1 taken 421 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 421 times.
✗ Branch 5 not taken.
421 xCross(2, 1) = +aa(0);
46
2/4
✓ Branch 1 taken 421 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 421 times.
✗ Branch 5 not taken.
421 xCross(1, 2) = -aa(0);
47
1/2
✓ Branch 1 taken 421 times.
✗ Branch 2 not taken.
421 R.setIdentity();
48
1/2
✓ Branch 1 taken 421 times.
✗ Branch 2 not taken.
421 value_type theta = aa.norm();
49
2/2
✓ Branch 0 taken 3 times.
✓ Branch 1 taken 418 times.
421 if (theta < 1e-6) {
50
1/2
✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
3 R += xCross;
51
4/8
✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 3 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 3 times.
✗ Branch 11 not taken.
3 R += 0.5 * xCross.transpose() * xCross;
52 } else {
53
2/4
✓ Branch 1 taken 418 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 418 times.
✗ Branch 5 not taken.
418 R += sin(theta) / theta * xCross;
54
3/6
✓ Branch 3 taken 418 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 418 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 418 times.
✗ Branch 10 not taken.
418 R += 2 * std::pow(sin(theta / 2), 2) / std::pow(theta, 2) * xCross * xCross;
55 }
56 842 return R;
57 }
58
59 21 vector3_t log(const matrix3_t R) {
60
1/2
✓ Branch 1 taken 21 times.
✗ Branch 2 not taken.
21 vector3_t log;
61 value_type theta;
62
1/2
✓ Branch 1 taken 21 times.
✗ Branch 2 not taken.
21 logSO3(R, theta, log);
63 42 return log;
64 }
65
66 21 bool check(const vector3_t& aa, const value_type eps = -1) {
67
2/4
✓ Branch 1 taken 21 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 21 times.
✗ Branch 5 not taken.
21 vector3_t res = log(exponential(aa));
68 bool ret;
69
2/2
✓ Branch 0 taken 16 times.
✓ Branch 1 taken 5 times.
21 if (eps < 0)
70
1/2
✓ Branch 2 taken 16 times.
✗ Branch 3 not taken.
16 ret = aa.isApprox(res);
71 else
72
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 ret = aa.isApprox(res, eps);
73
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 21 times.
21 if (!ret) {
74 std::cout << "x = " << aa << std::endl;
75 std::cout << "exp(x) = " << exponential(aa) << std::endl;
76 std::cout << "log(exp(x)) = " << res << std::endl;
77 std::cout << "(x - log(exp(x))) / norm(x) = "
78 << (aa - res).derived().transpose() / aa.norm() << std::endl;
79 std::cout << "eps = "
80 << (eps < 0 ? Eigen::NumTraits<value_type>::dummy_precision()
81 : eps)
82 << std::endl;
83 }
84 21 return ret;
85 }
86
87
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(logarithm) {
88 // Width of the domain considered as close to rotation of Pi. It should be the
89 // same as the value in the logarithm computation.
90 // When in this domain, the precision of the computation is done on the square
91 // of the angle axis. So we only have precision eps defined as follow.
92 2 const value_type dlUB = 1e-2;
93 2 const value_type eps = sqrt(Eigen::NumTraits<value_type>::epsilon());
94
95
7/14
✓ Branch 3 taken 1 times.
✗ Branch 4 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.
✓ 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(check(vector3_t(0, 0, 0)));
96
7/14
✓ Branch 3 taken 1 times.
✗ Branch 4 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.
✓ 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(check(vector3_t(1, 0, 0)));
97
7/14
✓ Branch 3 taken 1 times.
✗ Branch 4 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.
✓ 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(check(vector3_t(0, 1, 0)));
98
7/14
✓ Branch 3 taken 1 times.
✗ Branch 4 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.
✓ 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(check(vector3_t(0, 0, 1)));
99
7/14
✓ Branch 3 taken 1 times.
✗ Branch 4 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.
✓ 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(check(vector3_t(1, 1, 0)));
100
7/14
✓ Branch 3 taken 1 times.
✗ Branch 4 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.
✓ 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(check(vector3_t(0, 1, 1)));
101
7/14
✓ Branch 3 taken 1 times.
✗ Branch 4 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.
✓ 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(check(vector3_t(1, 0, 1)));
102
7/14
✓ Branch 3 taken 1 times.
✗ Branch 4 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.
✓ 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(check(vector3_t(1, 1, 1)));
103
104
9/18
✓ Branch 3 taken 1 times.
✗ Branch 4 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.
✓ 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(check(M_PI * vector3_t(1, 0, 0)));
105
9/18
✓ Branch 3 taken 1 times.
✗ Branch 4 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.
✓ 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(check(M_PI * vector3_t(0, 1, 0)));
106
9/18
✓ Branch 3 taken 1 times.
✗ Branch 4 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.
✓ 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(check(M_PI * vector3_t(0, 0, 1)));
107
9/18
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 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 33 not taken.
✓ Branch 34 taken 1 times.
2 BOOST_CHECK(check(M_PI / sqrt(2) * vector3_t(1, 1, 0)));
108
9/18
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 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 33 not taken.
✓ Branch 34 taken 1 times.
2 BOOST_CHECK(check(M_PI / sqrt(2) * vector3_t(0, 1, 1)));
109
9/18
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 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 33 not taken.
✓ Branch 34 taken 1 times.
2 BOOST_CHECK(check(M_PI / sqrt(2) * vector3_t(1, 0, 1)));
110
111
9/18
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 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 33 not taken.
✓ Branch 34 taken 1 times.
2 BOOST_CHECK(check(M_PI / sqrt(3) * vector3_t(1, -1, 1), eps));
112
9/18
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 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 33 not taken.
✓ Branch 34 taken 1 times.
2 BOOST_CHECK(check(M_PI / sqrt(3) * vector3_t(1, 1, 1), eps));
113
114
9/18
✓ Branch 3 taken 1 times.
✗ Branch 4 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.
✓ 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(check(1e-7 * vector3_t(1, 1, 1)));
115
9/18
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 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 33 not taken.
✓ Branch 34 taken 1 times.
2 BOOST_CHECK(check((M_PI - 0.1 * dlUB) / sqrt(3) * vector3_t(1, -1, 1), eps));
116
9/18
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 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 33 not taken.
✓ Branch 34 taken 1 times.
2 BOOST_CHECK(check((M_PI - 0.1 * dlUB) / sqrt(3) * vector3_t(1, 1, 1), eps));
117
118
9/18
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 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 33 not taken.
✓ Branch 34 taken 1 times.
2 BOOST_CHECK(check((M_PI - 1.001 * dlUB) / sqrt(3) * vector3_t(1, 1, 1), eps));
119
9/18
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 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 33 not taken.
✓ Branch 34 taken 1 times.
2 BOOST_CHECK(check((M_PI - 0.999 * dlUB) / sqrt(3) * vector3_t(1, 1, 1)));
120 2 }
121
122
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(Jlog_SO3) {
123 2 value_type lower(-1), upper(1);
124
2/2
✓ Branch 0 taken 100 times.
✓ Branch 1 taken 1 times.
202 for (size_type i = 0; i < 100; ++i) {
125 // Generate random rotation matrix
126
1/2
✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
200 vector3_t r0;
127
1/2
✓ Branch 2 taken 100 times.
✗ Branch 3 not taken.
200 r0[0] = lower + (upper - lower) * rand() / RAND_MAX;
128
1/2
✓ Branch 2 taken 100 times.
✗ Branch 3 not taken.
200 r0[1] = lower + (upper - lower) * rand() / RAND_MAX;
129
1/2
✓ Branch 2 taken 100 times.
✗ Branch 3 not taken.
200 r0[2] = lower + (upper - lower) * rand() / RAND_MAX;
130
1/2
✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
200 r0.normalize();
131
1/2
✓ Branch 2 taken 100 times.
✗ Branch 3 not taken.
200 r0 *= 3.14 * rand() / RAND_MAX;
132
3/4
✓ Branch 0 taken 1 times.
✓ Branch 1 taken 99 times.
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
200 if (i == 0) r0.setZero();
133
1/2
✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
200 matrix3_t R0(exponential(r0));
134
1/2
✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
200 vector3_t omega;
135 // \dot{R} = R0 [\omega]_{\times}
136 // R (dt) = R0 \exp (dt [\omega]_{\times})
137 200 value_type dt(1e-6);
138
2/2
✓ Branch 0 taken 300 times.
✓ Branch 1 taken 100 times.
800 for (size_type i = 0; i < 3; ++i) {
139
1/2
✓ Branch 1 taken 300 times.
✗ Branch 2 not taken.
600 omega.setZero();
140
1/2
✓ Branch 1 taken 300 times.
✗ Branch 2 not taken.
600 omega[i] = 1;
141
5/10
✓ Branch 1 taken 300 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 300 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 300 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 300 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 300 times.
✗ Branch 14 not taken.
600 matrix3_t R(R0 * exponential(dt * omega));
142 value_type theta;
143
1/2
✓ Branch 1 taken 300 times.
✗ Branch 2 not taken.
600 vector3_t r;
144
1/2
✓ Branch 1 taken 300 times.
✗ Branch 2 not taken.
600 logSO3(R, theta, r);
145
1/2
✓ Branch 1 taken 300 times.
✗ Branch 2 not taken.
600 matrix3_t Jlog;
146
1/2
✓ Branch 1 taken 300 times.
✗ Branch 2 not taken.
600 JlogSO3(theta, r, Jlog);
147
11/22
✓ Branch 1 taken 300 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 300 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 300 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 300 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 300 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 300 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 300 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 300 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 300 times.
✗ Branch 30 not taken.
✓ Branch 32 taken 300 times.
✗ Branch 33 not taken.
✗ Branch 37 not taken.
✓ Branch 38 taken 300 times.
600 BOOST_CHECK(((r - r0) / dt - Jlog * omega).squaredNorm() < 1e-8);
148 }
149 }
150 2 }
151
152
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(Jlog_SE3) {
153
2/2
✓ Branch 0 taken 100 times.
✓ Branch 1 taken 1 times.
202 for (size_type i = 0; i < 100; ++i) {
154 // Generate random rigid body motion
155
1/2
✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
200 Transform3s M0;
156
1/2
✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
200 M0.setRandom();
157
3/4
✓ Branch 0 taken 1 times.
✓ Branch 1 taken 99 times.
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
200 if (i == 0) M0.setIdentity();
158
2/4
✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 100 times.
✗ Branch 5 not taken.
200 vector6_t log0, log;
159 200 value_type dt(1e-6);
160
1/2
✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
200 logSE3(M0, log0);
161
1/2
✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
200 matrix6_t Jlog;
162
1/2
✓ Branch 1 taken 100 times.
✗ Branch 2 not taken.
200 JlogSE3(M0, Jlog);
163
2/2
✓ Branch 0 taken 600 times.
✓ Branch 1 taken 100 times.
1400 for (size_type i = 0; i < 6; ++i) {
164
1/2
✓ Branch 1 taken 600 times.
✗ Branch 2 not taken.
1200 vector6_t v;
165
1/2
✓ Branch 1 taken 600 times.
✗ Branch 2 not taken.
1200 v.setZero();
166
1/2
✓ Branch 1 taken 600 times.
✗ Branch 2 not taken.
1200 v[i] = 1;
167
1/2
✓ Branch 1 taken 600 times.
✗ Branch 2 not taken.
1200 ::pinocchio::Motion nu(v);
168
3/6
✓ Branch 1 taken 600 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 600 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 600 times.
✗ Branch 8 not taken.
1200 Transform3s M(M0 * ::pinocchio::exp6(dt * nu));
169
1/2
✓ Branch 1 taken 600 times.
✗ Branch 2 not taken.
1200 logSE3(M, log);
170
5/10
✓ Branch 1 taken 600 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 600 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 600 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 600 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 600 times.
✗ Branch 14 not taken.
1200 std::cout << "(log-log0)/dt=" << ((log - log0) / dt).transpose()
171
1/2
✓ Branch 1 taken 600 times.
✗ Branch 2 not taken.
1200 << std::endl;
172
5/10
✓ Branch 1 taken 600 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 600 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 600 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 600 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 600 times.
✗ Branch 14 not taken.
1200 std::cout << "Jlog * v= " << (Jlog * v).transpose() << std::endl;
173
11/22
✓ Branch 1 taken 600 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 600 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 600 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 600 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 600 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 600 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 600 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 600 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 600 times.
✗ Branch 30 not taken.
✓ Branch 32 taken 600 times.
✗ Branch 33 not taken.
✗ Branch 37 not taken.
✓ Branch 38 taken 600 times.
1200 BOOST_CHECK(((log - log0) / dt - Jlog * v).squaredNorm() < 1e-8);
174 }
175 }
176 2 }
177