Directory: | ./ |
---|---|
File: | tests/paths.cc |
Date: | 2024-12-13 16:14:03 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 73 | 79 | 92.4% |
Branches: | 243 | 490 | 49.6% |
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 paths | ||
30 | #include <boost/mpl/list.hpp> | ||
31 | #include <boost/test/included/unit_test.hpp> | ||
32 | #include <pinocchio/fwd.hpp> | ||
33 | |||
34 | // Boost version 1.54 | ||
35 | // Cannot include boost CPU timers | ||
36 | // #include <boost/timer/timer.hpp> | ||
37 | // because the original timers are already included by | ||
38 | // the unit test framework | ||
39 | // #include <boost/timer.hh> | ||
40 | |||
41 | #include <hpp/core/problem.hh> | ||
42 | #include <hpp/core/straight-path.hh> | ||
43 | #include <hpp/core/subchain-path.hh> | ||
44 | #include <hpp/pinocchio/configuration.hh> | ||
45 | #include <hpp/pinocchio/device.hh> | ||
46 | #include <hpp/pinocchio/joint.hh> | ||
47 | #include <hpp/pinocchio/urdf/util.hh> | ||
48 | |||
49 | #define TOSTR(x) \ | ||
50 | static_cast<std::ostringstream&>((std::ostringstream() << x)).str() | ||
51 | |||
52 | using namespace hpp::core; | ||
53 | using namespace hpp::pinocchio; | ||
54 | |||
55 | 1 | DevicePtr_t createRobot() { | |
56 | std::string urdf( | ||
57 | "<robot name='test'>" | ||
58 | "<link name='link0'/>" | ||
59 | "<joint name='joint0' type='prismatic'>" | ||
60 | "<parent link='link0'/>" | ||
61 | "<child link='link1'/>" | ||
62 | "<limit effort='30' velocity='1.0' lower='-4' upper='4'/>" | ||
63 | "</joint>" | ||
64 | "<link name='link1'/>" | ||
65 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
1 | "</robot>"); |
66 | |||
67 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | DevicePtr_t robot = Device::create("test"); |
68 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
|
1 | urdf::loadModelFromString(robot, 0, "", "anchor", urdf, ""); |
69 | 2 | return robot; | |
70 | 1 | } | |
71 | |||
72 | 1 | DevicePtr_t createRobot2() { | |
73 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | std::ostringstream oss; |
74 | oss << "<robot name='test'>" | ||
75 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
1 | << "<link name='link0'/>"; |
76 |
2/2✓ Branch 0 taken 10 times.
✓ Branch 1 taken 1 times.
|
11 | for (int i = 0; i < 10; ++i) { |
77 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | oss << "<joint name='joint" << i << "' type='prismatic'>" |
78 |
3/6✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 10 times.
✗ Branch 8 not taken.
|
10 | << "<parent link='link" << i << "'/>" |
79 |
3/6✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 10 times.
✗ Branch 8 not taken.
|
10 | << "<child link='link" << i + 1 << "'/>" |
80 | << "<limit effort='30' velocity='1.0' lower='-4' upper='4'/>" | ||
81 | << "</joint>" | ||
82 |
7/14✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 10 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 10 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 10 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 10 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 10 times.
✗ Branch 20 not taken.
|
10 | << "<link name='link" << i + 1 << "'/>"; |
83 | } | ||
84 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | oss << "</robot>"; |
85 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | std::string urdf(oss.str()); |
86 | |||
87 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | DevicePtr_t robot = Device::create("test"); |
88 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
|
1 | urdf::loadModelFromString(robot, 0, "", "anchor", urdf, ""); |
89 | 2 | return robot; | |
90 | 1 | } | |
91 | |||
92 | typedef std::pair<value_type, value_type> Pair_t; | ||
93 | |||
94 | ✗ | std::ostream& operator<<(std::ostream& os, const Pair_t& p) { | |
95 | ✗ | os << "Pair " << p.first << ", " << p.second; | |
96 | ✗ | return os; | |
97 | } | ||
98 | |||
99 | ✗ | void printAt(const PathPtr_t& p, ConfigurationOut_t q, value_type t) { | |
100 | ✗ | p->eval(q, t); | |
101 | ✗ | std::cout << t << ":\t" << q.transpose() << std::endl; | |
102 | } | ||
103 | 8 | void checkAt(const PathPtr_t orig, value_type to, const PathPtr_t extr, | |
104 | value_type te) { | ||
105 |
2/4✓ Branch 3 taken 8 times.
✗ Branch 4 not taken.
✓ Branch 8 taken 8 times.
✗ Branch 9 not taken.
|
8 | Configuration_t q1(orig->outputSize()), q2(orig->outputSize()); |
106 |
2/4✓ Branch 2 taken 8 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 8 times.
✗ Branch 6 not taken.
|
8 | orig->eval(q1, to); |
107 |
2/4✓ Branch 2 taken 8 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 8 times.
✗ Branch 6 not taken.
|
8 | extr->eval(q2, te); |
108 |
12/24✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 8 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 8 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 8 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 8 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 8 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 8 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 8 times.
✗ Branch 26 not taken.
✓ Branch 29 taken 8 times.
✗ Branch 30 not taken.
✓ Branch 32 taken 8 times.
✗ Branch 33 not taken.
✓ Branch 35 taken 8 times.
✗ Branch 36 not taken.
✗ Branch 43 not taken.
✓ Branch 44 taken 8 times.
|
8 | BOOST_CHECK_MESSAGE(q2.isApprox(q1), |
109 | "Extracted path is wrong." | ||
110 | "\nExpected: " | ||
111 | << q1.transpose() | ||
112 | << "\nGot : " << q2.transpose()); | ||
113 | 8 | } | |
114 | |||
115 |
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(extracted) { |
116 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | DevicePtr_t dev = createRobot(); |
117 |
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(dev); |
118 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | ProblemPtr_t problem = Problem::create(dev); |
119 | |||
120 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | Configuration_t q1(dev->configSize()); |
121 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | q1 << 0; |
122 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | Configuration_t q2(dev->configSize()); |
123 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | q2 << 1; |
124 |
3/6✓ 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.
|
4 | PathPtr_t p1 = (*problem->steeringMethod())(q1, q2), p2; |
125 | |||
126 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | p2 = p1->extract(Pair_t(0.5, 1)); |
127 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | checkAt(p1, 0.5, p2, 0.0); |
128 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | checkAt(p1, 1.0, p2, 0.5); |
129 | |||
130 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | p2 = p1->extract(Pair_t(1, 0.5)); |
131 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | checkAt(p1, 1.0, p2, 0.0); |
132 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | checkAt(p1, 0.5, p2, 0.5); |
133 | |||
134 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | p2 = p2->extract(Pair_t(0, 0.25)); |
135 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | checkAt(p1, 1.0, p2, 0.0); |
136 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | checkAt(p1, .75, p2, .25); |
137 | |||
138 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | p2 = p1->extract(Pair_t(1, 0.5)); |
139 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | p2 = p2->extract(Pair_t(0.25, 0)); |
140 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | checkAt(p1, .75, p2, 0.0); |
141 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | checkAt(p1, 1.0, p2, .25); |
142 | 2 | } | |
143 | |||
144 |
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(subchain) { |
145 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | DevicePtr_t dev = createRobot2(); // 10 translations |
146 |
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(dev); |
147 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | ProblemPtr_t problem = Problem::create(dev); |
148 | |||
149 | 2 | segments_t intervals; | |
150 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | intervals.push_back(segment_t(0, 3)); |
151 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | intervals.push_back(segment_t(6, 3)); |
152 | |||
153 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
2 | Configuration_t q1(Configuration_t::Zero(dev->configSize())); |
154 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
2 | Configuration_t q2(Configuration_t::Ones(dev->configSize())); |
155 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | q2.tail<5>().setConstant(-1); |
156 | |||
157 |
3/6✓ 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.
|
4 | PathPtr_t p1 = (*problem->steeringMethod())(q1, q2), p2; |
158 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | p2 = SubchainPath::create(p1, intervals, intervals); |
159 | |||
160 |
6/12✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✗ Branch 24 not taken.
✓ Branch 25 taken 1 times.
|
2 | BOOST_CHECK(p2->outputSize() == 6); |
161 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | Configuration_t q(p2->outputSize()); |
162 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | p2->eval(q, 0); |
163 |
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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(q.head<3>().isZero()); |
164 |
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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 1 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(q.tail<3>().isZero()); |
165 | |||
166 |
3/6✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
|
2 | p2->eval(q, p1->length()); |
167 |
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 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(q.head<3>().isApprox(Configuration_t::Ones(3))); |
168 |
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 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 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(q.tail<3>().isApprox(-Configuration_t::Ones(3))); |
169 | |||
170 |
3/6✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
|
2 | p2->eval(q, p1->length() * 0.5); |
171 |
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 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 30 taken 1 times.
✗ Branch 31 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 1 times.
|
2 | BOOST_CHECK(q.head<3>().isApprox(Configuration_t::Ones(3) * 0.5)); |
172 |
11/22✓ 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 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 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✗ Branch 38 not taken.
✓ Branch 39 taken 1 times.
|
2 | BOOST_CHECK(q.tail<3>().isApprox(-Configuration_t::Ones(3) * 0.5)); |
173 | 2 | } | |
174 |