GCC Code Coverage Report


Directory: ./
File: tests/roadmap-1.cc
Date: 2024-08-10 11:29:48
Exec Total Coverage
Lines: 248 249 99.6%
Branches: 871 1712 50.9%

Line Branch Exec Source
1 // Copyright (C) 2014 LAAS-CNRS
2 // Author: Mathieu Geisert
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 #include <boost/assign.hpp>
30 #include <hpp/core/connected-component.hh>
31 #include <hpp/core/fwd.hh>
32 #include <hpp/core/nearest-neighbor.hh>
33 #include <hpp/core/node.hh>
34 #include <hpp/core/parser/roadmap.hh>
35 #include <hpp/core/problem.hh>
36 #include <hpp/core/roadmap.hh>
37 #include <hpp/core/steering-method/straight.hh>
38 #include <hpp/core/weighed-distance.hh>
39 #include <hpp/pinocchio/configuration.hh>
40 #include <hpp/pinocchio/device.hh>
41 #include <hpp/pinocchio/joint.hh>
42 #include <hpp/pinocchio/serialization.hh>
43 #include <hpp/pinocchio/urdf/util.hh>
44 #include <hpp/util/debug.hh>
45
46 #define BOOST_TEST_MODULE roadmap - 1
47 #include <boost/test/included/unit_test.hpp>
48
49 using namespace hpp::core;
50 using namespace hpp::pinocchio;
51
52 using hpp::core::steeringMethod::Straight;
53 using hpp::core::steeringMethod::StraightPtr_t;
54
55 BOOST_AUTO_TEST_SUITE(test_hpp_core)
56
57 20 void addEdge(const hpp::core::RoadmapPtr_t& r,
58 const hpp::core::SteeringMethod& sm,
59 const std::vector<NodePtr_t>& nodes, std::size_t i,
60 std::size_t j) {
61
1/2
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
40 r->addEdge(nodes[i], nodes[j],
62
3/6
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 20 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 20 times.
✗ Branch 12 not taken.
40 sm(nodes[i]->configuration(), nodes[j]->configuration()));
63 20 }
64
65 4 DevicePtr_t createRobot() {
66 std::string urdf(
67 "<robot name='test'>"
68 "<link name='link1'/>"
69 "<link name='link2'/>"
70 "<link name='link3'/>"
71 "<joint name='tx' type='prismatic'>"
72 "<parent link='link1'/>"
73 "<child link='link2'/>"
74 "<limit effort='30' velocity='1.0' lower='-3' upper='3'/>"
75 "</joint>"
76 "<joint name='ty' type='prismatic'>"
77 "<axis xyz='0 1 0'/>"
78 "<parent link='link2'/>"
79 "<child link='link3'/>"
80 "<limit effort='30' velocity='1.0' lower='-3' upper='3'/>"
81 "</joint>"
82
1/2
✓ Branch 2 taken 4 times.
✗ Branch 3 not taken.
4 "</robot>");
83
84
2/4
✓ Branch 2 taken 4 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
8 DevicePtr_t robot = Device::create("test");
85
5/10
✓ Branch 1 taken 4 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 4 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 4 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 4 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 4 times.
✗ Branch 17 not taken.
4 urdf::loadModelFromString(robot, 0, "", "anchor", urdf, "");
86 8 return robot;
87 4 }
88
89
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(Roadmap1) {
90 // Build robot
91
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 DevicePtr_t robot = createRobot();
92
93 // Create steering method
94
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 ProblemPtr_t p = Problem::create(robot);
95
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 StraightPtr_t sm = Straight::create(p);
96 // create roadmap
97 hpp::core::DistancePtr_t distance(
98
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.
4 WeighedDistance::createWithWeight(robot, vector_t::Ones(2)));
99
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 RoadmapPtr_t r = Roadmap::create(distance, robot);
100
101 2 std::vector<NodePtr_t> nodes;
102
103 // nodes [0]
104
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 Configuration_t q(robot->configSize());
105
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 0;
106
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 0;
107 // Set init node
108
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 r->initNode(q);
109
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 nodes.push_back(r->initNode());
110
111 // nodes [1]
112
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
113
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 1;
114
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 0;
115
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 nodes.push_back(r->addNode(q));
116
117 // nodes [2]
118
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
119
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 0.5;
120
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 0.9;
121
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 nodes.push_back(r->addNode(q));
122
123 // nodes [3]
124
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
125
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = -0.1;
126
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = -0.9;
127
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 nodes.push_back(r->addNode(q));
128
129 // nodes [4]
130
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
131
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 1.5;
132
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 2.9;
133
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 nodes.push_back(r->addNode(q));
134
135 // nodes [5]
136
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
137
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 2.5;
138
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 2.9;
139
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 nodes.push_back(r->addNode(q));
140
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 r->addGoalNode(nodes[5]->configuration());
141
142
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 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
2 BOOST_TEST_MESSAGE(*r);
143
6/12
✓ 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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
2 BOOST_CHECK_EQUAL(r->connectedComponents().size(), 6);
144
2/2
✓ Branch 1 taken 6 times.
✓ Branch 2 taken 1 times.
14 for (std::size_t i = 0; i < nodes.size(); ++i) {
145
2/2
✓ Branch 1 taken 15 times.
✓ Branch 2 taken 6 times.
42 for (std::size_t j = i + 1; j < nodes.size(); ++j) {
146
13/26
✓ Branch 1 taken 15 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 15 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 15 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 15 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 15 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 15 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 15 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 15 times.
✗ Branch 26 not taken.
✓ Branch 29 taken 15 times.
✗ Branch 30 not taken.
✓ Branch 33 taken 15 times.
✗ Branch 34 not taken.
✓ Branch 37 taken 15 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 15 times.
✗ Branch 41 not taken.
✗ Branch 52 not taken.
✓ Branch 53 taken 15 times.
30 BOOST_CHECK_MESSAGE(
147 nodes[i]->connectedComponent() != nodes[j]->connectedComponent(),
148 "nodes " << i << " and " << j << "are in the same"
149 << " connected component");
150 }
151 }
152
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 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(!r->pathExists());
153 // 0 -> 1
154
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 0, 1);
155
6/12
✓ 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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
2 BOOST_CHECK_EQUAL(r->connectedComponents().size(), 6);
156
2/2
✓ Branch 1 taken 6 times.
✓ Branch 2 taken 1 times.
14 for (std::size_t i = 0; i < nodes.size(); ++i) {
157
2/2
✓ Branch 1 taken 15 times.
✓ Branch 2 taken 6 times.
42 for (std::size_t j = i + 1; j < nodes.size(); ++j) {
158
13/26
✓ Branch 1 taken 15 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 15 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 15 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 15 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 15 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 15 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 15 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 15 times.
✗ Branch 26 not taken.
✓ Branch 29 taken 15 times.
✗ Branch 30 not taken.
✓ Branch 33 taken 15 times.
✗ Branch 34 not taken.
✓ Branch 37 taken 15 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 15 times.
✗ Branch 41 not taken.
✗ Branch 52 not taken.
✓ Branch 53 taken 15 times.
30 BOOST_CHECK_MESSAGE(
159 nodes[i]->connectedComponent() != nodes[j]->connectedComponent(),
160 "nodes " << i << " and " << j << "are in the same"
161 << " connected component");
162 }
163 }
164
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 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(!r->pathExists());
165
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 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
2 BOOST_TEST_MESSAGE(*r);
166
167 // 1 -> 0
168
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 1, 0);
169
170
6/12
✓ 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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
2 BOOST_CHECK_EQUAL(r->connectedComponents().size(), 5);
171
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[1]->connectedComponent());
172
2/2
✓ Branch 1 taken 5 times.
✓ Branch 2 taken 1 times.
12 for (std::size_t i = 1; i < nodes.size(); ++i) {
173
2/2
✓ Branch 1 taken 10 times.
✓ Branch 2 taken 5 times.
30 for (std::size_t j = i + 1; j < nodes.size(); ++j) {
174
13/26
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 10 times.
✗ Branch 6 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.
✓ Branch 22 taken 10 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 10 times.
✗ Branch 26 not taken.
✓ Branch 29 taken 10 times.
✗ Branch 30 not taken.
✓ Branch 33 taken 10 times.
✗ Branch 34 not taken.
✓ Branch 37 taken 10 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 10 times.
✗ Branch 41 not taken.
✗ Branch 52 not taken.
✓ Branch 53 taken 10 times.
20 BOOST_CHECK_MESSAGE(
175 nodes[i]->connectedComponent() != nodes[j]->connectedComponent(),
176 "nodes " << i << " and " << j << "are in the same"
177 << " connected component");
178 }
179 }
180
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 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(!r->pathExists());
181
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 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
2 BOOST_TEST_MESSAGE(*r);
182 // 1 -> 2
183
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 1, 2);
184
6/12
✓ 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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
2 BOOST_CHECK_EQUAL(r->connectedComponents().size(), 5);
185
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[1]->connectedComponent());
186
2/2
✓ Branch 1 taken 5 times.
✓ Branch 2 taken 1 times.
12 for (std::size_t i = 1; i < nodes.size(); ++i) {
187
2/2
✓ Branch 1 taken 10 times.
✓ Branch 2 taken 5 times.
30 for (std::size_t j = i + 1; j < nodes.size(); ++j) {
188
13/26
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 10 times.
✗ Branch 6 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.
✓ Branch 22 taken 10 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 10 times.
✗ Branch 26 not taken.
✓ Branch 29 taken 10 times.
✗ Branch 30 not taken.
✓ Branch 33 taken 10 times.
✗ Branch 34 not taken.
✓ Branch 37 taken 10 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 10 times.
✗ Branch 41 not taken.
✗ Branch 52 not taken.
✓ Branch 53 taken 10 times.
20 BOOST_CHECK_MESSAGE(
189 nodes[i]->connectedComponent() != nodes[j]->connectedComponent(),
190 "nodes " << i << " and " << j << "are in the same"
191 << " connected component");
192 }
193 }
194
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 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(!r->pathExists());
195
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 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
2 BOOST_TEST_MESSAGE(*r);
196
197 // 2 -> 0
198
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 2, 0);
199
6/12
✓ 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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
2 BOOST_CHECK_EQUAL(r->connectedComponents().size(), 4);
200
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[1]->connectedComponent());
201
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[2]->connectedComponent());
202
2/2
✓ Branch 1 taken 4 times.
✓ Branch 2 taken 1 times.
10 for (std::size_t i = 2; i < nodes.size(); ++i) {
203
2/2
✓ Branch 1 taken 6 times.
✓ Branch 2 taken 4 times.
20 for (std::size_t j = i + 1; j < nodes.size(); ++j) {
204
13/26
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 6 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 6 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 6 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 6 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 6 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 6 times.
✗ Branch 26 not taken.
✓ Branch 29 taken 6 times.
✗ Branch 30 not taken.
✓ Branch 33 taken 6 times.
✗ Branch 34 not taken.
✓ Branch 37 taken 6 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 6 times.
✗ Branch 41 not taken.
✗ Branch 52 not taken.
✓ Branch 53 taken 6 times.
12 BOOST_CHECK_MESSAGE(
205 nodes[i]->connectedComponent() != nodes[j]->connectedComponent(),
206 "nodes " << i << " and " << j << "are in the same"
207 << " connected component");
208 }
209 }
210
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 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(!r->pathExists());
211
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 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
2 BOOST_TEST_MESSAGE(*r);
212
213 // 2 -> 3
214
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 2, 3);
215
6/12
✓ 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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
2 BOOST_CHECK_EQUAL(r->connectedComponents().size(), 4);
216
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[1]->connectedComponent());
217
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[2]->connectedComponent());
218
2/2
✓ Branch 1 taken 4 times.
✓ Branch 2 taken 1 times.
10 for (std::size_t i = 2; i < nodes.size(); ++i) {
219
2/2
✓ Branch 1 taken 6 times.
✓ Branch 2 taken 4 times.
20 for (std::size_t j = i + 1; j < nodes.size(); ++j) {
220
13/26
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 6 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 6 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 6 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 6 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 6 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 6 times.
✗ Branch 26 not taken.
✓ Branch 29 taken 6 times.
✗ Branch 30 not taken.
✓ Branch 33 taken 6 times.
✗ Branch 34 not taken.
✓ Branch 37 taken 6 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 6 times.
✗ Branch 41 not taken.
✗ Branch 52 not taken.
✓ Branch 53 taken 6 times.
12 BOOST_CHECK_MESSAGE(
221 nodes[i]->connectedComponent() != nodes[j]->connectedComponent(),
222 "nodes " << i << " and " << j << "are in the same"
223 << " connected component");
224 }
225 }
226
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 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(!r->pathExists());
227
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 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
2 BOOST_TEST_MESSAGE(*r);
228
229 // 2 -> 4
230
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 2, 4);
231
6/12
✓ 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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
2 BOOST_CHECK_EQUAL(r->connectedComponents().size(), 4);
232
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[1]->connectedComponent());
233
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[2]->connectedComponent());
234
2/2
✓ Branch 1 taken 4 times.
✓ Branch 2 taken 1 times.
10 for (std::size_t i = 2; i < nodes.size(); ++i) {
235
2/2
✓ Branch 1 taken 6 times.
✓ Branch 2 taken 4 times.
20 for (std::size_t j = i + 1; j < nodes.size(); ++j) {
236
13/26
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 6 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 6 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 6 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 6 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 6 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 6 times.
✗ Branch 26 not taken.
✓ Branch 29 taken 6 times.
✗ Branch 30 not taken.
✓ Branch 33 taken 6 times.
✗ Branch 34 not taken.
✓ Branch 37 taken 6 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 6 times.
✗ Branch 41 not taken.
✗ Branch 52 not taken.
✓ Branch 53 taken 6 times.
12 BOOST_CHECK_MESSAGE(
237 nodes[i]->connectedComponent() != nodes[j]->connectedComponent(),
238 "nodes " << i << " and " << j << "are in the same"
239 << " connected component");
240 }
241 }
242
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 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(!r->pathExists());
243
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 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
2 BOOST_TEST_MESSAGE(*r);
244
245 // 3 -> 5
246
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 3, 5);
247
6/12
✓ 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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
2 BOOST_CHECK_EQUAL(r->connectedComponents().size(), 4);
248
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[1]->connectedComponent());
249
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[2]->connectedComponent());
250
2/2
✓ Branch 1 taken 4 times.
✓ Branch 2 taken 1 times.
10 for (std::size_t i = 2; i < nodes.size(); ++i) {
251
2/2
✓ Branch 1 taken 6 times.
✓ Branch 2 taken 4 times.
20 for (std::size_t j = i + 1; j < nodes.size(); ++j) {
252
13/26
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 6 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 6 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 6 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 6 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 6 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 6 times.
✗ Branch 26 not taken.
✓ Branch 29 taken 6 times.
✗ Branch 30 not taken.
✓ Branch 33 taken 6 times.
✗ Branch 34 not taken.
✓ Branch 37 taken 6 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 6 times.
✗ Branch 41 not taken.
✗ Branch 52 not taken.
✓ Branch 53 taken 6 times.
12 BOOST_CHECK_MESSAGE(
253 nodes[i]->connectedComponent() != nodes[j]->connectedComponent(),
254 "nodes " << i << " and " << j << "are in the same"
255 << " connected component");
256 }
257 }
258
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 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(r->pathExists());
259
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 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
2 BOOST_TEST_MESSAGE(*r);
260
261 // 4 -> 5
262
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 4, 5);
263
6/12
✓ 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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
2 BOOST_CHECK_EQUAL(r->connectedComponents().size(), 4);
264
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[1]->connectedComponent());
265
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[2]->connectedComponent());
266
2/2
✓ Branch 1 taken 4 times.
✓ Branch 2 taken 1 times.
10 for (std::size_t i = 2; i < nodes.size(); ++i) {
267
2/2
✓ Branch 1 taken 6 times.
✓ Branch 2 taken 4 times.
20 for (std::size_t j = i + 1; j < nodes.size(); ++j) {
268
13/26
✓ Branch 1 taken 6 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 6 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 6 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 6 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 6 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 6 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 6 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 6 times.
✗ Branch 26 not taken.
✓ Branch 29 taken 6 times.
✗ Branch 30 not taken.
✓ Branch 33 taken 6 times.
✗ Branch 34 not taken.
✓ Branch 37 taken 6 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 6 times.
✗ Branch 41 not taken.
✗ Branch 52 not taken.
✓ Branch 53 taken 6 times.
12 BOOST_CHECK_MESSAGE(
269 nodes[i]->connectedComponent() != nodes[j]->connectedComponent(),
270 "nodes " << i << " and " << j << "are in the same"
271 << " connected component");
272 }
273 }
274
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 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(r->pathExists());
275
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 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
2 BOOST_TEST_MESSAGE(*r);
276
277 // 5 -> 0
278
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 5, 0);
279
6/12
✓ 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 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
2 BOOST_CHECK_EQUAL(r->connectedComponents().size(), 1);
280
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[1]->connectedComponent());
281
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[2]->connectedComponent());
282
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[3]->connectedComponent());
283
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[4]->connectedComponent());
284
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 19 taken 1 times.
✗ Branch 20 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(nodes[0]->connectedComponent() == nodes[5]->connectedComponent());
285
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 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(r->pathExists());
286
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 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
2 BOOST_TEST_MESSAGE(*r);
287
288 // Check that memory if well deallocated.
289 2 std::list<ConnectedComponentWkPtr_t> ccs;
290 2 for (ConnectedComponents_t::const_iterator _cc =
291
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 r->connectedComponents().begin();
292
3/4
✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✓ Branch 7 taken 1 times.
4 _cc != r->connectedComponents().end(); ++_cc)
293
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 ccs.push_back(*_cc);
294
295 2 r.reset();
296 2 for (std::list<ConnectedComponentWkPtr_t>::const_iterator _cc = ccs.begin();
297
1/2
✗ Branch 4 not taken.
✓ Branch 5 taken 1 times.
2 _cc != ccs.begin(); ++_cc) {
298 BOOST_CHECK(!_cc->lock());
299 }
300 2 }
301
302
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(nearestNeighbor) {
303 // Build robot
304
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 DevicePtr_t robot = createRobot();
305
306 // Create steering method
307
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 ProblemPtr_t p = Problem::create(robot);
308
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 StraightPtr_t sm = Straight::create(p);
309 // create roadmap
310 hpp::core::DistancePtr_t distance(
311
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.
4 WeighedDistance::createWithWeight(robot, vector_t::Ones(2)));
312
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 RoadmapPtr_t r = Roadmap::create(distance, robot);
313
314 2 std::vector<NodePtr_t> nodes;
315
316 // nodes [0]
317
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 Configuration_t q(robot->configSize());
318
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 0;
319
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 0;
320
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 nodes.push_back(r->addNode(q));
321
322 // nodes [1]
323
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
324
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 1;
325
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 0;
326
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 nodes.push_back(r->addNode(q));
327
328 // nodes [2]
329
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
330
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 0.5;
331
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 0.9;
332
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 nodes.push_back(r->addNode(q));
333
334 // nodes [3]
335
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
336
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = -0.1;
337
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = -0.9;
338
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 nodes.push_back(r->addNode(q));
339
340 // nodes [4]
341
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
342
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 1.5;
343
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 2.9;
344
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 nodes.push_back(r->addNode(q));
345
346 // nodes [5]
347
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
348
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 2.5;
349
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 2.9;
350
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 nodes.push_back(r->addNode(q));
351
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 r->addGoalNode(nodes[5]->configuration());
352
353 // nodes [6]
354
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
355
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 0;
356
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 0.2;
357
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 nodes.push_back(r->addNode(q));
358
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 r->addGoalNode(nodes[6]->configuration());
359
360 // 0 -> 1
361
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 0, 1);
362 // 1 -> 0
363
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 1, 0);
364 // 1 -> 2
365
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 1, 2);
366 // 2 -> 0
367
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 2, 0);
368 // 0 -> 3
369
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 0, 3);
370 // 3 -> 2
371
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 3, 2);
372
373 hpp::pinocchio::value_type dist;
374 using hpp::core::Nodes_t;
375
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 Nodes_t knearest = r->nearestNeighbor()->KnearestSearch(
376
4/8
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
4 nodes[0]->configuration(), nodes[0]->connectedComponent(), 3, dist);
377
2/2
✓ Branch 5 taken 3 times.
✓ Branch 6 taken 1 times.
8 for (Nodes_t::const_iterator it = knearest.begin(); it != knearest.end();
378 6 ++it) {
379
15/30
✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 3 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 3 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 3 times.
✗ Branch 13 not taken.
✓ Branch 16 taken 3 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 3 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 3 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 3 times.
✗ Branch 26 not taken.
✓ Branch 30 taken 3 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 3 times.
✗ Branch 34 not taken.
✓ Branch 37 taken 3 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 3 times.
✗ Branch 41 not taken.
✓ Branch 43 taken 3 times.
✗ Branch 44 not taken.
✓ Branch 46 taken 3 times.
✗ Branch 47 not taken.
✓ Branch 49 taken 3 times.
✗ Branch 50 not taken.
6 BOOST_TEST_MESSAGE("q = [" << (*it)->configuration().transpose()
380 << "] - dist : "
381 << (*distance)(nodes[0]->configuration(),
382 (*it)->configuration()));
383 }
384 2 for (std::vector<NodePtr_t>::const_iterator it = nodes.begin();
385
2/2
✓ Branch 3 taken 7 times.
✓ Branch 4 taken 1 times.
16 it != nodes.end(); ++it) {
386
2/4
✓ Branch 2 taken 7 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 7 times.
✗ Branch 6 not taken.
14 Configuration_t q = (*it)->configuration();
387
13/26
✓ Branch 2 taken 7 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 7 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 7 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 7 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 7 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 7 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 7 times.
✗ Branch 22 not taken.
✓ Branch 25 taken 7 times.
✗ Branch 26 not taken.
✓ Branch 29 taken 7 times.
✗ Branch 30 not taken.
✓ Branch 32 taken 7 times.
✗ Branch 33 not taken.
✓ Branch 35 taken 7 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 7 times.
✗ Branch 39 not taken.
✓ Branch 41 taken 7 times.
✗ Branch 42 not taken.
14 BOOST_TEST_MESSAGE("[" << q.transpose() << "] - dist : "
388 << (*distance)(nodes[0]->configuration(), q));
389 14 }
390 2 }
391
392
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(serialization) {
393 // Build robot
394
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 DevicePtr_t robot = createRobot();
395
396 // Create steering method
397
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 ProblemPtr_t p = Problem::create(robot);
398
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 StraightPtr_t sm = Straight::create(p);
399 // create roadmap
400 hpp::core::DistancePtr_t distance(
401
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.
4 WeighedDistance::createWithWeight(robot, vector_t::Ones(2)));
402
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 RoadmapPtr_t r = Roadmap::create(distance, robot);
403
404 2 std::vector<NodePtr_t> nodes;
405
406 // nodes [0]
407
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 Configuration_t q(robot->configSize());
408
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 0;
409
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 0;
410 // Set init node
411
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 r->initNode(q);
412
1/2
✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
2 nodes.push_back(r->initNode());
413
414 // nodes [1]
415
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
416
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 1;
417
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 0;
418
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 nodes.push_back(r->addNode(q));
419
420 // nodes [2]
421
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
422
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 0.5;
423
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 0.9;
424
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 nodes.push_back(r->addNode(q));
425
426 // nodes [3]
427
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
428
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = -0.1;
429
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = -0.9;
430
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 nodes.push_back(r->addNode(q));
431
432 // nodes [4]
433
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
434
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 1.5;
435
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 2.9;
436
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 nodes.push_back(r->addNode(q));
437
438 // nodes [5]
439
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 q = Configuration_t(robot->configSize());
440
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[0] = 2.5;
441
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 q[1] = 2.9;
442
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 nodes.push_back(r->addNode(q));
443
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 r->addGoalNode(nodes[5]->configuration());
444
445 // 1 -> 0
446
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 0, 1);
447 // 1 -> 2
448
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 1, 2);
449 // 2 -> 0
450
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 2, 0);
451 // 3 -> 5
452
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 3, 5);
453 // 4 -> 5
454
1/2
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
2 addEdge(r, *sm, nodes, 4, 5);
455
456
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 std::cout << *r << std::endl;
457
458 // save data to archive
459
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 parser::serializeRoadmap<hpp::serialization::text_oarchive>(
460
1/2
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
4 r, "filename.txt", parser::make_nvp(robot->name(), robot.get()));
461
462
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 parser::serializeRoadmap<hpp::serialization::xml_oarchive>(
463
1/2
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
4 r, "filename.xml", parser::make_nvp(robot->name(), robot.get()));
464
465
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 parser::serializeRoadmap<hpp::serialization::binary_oarchive>(
466
1/2
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
4 r, "filename.bin", parser::make_nvp(robot->name(), robot.get()));
467 2 }
468
469
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(deserialization) {
470
1/2
✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
2 DevicePtr_t robot = createRobot();
471
472 2 RoadmapPtr_t nr;
473
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 parser::serializeRoadmap<hpp::serialization::text_iarchive>(
474
1/2
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
4 nr, "filename.txt", parser::make_nvp(robot->name(), robot.get()));
475
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 std::cout << *nr << std::endl;
476
477
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 parser::serializeRoadmap<hpp::serialization::xml_iarchive>(
478
1/2
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
4 nr, "filename.xml", parser::make_nvp(robot->name(), robot.get()));
479
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 std::cout << *nr << std::endl;
480
481
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 parser::serializeRoadmap<hpp::serialization::binary_iarchive>(
482
1/2
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
4 nr, "filename.bin", parser::make_nvp(robot->name(), robot.get()));
483
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 std::cout << *nr << std::endl;
484 2 }
485
486 BOOST_AUTO_TEST_SUITE_END()
487