Directory: | ./ |
---|---|
File: | unittest/rotation.cpp |
Date: | 2025-02-12 21:03:38 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 28 | 28 | 100.0% |
Branches: | 126 | 246 | 51.2% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // | ||
2 | // Copyright (c) 2019-2020 INRIA | ||
3 | // | ||
4 | |||
5 | #include <iostream> | ||
6 | |||
7 | #include <pinocchio/math/rotation.hpp> | ||
8 | #include <pinocchio/math/sincos.hpp> | ||
9 | #include <Eigen/Geometry> | ||
10 | |||
11 | #include <boost/variant.hpp> // to avoid C99 warnings | ||
12 | |||
13 | #include <boost/test/unit_test.hpp> | ||
14 | #include <boost/utility/binary.hpp> | ||
15 | |||
16 | BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) | ||
17 | |||
18 |
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_toRotationMatrix) |
19 | { | ||
20 | using namespace pinocchio; | ||
21 | #ifndef NDEBUG | ||
22 | 2 | const int max_tests = 1e5; | |
23 | #else | ||
24 | const int max_tests = 1e2; | ||
25 | #endif | ||
26 |
2/2✓ Branch 0 taken 100000 times.
✓ Branch 1 taken 1 times.
|
200002 | for (int k = 0; k < max_tests; ++k) |
27 | { | ||
28 | 200000 | const double theta = std::rand(); | |
29 | double cos_value, sin_value; | ||
30 | |||
31 | 200000 | pinocchio::SINCOS(theta, &sin_value, &cos_value); | |
32 |
2/4✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 100000 times.
✗ Branch 5 not taken.
|
200000 | const Eigen::Vector3d axis(Eigen::Vector3d::Random().normalized()); |
33 | |||
34 |
1/2✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
|
200000 | Eigen::Matrix3d rot; |
35 |
1/2✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
|
200000 | toRotationMatrix(axis, cos_value, sin_value, rot); |
36 |
1/2✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
|
200000 | Eigen::Matrix3d rot2; |
37 |
1/2✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
|
200000 | toRotationMatrix(axis, theta, rot2); |
38 | |||
39 |
2/4✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 100000 times.
✗ Branch 5 not taken.
|
200000 | const Eigen::Matrix3d rot_ref = Eigen::AngleAxisd(theta, axis).toRotationMatrix(); |
40 | |||
41 |
7/14✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 100000 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 100000 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 100000 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 100000 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 100000 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 100000 times.
|
200000 | BOOST_CHECK(rot.isApprox(rot_ref)); |
42 |
7/14✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 100000 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 100000 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 100000 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 100000 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 100000 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 100000 times.
|
200000 | BOOST_CHECK(rot2.isApprox(rot_ref)); |
43 | } | ||
44 | 2 | } | |
45 | |||
46 |
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_orthogonal_projection) |
47 | { | ||
48 | using namespace pinocchio; | ||
49 | #ifndef NDEBUG | ||
50 | 2 | const int max_tests = 1e5; | |
51 | #else | ||
52 | const int max_tests = 1e2; | ||
53 | #endif | ||
54 | |||
55 | typedef Eigen::Vector4d Vector4; | ||
56 | typedef Eigen::Quaterniond Quaternion; | ||
57 | typedef Eigen::Matrix3d Matrix3; | ||
58 | |||
59 |
2/2✓ Branch 0 taken 100000 times.
✓ Branch 1 taken 1 times.
|
200002 | for (int k = 0; k < max_tests; ++k) |
60 | { | ||
61 |
2/4✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 100000 times.
✗ Branch 5 not taken.
|
200000 | const Vector4 vec4 = Vector4::Random(); |
62 |
2/4✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 100000 times.
✗ Branch 5 not taken.
|
200000 | const Quaternion quat(vec4.normalized()); |
63 | |||
64 |
1/2✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
|
200000 | const Matrix3 rot = quat.toRotationMatrix(); |
65 | |||
66 |
1/2✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
|
200000 | Matrix3 rot_proj = orthogonalProjection(rot); |
67 |
7/14✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 100000 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 100000 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 100000 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 100000 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 100000 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 100000 times.
|
200000 | BOOST_CHECK(rot.isApprox(rot_proj)); |
68 | } | ||
69 | |||
70 |
2/2✓ Branch 0 taken 100000 times.
✓ Branch 1 taken 1 times.
|
200002 | for (int k = 0; k < max_tests; ++k) |
71 | { | ||
72 |
2/4✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 100000 times.
✗ Branch 5 not taken.
|
200000 | const Matrix3 mat = Matrix3::Random(); |
73 | |||
74 |
1/2✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
|
200000 | Matrix3 rot_proj = orthogonalProjection(mat); |
75 |
9/18✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 100000 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 100000 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 100000 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 100000 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 100000 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 100000 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 100000 times.
✗ Branch 28 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 100000 times.
|
200000 | BOOST_CHECK((rot_proj.transpose() * rot_proj).isIdentity()); |
76 |
7/14✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 100000 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 100000 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 100000 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 100000 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 100000 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 100000 times.
|
200000 | BOOST_CHECK(fabs(rot_proj.determinant() - 1.) <= Eigen::NumTraits<double>::dummy_precision()); |
77 | } | ||
78 | 2 | } | |
79 | |||
80 | BOOST_AUTO_TEST_SUITE_END() | ||
81 |