Directory: | ./ |
---|---|
File: | unittest/coulomb-friction-cone.cpp |
Date: | 2025-02-12 21:03:38 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 36 | 36 | 100.0% |
Branches: | 207 | 404 | 51.2% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // | ||
2 | // Copyright (c) 2022 INRIA | ||
3 | // | ||
4 | |||
5 | #include <iostream> | ||
6 | #include "pinocchio/algorithm/constraints/coulomb-friction-cone.hpp" | ||
7 | |||
8 | #include <boost/test/unit_test.hpp> | ||
9 | #include <boost/utility/binary.hpp> | ||
10 | |||
11 | using namespace pinocchio; | ||
12 | |||
13 | BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) | ||
14 | |||
15 |
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_proj) |
16 | { | ||
17 | 2 | const int num_tests = int(1e5); | |
18 | 2 | const double mu = .4; | |
19 | |||
20 | 2 | const CoulombFrictionCone cone(mu); | |
21 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | const DualCoulombFrictionCone dual_cone = cone.dual(); |
22 | |||
23 |
8/16✓ 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 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(cone.isInside(Eigen::Vector3d::Zero())); |
24 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 1 times.
✗ Branch 30 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 1 times.
|
2 | BOOST_CHECK(cone.project(Eigen::Vector3d::Zero()) == Eigen::Vector3d::Zero()); |
25 | |||
26 |
8/16✓ 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 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(dual_cone.isInside(Eigen::Vector3d::Zero())); |
27 |
10/20✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 1 times.
✗ Branch 30 not taken.
✗ Branch 34 not taken.
✓ Branch 35 taken 1 times.
|
2 | BOOST_CHECK(dual_cone.project(Eigen::Vector3d::Zero()) == Eigen::Vector3d::Zero()); |
28 | |||
29 |
2/2✓ Branch 0 taken 100000 times.
✓ Branch 1 taken 1 times.
|
200002 | for (int k = 0; k < num_tests; ++k) |
30 | { | ||
31 |
2/4✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 100000 times.
✗ Branch 5 not taken.
|
200000 | const Eigen::Vector3d x = Eigen::Vector3d::Random(); |
32 | |||
33 | // Cone | ||
34 |
1/2✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
|
200000 | const Eigen::Vector3d proj_x = cone.project(x); |
35 |
1/2✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
|
200000 | const Eigen::Vector3d proj_proj_x = cone.project(proj_x); |
36 | |||
37 |
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 17 taken 100000 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 100000 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 100000 times.
|
200000 | BOOST_CHECK(cone.isInside(proj_x, 1e-12)); |
38 |
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 17 taken 100000 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 100000 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 100000 times.
|
200000 | BOOST_CHECK(cone.isInside(proj_proj_x, 1e-12)); |
39 |
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(proj_x.isApprox(proj_proj_x)); |
40 |
3/4✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 2107 times.
✓ Branch 4 taken 97893 times.
|
200000 | if (cone.isInside(x)) |
41 |
7/14✓ Branch 1 taken 2107 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 2107 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 2107 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 2107 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 2107 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 2107 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 2107 times.
|
4214 | BOOST_CHECK(x == proj_x); |
42 | |||
43 |
8/16✓ 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 20 taken 100000 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 100000 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 100000 times.
|
200000 | BOOST_CHECK(fabs((x - proj_x).dot(proj_x)) <= 1e-12); // orthogonal projection |
44 | |||
45 | // Dual cone | ||
46 |
1/2✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
|
200000 | const Eigen::Vector3d dual_proj_x = dual_cone.project(x); |
47 |
1/2✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
|
200000 | const Eigen::Vector3d dual_proj_proj_x = dual_cone.project(dual_proj_x); |
48 | |||
49 |
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 17 taken 100000 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 100000 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 100000 times.
|
200000 | BOOST_CHECK(dual_cone.isInside(dual_proj_x, 1e-12)); |
50 |
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 17 taken 100000 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 100000 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 100000 times.
|
200000 | BOOST_CHECK(dual_cone.isInside(dual_proj_proj_x, 1e-12)); |
51 |
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(dual_proj_x.isApprox(dual_proj_proj_x)); |
52 | |||
53 |
3/4✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 34935 times.
✓ Branch 4 taken 65065 times.
|
200000 | if (dual_cone.isInside(x)) |
54 |
7/14✓ Branch 1 taken 34935 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 34935 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 34935 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 34935 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 34935 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 34935 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 34935 times.
|
69870 | BOOST_CHECK(x == dual_proj_x); |
55 | |||
56 |
8/16✓ 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 20 taken 100000 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 100000 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 100000 times.
|
200000 | BOOST_CHECK(fabs((x - dual_proj_x).dot(dual_proj_x)) <= 1e-12); // orthogonal projection |
57 | |||
58 | // Radial projection | ||
59 | { | ||
60 |
1/2✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
|
200000 | const Eigen::Vector3d radial_proj_x = cone.computeRadialProjection(x); |
61 |
1/2✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
|
200000 | const Eigen::Vector3d radial_proj_radial_proj_x = cone.computeRadialProjection(radial_proj_x); |
62 |
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 17 taken 100000 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 100000 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 100000 times.
|
200000 | BOOST_CHECK(cone.isInside(radial_proj_x, 1e-12)); |
63 |
12/22✓ 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 19 taken 49847 times.
✓ Branch 20 taken 50153 times.
✓ Branch 22 taken 49847 times.
✗ Branch 23 not taken.
✓ Branch 24 taken 49847 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 100000 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 100000 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 100000 times.
|
200000 | BOOST_CHECK(radial_proj_x[2] == x[2] || radial_proj_x[2] == 0.); |
64 |
4/6✓ Branch 1 taken 100000 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 100000 times.
✗ Branch 5 not taken.
✓ Branch 6 taken 50153 times.
✓ Branch 7 taken 49847 times.
|
200000 | if (radial_proj_x[2] == x[2]) |
65 |
11/22✓ Branch 1 taken 50153 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 50153 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 50153 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 50153 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 50153 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 50153 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 50153 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 50153 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 50153 times.
✗ Branch 30 not taken.
✓ Branch 32 taken 50153 times.
✗ Branch 33 not taken.
✗ Branch 37 not taken.
✓ Branch 38 taken 50153 times.
|
100306 | BOOST_CHECK( |
66 | std::fabs(radial_proj_x.head<2>().normalized().dot(x.head<2>().normalized()) - 1.) | ||
67 | <= 1e-6); | ||
68 | else | ||
69 |
8/16✓ Branch 1 taken 49847 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 49847 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 49847 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 49847 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 49847 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 49847 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 49847 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 49847 times.
|
99694 | BOOST_CHECK(radial_proj_x.head<2>().isZero()); |
70 |
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(radial_proj_radial_proj_x.isApprox(radial_proj_radial_proj_x)); |
71 | } | ||
72 | } | ||
73 | 2 | } | |
74 | |||
75 | BOOST_AUTO_TEST_SUITE_END() | ||
76 |