GCC Code Coverage Report


Directory: ./
File: tests/solver-hierarchical-iterative.cc
Date: 2025-05-05 12:19:30
Exec Total Coverage
Lines: 162 165 98.2%
Branches: 706 1424 49.6%

Line Branch Exec Source
1 // Copyright (c) 2017, 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 HIERARCHICAL_ITERATIVE_SOLVER
30 #include <../tests/util.hh>
31 #include <boost/make_shared.hpp>
32 #include <boost/test/unit_test.hpp>
33 #include <functional>
34 #include <hpp/constraints/affine-function.hh>
35 #include <hpp/constraints/generic-transformation.hh>
36 #include <hpp/constraints/implicit.hh>
37 #include <hpp/constraints/solver/hierarchical-iterative.hh>
38 #include <hpp/pinocchio/configuration.hh>
39 #include <hpp/pinocchio/device.hh>
40 #include <hpp/pinocchio/joint.hh>
41 #include <hpp/pinocchio/liegroup-space.hh>
42 #include <hpp/pinocchio/simple-device.hh>
43 #include <pinocchio/algorithm/joint-configuration.hpp>
44
45 using namespace hpp::constraints;
46 namespace saturation = hpp::constraints::solver::saturation;
47
48 const value_type test_precision = 1e-5;
49
50 #define VECTOR2(x0, x1) ((hpp::constraints::vector_t(2) << x0, x1).finished())
51
52 using Eigen::VectorXi;
53 using hpp::pinocchio::LiegroupSpace;
54
55 template <typename LineSearch>
56 struct test_base {
57 solver::HierarchicalIterative solver;
58 LineSearch ls;
59
60
2/4
✓ Branch 2 taken 6 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 2 times.
✗ Branch 7 not taken.
12 test_base(const size_type& d) : solver(LiegroupSpace::Rn(d)) {
61 12 solver.maxIterations(20);
62 12 solver.errorThreshold(test_precision);
63
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.
12 solver.saturation(hpp::make_shared<saturation::Bounds>(vector_t::Zero(2),
64 vector_t::Ones(2)));
65 12 }
66
67 50 vector_t success(value_type x0, value_type x1) {
68
4/8
✓ Branch 1 taken 25 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 25 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 25 times.
✗ Branch 8 not taken.
✓ Branch 11 taken 25 times.
✗ Branch 12 not taken.
100 vector_t x(VECTOR2(x0, x1));
69
7/14
✓ Branch 1 taken 25 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 25 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 25 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 25 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 25 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 25 times.
✗ Branch 20 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 25 times.
50 BOOST_CHECK_EQUAL(solver.solve(x, ls),
70 solver::HierarchicalIterative::SUCCESS);
71 50 return x;
72 }
73
74 1 vector_t failure(value_type x0, value_type x1) {
75
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 11 taken 1 times.
✗ Branch 12 not taken.
2 vector_t x(VECTOR2(x0, x1));
76
7/14
✓ 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 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 24 not taken.
✓ Branch 25 taken 1 times.
1 BOOST_CHECK_PREDICATE(
77 std::not_equal_to<solver::HierarchicalIterative::Status>(),
78 (solver.solve(x, ls))(solver::HierarchicalIterative::SUCCESS));
79 1 return x;
80 }
81 };
82
83 template <typename LineSearch = solver::lineSearch::Constant>
84 struct test_quadratic : test_base<LineSearch> {
85
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
10 test_quadratic(const matrix_t& A) : test_base<LineSearch>(A.cols()) {
86 // Find (x, y)
87 // s.t. a * x^2 + b * y^2 - 1 = 0
88 // 0 <= x <= 1
89 // 0 <= y <= 1
90
5/10
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 5 times.
✗ Branch 6 not taken.
✓ Branch 12 taken 5 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 5 times.
✗ Branch 16 not taken.
✗ Branch 19 not taken.
✓ Branch 20 taken 5 times.
10 BOOST_REQUIRE_EQUAL(A.rows(), A.cols());
91
5/10
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 5 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 5 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 5 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 5 times.
✗ Branch 16 not taken.
10 BOOST_TEST_MESSAGE(A);
92
3/6
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 5 times.
✗ Branch 8 not taken.
10 Quadratic::Ptr_t f(new Quadratic(A, -1));
93
94
2/4
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 5 times.
✗ Branch 6 not taken.
10 this->solver.add(
95 Implicit::create(
96
1/2
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
20 f, ComparisonTypes_t(f->outputDerivativeSize(), Equality)),
97 20 0);
98
6/12
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 5 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 5 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 5 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 5 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 5 times.
10 BOOST_CHECK(this->solver.numberStacks() == 1);
99 10 }
100 };
101
102
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(quadratic) {
103
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 matrix_t A(2, 2);
104
105
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 A << 1, 0, 0, 1;
106
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 test_quadratic<> test(A);
107
9/18
✓ 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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✗ Branch 33 not taken.
✓ Branch 34 taken 1 times.
2 BOOST_CHECK_EQUAL(test.failure(0, 0), VECTOR2(0, 0));
108
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 test.success(0.1, 0);
109
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 test.success(0, 0.1);
110
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 test.success(0.5, 0.5);
111
112
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 A << 2, 0, 0, 2;
113
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 test = test_quadratic<>(A);
114
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 test.success(0.1, 0);
115
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 test.success(0, 0.1);
116
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 test.success(0.5, 0.5);
117
118
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 A << 0.5, 0, 0, 0.5;
119
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 test = test_quadratic<>(A);
120 // This is exact because of the saturation
121
9/18
✓ 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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✗ Branch 33 not taken.
✓ Branch 34 taken 1 times.
2 BOOST_CHECK_EQUAL(test.success(1, 0.001),
122 VECTOR2(1, 1)); // Slide on the border x = 1
123
9/18
✓ 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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✗ Branch 33 not taken.
✓ Branch 34 taken 1 times.
2 BOOST_CHECK_EQUAL(test.success(0.001, 1),
124 VECTOR2(1, 1)); // Slide on the border y = 1
125
126
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 A << 0.75, 0, 0, 0.75;
127
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 test_quadratic<solver::lineSearch::FixedSequence> test4(A);
128 // This is not exact because the solver does not saturate.
129
21/42
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 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.
✓ 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 32 taken 1 times.
✗ Branch 33 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 39 taken 1 times.
✗ Branch 40 not taken.
✓ Branch 42 taken 1 times.
✗ Branch 43 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 51 taken 1 times.
✗ Branch 52 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 59 taken 1 times.
✗ Branch 60 not taken.
✓ Branch 62 taken 1 times.
✗ Branch 63 not taken.
✓ Branch 65 taken 1 times.
✗ Branch 66 not taken.
✗ Branch 80 not taken.
✓ Branch 81 taken 1 times.
2 EIGEN_VECTOR_IS_APPROX(
130 test4.success(1, 0.1),
131 VECTOR2(1., 1 / sqrt(3))); // Slide on the border x = 1
132
21/42
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 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.
✓ 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 29 taken 1 times.
✗ Branch 30 not taken.
✓ Branch 32 taken 1 times.
✗ Branch 33 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 39 taken 1 times.
✗ Branch 40 not taken.
✓ Branch 42 taken 1 times.
✗ Branch 43 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 59 taken 1 times.
✗ Branch 60 not taken.
✓ Branch 62 taken 1 times.
✗ Branch 63 not taken.
✓ Branch 65 taken 1 times.
✗ Branch 66 not taken.
✗ Branch 80 not taken.
✓ Branch 81 taken 1 times.
2 EIGEN_VECTOR_IS_APPROX(
133 test4.success(0.1, 1),
134 VECTOR2(1 / sqrt(3), 1.)); // Slide on the border y = 1
135 // There is an overshoot. To overcome this, the Hessian of the function should
136 // be obtained.
137
21/42
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 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.
✓ 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 32 taken 1 times.
✗ Branch 33 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 39 taken 1 times.
✗ Branch 40 not taken.
✓ Branch 42 taken 1 times.
✗ Branch 43 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 51 taken 1 times.
✗ Branch 52 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 59 taken 1 times.
✗ Branch 60 not taken.
✓ Branch 62 taken 1 times.
✗ Branch 63 not taken.
✓ Branch 65 taken 1 times.
✗ Branch 66 not taken.
✗ Branch 80 not taken.
✓ Branch 81 taken 1 times.
2 EIGEN_VECTOR_IS_NOT_APPROX(
138 test4.success(1, 0.001),
139 VECTOR2(1., 1 / sqrt(3))); // Slide on the border x = 1
140
21/42
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 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.
✓ 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 29 taken 1 times.
✗ Branch 30 not taken.
✓ Branch 32 taken 1 times.
✗ Branch 33 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 39 taken 1 times.
✗ Branch 40 not taken.
✓ Branch 42 taken 1 times.
✗ Branch 43 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 59 taken 1 times.
✗ Branch 60 not taken.
✓ Branch 62 taken 1 times.
✗ Branch 63 not taken.
✓ Branch 65 taken 1 times.
✗ Branch 66 not taken.
✗ Branch 80 not taken.
✓ Branch 81 taken 1 times.
2 EIGEN_VECTOR_IS_NOT_APPROX(
141 test4.success(0.001, 1),
142 VECTOR2(1 / sqrt(3), 1.)); // Slide on the border y = 1
143
144 // Ellipsoid: computations are approximative
145
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 A << 0.5, 0, 0, 2;
146
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 test_quadratic<solver::lineSearch::FixedSequence> test1(A);
147
9/18
✓ 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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1 times.
✗ Branch 27 not taken.
✗ Branch 33 not taken.
✓ Branch 34 taken 1 times.
2 BOOST_CHECK_EQUAL(test1.success(1, 0.5),
148 VECTOR2(1., 0.5)); // Slide on the border x = 1
149
21/42
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 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.
✓ 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 35 taken 1 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 1 times.
✗ Branch 39 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 44 taken 1 times.
✗ Branch 45 not taken.
✓ Branch 47 taken 1 times.
✗ Branch 48 not taken.
✓ Branch 50 taken 1 times.
✗ Branch 51 not taken.
✓ Branch 53 taken 1 times.
✗ Branch 54 not taken.
✓ Branch 57 taken 1 times.
✗ Branch 58 not taken.
✓ Branch 60 taken 1 times.
✗ Branch 61 not taken.
✓ Branch 63 taken 1 times.
✗ Branch 64 not taken.
✗ Branch 78 not taken.
✓ Branch 79 taken 1 times.
2 EIGEN_VECTOR_IS_APPROX(test1.success(1, 0.1),
150 VECTOR2(1., 0.5)); // Slide on the border x = 1
151
21/42
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 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.
✓ 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 32 taken 1 times.
✗ Branch 33 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 39 taken 1 times.
✗ Branch 40 not taken.
✓ Branch 42 taken 1 times.
✗ Branch 43 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 51 taken 1 times.
✗ Branch 52 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 59 taken 1 times.
✗ Branch 60 not taken.
✓ Branch 62 taken 1 times.
✗ Branch 63 not taken.
✓ Branch 65 taken 1 times.
✗ Branch 66 not taken.
✗ Branch 80 not taken.
✓ Branch 81 taken 1 times.
2 EIGEN_VECTOR_IS_APPROX(test1.success(0, 1), VECTOR2(0., 1 / sqrt(2)));
152 2 }
153
154
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(one_layer) {
155 DevicePtr_t device = hpp::pinocchio::unittest::makeDevice(
156
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
4 hpp::pinocchio::unittest::HumanoidSimple);
157
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 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
2 BOOST_REQUIRE(device);
158
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
2 device->rootJoint()->lowerBound(0, -1);
159
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
2 device->rootJoint()->lowerBound(1, -1);
160
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
2 device->rootJoint()->lowerBound(2, -1);
161
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
2 device->rootJoint()->upperBound(0, 1);
162
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
2 device->rootJoint()->upperBound(1, 1);
163
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
2 device->rootJoint()->upperBound(2, 1);
164
2/4
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
4 JointPtr_t ee1 = device->getJointByName("lleg5_joint"),
165
2/4
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
4 ee2 = device->getJointByName("rleg5_joint");
166
167
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 Configuration_t q = device->currentConfiguration(),
168
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 qrand = ::pinocchio::randomConfiguration(device->model());
169
170
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 solver::HierarchicalIterative solver(device->configSpace());
171 2 solver.maxIterations(20);
172 2 solver.errorThreshold(1e-3);
173
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 solver.saturation(hpp::make_shared<solver::saturation::Device>(device));
174
175
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 device->currentConfiguration(q);
176
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 device->computeForwardKinematics(hpp::pinocchio::JOINT_POSITION);
177
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 Transform3s tf1(ee1->currentTransformation());
178
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 Transform3s tf2(ee2->currentTransformation());
179
180 ImplicitPtr_t constraint(Implicit::create(
181
5/10
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
4 Orientation::create("Orientation", device, ee2, tf2), 3 * Equality));
182
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 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(constraint->comparisonType() == 3 * Equality);
183
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 solver.add(constraint, 0);
184
5/10
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
8 constraint = Implicit::create(Position::create("Position", device, ee2, tf2),
185 6 3 * Equality);
186
7/14
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 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(constraint->comparisonType() == 3 * Equality);
187
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 solver.add(constraint, 0);
188
189
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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
2 BOOST_CHECK(solver.numberStacks() == 1);
190
191
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 29 not taken.
✓ Branch 30 taken 1 times.
2 BOOST_CHECK(solver.isSatisfied(q));
192
193
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 Configuration_t tmp = qrand;
194
8/16
✓ 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 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
2 BOOST_CHECK_EQUAL(solver.solve<solver::lineSearch::Backtracking>(qrand),
195 solver::HierarchicalIterative::SUCCESS);
196
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 qrand = tmp;
197
8/16
✓ 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 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
2 BOOST_CHECK_EQUAL(solver.solve<solver::lineSearch::ErrorNormBased>(qrand),
198 solver::HierarchicalIterative::SUCCESS);
199
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 qrand = tmp;
200
8/16
✓ 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 22 taken 1 times.
✗ Branch 23 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
2 BOOST_CHECK_EQUAL(solver.solve<solver::lineSearch::FixedSequence>(qrand),
201 solver::HierarchicalIterative::SUCCESS);
202 2 }
203
204 template <typename LineSearch = solver::lineSearch::Constant>
205 struct test_affine_opt : test_base<LineSearch> {
206 1 test_affine_opt(const matrix_t& A, const matrix_t& B)
207
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
1 : test_base<LineSearch>(A.cols()) {
208 // min X^T * B * X
209 // s.t. A * X - 1 = 0
210 // 0 <= X <= 1
211
5/10
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✗ Branch 19 not taken.
✓ Branch 20 taken 1 times.
1 BOOST_REQUIRE_EQUAL(A.cols(), B.cols());
212
5/10
✓ 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 18 not taken.
✓ Branch 19 taken 1 times.
1 BOOST_REQUIRE_EQUAL(A.rows(), 1);
213
5/10
✓ 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.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
1 BOOST_TEST_MESSAGE(A);
214
5/10
✓ 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.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
1 BOOST_TEST_MESSAGE(B);
215
5/10
✓ 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.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
2 AffineFunctionPtr_t f(AffineFunction::create(A, vector_t::Constant(1, -1)));
216
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.
1 Quadratic::Ptr_t cost(new Quadratic(B));
217
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
3 ImplicitPtr_t f_constraint(Implicit::create(
218
1/2
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 f, ComparisonTypes_t(f->outputDerivativeSize(), Equality)));
219
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
3 ImplicitPtr_t cost_constraint(Implicit::create(
220
1/2
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 cost, ComparisonTypes_t(f->outputDerivativeSize(), Equality)));
221
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 this->solver.add(f_constraint, 0);
222
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
1 this->solver.add(cost_constraint, 1);
223 // this->solver.add(cost, 0);
224 1 this->solver.lastIsOptional(true);
225
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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 1 times.
1 BOOST_CHECK(this->solver.numberStacks() == 2);
226 1 }
227
228 6 vector_t optimize(value_type x0, value_type x1) {
229
4/8
✓ 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 11 taken 6 times.
✗ Branch 12 not taken.
12 vector_t x(VECTOR2(x0, x1));
230 6 this->solver.lastIsOptional(false);
231
2/4
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 6 times.
✗ Branch 5 not taken.
6 this->solver.solve(x, this->ls);
232 6 this->solver.lastIsOptional(true);
233 6 return x;
234 }
235 };
236
237
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(affine_opt) {
238
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 matrix_t A(1, 2);
239
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 A << 1, 1;
240
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 matrix_t B(2, 2);
241
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 B << 1, 0, 0, 1;
242
243
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 test_affine_opt<> test(A, B);
244
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 test.success(0, 0);
245
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 test.success(0.1, 0);
246
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 test.success(0, 0.1);
247
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 test.success(0.5, 0.5);
248
249
21/42
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 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.
✓ 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 35 taken 1 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 1 times.
✗ Branch 39 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 44 taken 1 times.
✗ Branch 45 not taken.
✓ Branch 47 taken 1 times.
✗ Branch 48 not taken.
✓ Branch 50 taken 1 times.
✗ Branch 51 not taken.
✓ Branch 53 taken 1 times.
✗ Branch 54 not taken.
✓ Branch 57 taken 1 times.
✗ Branch 58 not taken.
✓ Branch 60 taken 1 times.
✗ Branch 61 not taken.
✓ Branch 63 taken 1 times.
✗ Branch 64 not taken.
✗ Branch 78 not taken.
✓ Branch 79 taken 1 times.
2 EIGEN_VECTOR_IS_APPROX(test.optimize(0.1, 0), VECTOR2(0.5, 0.5));
250
21/42
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 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.
✓ 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 35 taken 1 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 1 times.
✗ Branch 39 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 44 taken 1 times.
✗ Branch 45 not taken.
✓ Branch 47 taken 1 times.
✗ Branch 48 not taken.
✓ Branch 50 taken 1 times.
✗ Branch 51 not taken.
✓ Branch 53 taken 1 times.
✗ Branch 54 not taken.
✓ Branch 57 taken 1 times.
✗ Branch 58 not taken.
✓ Branch 60 taken 1 times.
✗ Branch 61 not taken.
✓ Branch 63 taken 1 times.
✗ Branch 64 not taken.
✗ Branch 78 not taken.
✓ Branch 79 taken 1 times.
2 EIGEN_VECTOR_IS_APPROX(test.optimize(0, 0.1), VECTOR2(0.5, 0.5));
251
21/42
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 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.
✓ 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 35 taken 1 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 1 times.
✗ Branch 39 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 44 taken 1 times.
✗ Branch 45 not taken.
✓ Branch 47 taken 1 times.
✗ Branch 48 not taken.
✓ Branch 50 taken 1 times.
✗ Branch 51 not taken.
✓ Branch 53 taken 1 times.
✗ Branch 54 not taken.
✓ Branch 57 taken 1 times.
✗ Branch 58 not taken.
✓ Branch 60 taken 1 times.
✗ Branch 61 not taken.
✓ Branch 63 taken 1 times.
✗ Branch 64 not taken.
✗ Branch 78 not taken.
✓ Branch 79 taken 1 times.
2 EIGEN_VECTOR_IS_APPROX(test.optimize(0.5, 0.5), VECTOR2(0.5, 0.5));
252 2 }
253
254 // build an implicit constraint with values in SE3 and with non trivial mask
255
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(mask) {
256 struct Identity : public DifferentiableFunction {
257 2 static DifferentiableFunctionPtr_t create() {
258
1/2
✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
2 return DifferentiableFunctionPtr_t(new Identity());
259 }
260
2/4
✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 2 times.
✗ Branch 6 not taken.
2 Identity() : DifferentiableFunction(7, 6, LiegroupSpace::R3xSO3()) {}
261 4 virtual void impl_compute(LiegroupElementRef result,
262 vectorIn_t argument) const {
263 4 result.vector() = argument;
264 }
265
266 virtual void impl_jacobian(matrixOut_t jacobian, vectorIn_t) const {
267 jacobian.setIdentity();
268 }
269
270 14 bool isEqual(const DifferentiableFunction& other) const {
271
1/2
✓ Branch 0 taken 14 times.
✗ Branch 1 not taken.
14 dynamic_cast<const Identity&>(other);
272
1/2
✗ Branch 1 not taken.
✓ Branch 2 taken 14 times.
14 if (!DifferentiableFunction::isEqual(other)) return false;
273
274 14 return true;
275 }
276 }; // class Identity
277
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 solver::HierarchicalIterative solver(LiegroupSpace::R3xSO3());
278 2 solver.maxIterations(20);
279 2 solver.errorThreshold(1e-10);
280
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 std::vector<bool> mask{true, true, false, false, false, true};
281
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.
4 ImplicitPtr_t c1(Implicit::create(Identity::create(), 6 * Equality, mask));
282
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.
4 ImplicitPtr_t c2(Implicit::create(Identity::create(), 6 * Equality, mask));
283
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 solver.add(c1, 0);
284 try {
285
1/2
✗ Branch 1 not taken.
✓ Branch 2 taken 1 times.
2 solver.add(c2, 0);
286 BOOST_CHECK(false);
287
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 1 times.
2 } catch (const std::logic_error& err) {
288
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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✗ Branch 36 not taken.
✓ Branch 37 taken 1 times.
2 BOOST_CHECK(std::string(err.what()) ==
289 std::string("Contraint \"\" already in solver"));
290 2 }
291
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 vector_t q(7);
292
7/14
✓ 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.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
2 q << 1, 2, 3, .5, .5, .5, .5;
293
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 solver.rightHandSideFromConfig(q);
294 bool found;
295
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 vector_t error(6);
296
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 std::cout << "q=" << q.transpose() << std::endl;
297
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 29 not taken.
✓ Branch 30 taken 1 times.
2 BOOST_CHECK(solver.isSatisfied(q));
298
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 32 not taken.
✓ Branch 33 taken 1 times.
2 BOOST_CHECK(solver.isConstraintSatisfied(c1, q, error, found));
299
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 std::cout << "error=" << error.transpose() << std::endl;
300
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 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
2 BOOST_CHECK(found);
301
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(error.norm() < 1e-10);
302
2/4
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
2 std::cout << solver << std::endl;
303
7/14
✓ 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.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
2 q << 0, 0, 0, 0, 0, 0, 1;
304
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 std::cout << "q=" << q.transpose() << std::endl;
305
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 32 not taken.
✓ Branch 33 taken 1 times.
2 BOOST_CHECK(!solver.isConstraintSatisfied(c1, q, error, found));
306
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 std::cout << "error=" << error.transpose() << std::endl;
307 2 }
308