1 #include <gtest/gtest.h>
3 #include <boost/optional/optional_io.hpp>
14 EXPECT_TRUE((!!
left));
15 EXPECT_TRUE(*
left == lanelets.at(2003));
17 left = graph->left(lanelets.at(2002));
18 EXPECT_FALSE((!!
left));
23 EXPECT_FALSE((!!
left));
25 left = graph->left(lanelets.at(2006));
26 EXPECT_FALSE((!!
left));
31 EXPECT_FALSE((!!
left));
33 left = graph->left(lanelets.at(2009));
34 EXPECT_FALSE((!!
left));
39 EXPECT_FALSE((!!
left));
41 left = graph->left(lanelets.at(2020));
42 EXPECT_FALSE((!!
left));
48 EXPECT_FALSE((!!
left));
54 EXPECT_TRUE((!!
right));
55 EXPECT_TRUE(*
right == lanelets.at(2001));
57 right = graph->right(lanelets.at(2004));
58 EXPECT_FALSE((!!
right));
60 right = graph->right(lanelets.at(2001));
61 EXPECT_FALSE((!!
right));
63 right = graph->right(lanelets.at(2002));
64 EXPECT_FALSE((!!
right));
69 EXPECT_FALSE((!!
right));
71 right = graph->right(lanelets.at(2005));
72 EXPECT_FALSE((!!
right));
77 EXPECT_FALSE((!!
right));
79 right = graph->right(lanelets.at(2009));
80 EXPECT_FALSE((!!
right));
85 EXPECT_FALSE((!!
right));
87 right = graph->right(lanelets.at(2020));
88 EXPECT_FALSE((!!
right));
95 EXPECT_FALSE((!!
right));
101 left = graph->lefts(lanelets.at(2012));
102 EXPECT_EQ(
left.size(), 1ul);
103 EXPECT_TRUE(std::find(
left.begin(),
left.end(), lanelets.at(2011)) !=
left.end());
105 left = graph->lefts(lanelets.at(2011));
106 EXPECT_TRUE(
left.empty());
108 left = graph->lefts(lanelets.at(2014));
109 EXPECT_EQ(
left.size(), 1ul);
110 EXPECT_TRUE(std::find(
left.begin(),
left.end(), lanelets.at(2013)) !=
left.end());
112 left = graph->lefts(lanelets.at(2015));
113 EXPECT_EQ(
left.size(), 2ul);
114 EXPECT_TRUE(std::find(
left.begin(),
left.end(), lanelets.at(2014)) !=
left.end());
115 EXPECT_TRUE(std::find(
left.begin(),
left.end(), lanelets.at(2013)) !=
left.end());
121 right = graph->rights(lanelets.at(2011));
122 EXPECT_EQ(
right.size(), 1ul);
123 EXPECT_TRUE(std::find(
right.begin(),
right.end(), lanelets.at(2012)) !=
right.end());
125 right = graph->rights(lanelets.at(2012));
126 EXPECT_TRUE(
right.empty());
128 right = graph->rights(lanelets.at(2013));
129 EXPECT_EQ(
right.size(), 2ul);
130 EXPECT_TRUE(std::find(
right.begin(),
right.end(), lanelets.at(2014)) !=
right.end());
131 EXPECT_TRUE(std::find(
right.begin(),
right.end(), lanelets.at(2015)) !=
right.end());
133 right = graph->rights(lanelets.at(2014));
134 EXPECT_EQ(
right.size(), 1ul);
135 EXPECT_TRUE(std::find(
right.begin(),
right.end(), lanelets.at(2015)) !=
right.end());
140 ConstLanelets following = graph->following(lanelets.at(2001),
false);
141 EXPECT_EQ(following.size(), 1ul);
142 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2002)) != following.end());
144 following = graph->following(lanelets.at(2003),
false);
145 EXPECT_EQ(following.size(), 1ul);
146 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2004)) != following.end());
148 following = graph->following(lanelets.at(2002),
false);
149 EXPECT_EQ(following.size(), 1ul);
150 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2006)) != following.end());
152 following = graph->following(lanelets.at(2004),
false);
153 EXPECT_EQ(following.size(), 1ul);
154 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2005)) != following.end());
158 ConstLanelets following = graph->following(lanelets.at(2005),
false);
159 EXPECT_EQ(following.size(), 1ul);
160 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2007)) != following.end());
165 ConstLanelets following = graph->following(lanelets.at(2007),
false);
166 EXPECT_EQ(following.size(), 2ul);
167 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2008)) != following.end());
168 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2009)) != following.end());
173 ConstLanelets following = graph->following(lanelets.at(2018),
false);
174 EXPECT_EQ(following.size(), 1ul);
175 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2016)) != following.end());
177 following = graph->following(lanelets.at(2019),
false);
178 EXPECT_EQ(following.size(), 1ul);
179 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2020)) != following.end());
181 following = graph->following(lanelets.at(2020),
false);
182 EXPECT_EQ(following.size(), 1ul);
183 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2022)) != following.end());
185 following = graph->following(lanelets.at(2022),
false);
186 EXPECT_EQ(following.size(), 1ul);
187 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2024)) != following.end());
189 following = graph->following(lanelets.at(2021),
false);
190 EXPECT_EQ(following.size(), 1ul);
191 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2020).invert()) != following.end());
193 following = graph->following(lanelets.at(2020).invert(),
false);
194 EXPECT_EQ(following.size(), 1ul);
195 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2018)) != following.end());
201 ConstLanelets following = graph->following(invalidLanelet,
false);
202 EXPECT_TRUE(following.empty());
207 ConstLanelets following = graph->following(lanelets.at(2001),
true);
208 EXPECT_EQ(following.size(), 2ul);
209 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2002)) != following.end());
210 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2003)) != following.end());
212 following = graph->following(lanelets.at(2003),
true);
213 EXPECT_EQ(following.size(), 2ul);
214 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2001)) != following.end());
215 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2004)) != following.end());
217 following = graph->following(lanelets.at(2002),
true);
218 EXPECT_EQ(following.size(), 1ul);
219 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2006)) != following.end());
221 following = graph->following(lanelets.at(2004),
true);
222 EXPECT_EQ(following.size(), 1ul);
223 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2005)) != following.end());
227 ConstLanelets following = graph->following(lanelets.at(2005),
true);
228 EXPECT_EQ(following.size(), 1ul);
229 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2007)) != following.end());
231 following = graph->following(lanelets.at(2006),
true);
232 EXPECT_EQ(following.size(), 1ul);
233 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2007)) != following.end());
238 ConstLanelets following = graph->following(lanelets.at(2007),
true);
239 EXPECT_EQ(following.size(), 2ul);
240 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2008)) != following.end());
241 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2009)) != following.end());
246 ConstLanelets following = graph->following(lanelets.at(2018),
true);
247 EXPECT_EQ(following.size(), 1ul);
248 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2016)) != following.end());
250 following = graph->following(lanelets.at(2019),
true);
251 EXPECT_EQ(following.size(), 1ul);
252 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2020)) != following.end());
254 following = graph->following(lanelets.at(2020),
true);
255 EXPECT_EQ(following.size(), 1ul);
256 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2022)) != following.end());
258 following = graph->following(lanelets.at(2022),
true);
259 EXPECT_EQ(following.size(), 1ul);
260 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2024)) != following.end());
262 following = graph->following(lanelets.at(2021),
true);
263 EXPECT_EQ(following.size(), 1ul);
264 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2020).invert()) != following.end());
266 following = graph->following(lanelets.at(2020).invert(),
true);
267 EXPECT_EQ(following.size(), 1ul);
268 EXPECT_TRUE(std::find(following.begin(), following.end(), lanelets.at(2018)) != following.end());
274 previous = graph->previous(lanelets.at(2001),
false);
275 EXPECT_EQ(previous.size(), 0ul);
277 previous = graph->previous(lanelets.at(2003),
false);
278 EXPECT_EQ(previous.size(), 0ul);
280 previous = graph->previous(lanelets.at(2002),
false);
281 EXPECT_EQ(previous.size(), 1ul);
282 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2001)) != previous.end());
284 previous = graph->previous(lanelets.at(2004),
false);
285 EXPECT_EQ(previous.size(), 1ul);
286 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2003)) != previous.end());
290 ConstLanelets previous = graph->previous(lanelets.at(2005),
false);
291 EXPECT_EQ(previous.size(), 1ul);
292 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2004)) != previous.end());
294 previous = graph->previous(lanelets.at(2006),
false);
295 EXPECT_EQ(previous.size(), 1ul);
296 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2002)) != previous.end());
300 ConstLanelets previous = graph->previous(lanelets.at(2007),
false);
301 EXPECT_EQ(previous.size(), 2ul);
302 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2005)) != previous.end());
303 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2006)) != previous.end());
307 ConstLanelets previous = graph->previous(lanelets.at(2008),
false);
308 EXPECT_EQ(previous.size(), 1ul);
309 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2007)) != previous.end());
311 previous = graph->previous(lanelets.at(2009),
false);
312 EXPECT_EQ(previous.size(), 1ul);
313 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2007)) != previous.end());
318 ConstLanelets previous = graph->previous(lanelets.at(2019),
false);
319 EXPECT_EQ(previous.size(), 1ul);
320 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2017)) != previous.end());
322 previous = graph->previous(lanelets.at(2020),
false);
323 EXPECT_EQ(previous.size(), 1ul);
324 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2019)) != previous.end());
326 previous = graph->previous(lanelets.at(2022),
false);
327 EXPECT_EQ(previous.size(), 1ul);
328 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2020)) != previous.end());
330 previous = graph->previous(lanelets.at(2024),
false);
331 EXPECT_EQ(previous.size(), 1ul);
332 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2022)) != previous.end());
334 previous = graph->previous(lanelets.at(2021),
false);
335 EXPECT_EQ(previous.size(), 1ul);
336 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2023)) != previous.end());
338 previous = graph->previous(lanelets.at(2020).invert(),
false);
339 EXPECT_EQ(previous.size(), 1ul);
340 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2021)) != previous.end());
342 previous = graph->previous(lanelets.at(2018),
false);
343 EXPECT_EQ(previous.size(), 1ul);
344 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2020).invert()) != previous.end());
346 previous = graph->previous(lanelets.at(2016),
false);
347 EXPECT_EQ(previous.size(), 1ul);
348 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2018)) != previous.end());
353 ConstLanelets previous = graph->previous(invalidLanelet,
false);
354 EXPECT_TRUE(previous.empty());
359 ConstLanelets previous = graph->previous(lanelets.at(2001),
true);
360 EXPECT_EQ(previous.size(), 1ul);
361 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2003)) != previous.end());
363 previous = graph->previous(lanelets.at(2003),
true);
364 EXPECT_EQ(previous.size(), 1ul);
365 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2001)) != previous.end());
367 previous = graph->previous(lanelets.at(2002),
true);
368 EXPECT_EQ(previous.size(), 1ul);
369 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2001)) != previous.end());
371 previous = graph->previous(lanelets.at(2004),
true);
372 EXPECT_EQ(previous.size(), 1ul);
373 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2003)) != previous.end());
377 ConstLanelets previous = graph->previous(lanelets.at(2005),
true);
378 EXPECT_EQ(previous.size(), 1ul);
379 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2004)) != previous.end());
381 previous = graph->previous(lanelets.at(2006),
true);
382 EXPECT_EQ(previous.size(), 1ul);
383 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2002)) != previous.end());
387 ConstLanelets previous = graph->previous(lanelets.at(2007),
true);
388 EXPECT_EQ(previous.size(), 2ul);
389 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2005)) != previous.end());
390 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2006)) != previous.end());
394 ConstLanelets previous = graph->previous(lanelets.at(2008),
true);
395 EXPECT_EQ(previous.size(), 1ul);
396 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2007)) != previous.end());
398 previous = graph->previous(lanelets.at(2009),
true);
399 EXPECT_EQ(previous.size(), 1ul);
400 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2007)) != previous.end());
404 ConstLanelets previous = graph->previous(lanelets.at(2019),
true);
405 EXPECT_EQ(previous.size(), 1ul);
406 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2017)) != previous.end());
408 previous = graph->previous(lanelets.at(2020),
true);
409 EXPECT_EQ(previous.size(), 1ul);
410 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2019)) != previous.end());
412 previous = graph->previous(lanelets.at(2022),
true);
413 EXPECT_EQ(previous.size(), 1ul);
414 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2020)) != previous.end());
416 previous = graph->previous(lanelets.at(2024),
true);
417 EXPECT_EQ(previous.size(), 1ul);
418 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2022)) != previous.end());
420 previous = graph->previous(lanelets.at(2021),
true);
421 EXPECT_EQ(previous.size(), 1ul);
422 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2023)) != previous.end());
424 previous = graph->previous(lanelets.at(2020).invert(),
true);
425 EXPECT_EQ(previous.size(), 1ul);
426 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2021)) != previous.end());
428 previous = graph->previous(lanelets.at(2018),
true);
429 EXPECT_EQ(previous.size(), 1ul);
430 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2020).invert()) != previous.end());
432 previous = graph->previous(lanelets.at(2016),
true);
433 EXPECT_EQ(previous.size(), 1ul);
434 EXPECT_TRUE(std::find(previous.begin(), previous.end(), lanelets.at(2018)) != previous.end());
439 ConstLanelets previous = graph->previous(invalidLanelet,
true);
440 EXPECT_TRUE(previous.empty());
446 laneletSet = graph->besides(lanelets.at(2010));
447 ASSERT_EQ(1ul, laneletSet.size());
448 EXPECT_EQ(laneletSet[0], lanelets.at(2010));
450 laneletSet = graph->besides(lanelets.at(2011));
451 ASSERT_EQ(laneletSet.size(), 2ul);
452 EXPECT_EQ(laneletSet[0], lanelets.at(2011));
453 EXPECT_EQ(laneletSet[1], lanelets.at(2012));
456 laneletSet = graph->besides(lanelets.at(2015));
457 ASSERT_EQ(laneletSet.size(), 3ul);
458 EXPECT_EQ(laneletSet[0], lanelets.at(2013));
459 EXPECT_EQ(laneletSet[1], lanelets.at(2014));
460 EXPECT_EQ(laneletSet[2], lanelets.at(2015));
462 laneletSet = graph->besides(lanelets.at(2014));
463 ASSERT_EQ(laneletSet.size(), 3ul);
464 EXPECT_EQ(laneletSet[0], lanelets.at(2013));
465 EXPECT_EQ(laneletSet[1], lanelets.at(2014));
466 EXPECT_EQ(laneletSet[2], lanelets.at(2015));
468 laneletSet = graph->besides(lanelets.at(2013));
469 ASSERT_EQ(laneletSet.size(), 3ul);
470 EXPECT_EQ(laneletSet[0], lanelets.at(2013));
471 EXPECT_EQ(laneletSet[1], lanelets.at(2014));
472 EXPECT_EQ(laneletSet[2], lanelets.at(2015));
477 auto result = graph->conflicting(lanelets.at(2007));
478 EXPECT_EQ(result.size(), 0ul);
480 result = graph->conflicting(lanelets.at(2012));
481 EXPECT_EQ(result.size(), 0ul);
483 result = graph->conflicting(lanelets.at(2001));
484 EXPECT_EQ(result.size(), 0ul);
486 result = graph->conflicting(lanelets.at(2005));
487 EXPECT_EQ(result.size(), 1ul);
492 auto result = graph->conflicting(lanelets.at(2005));
493 ASSERT_EQ(result.size(), 1ul);
494 EXPECT_TRUE(result.front() == lanelets.at(2006));
496 result = graph->conflicting(lanelets.at(2006));
497 ASSERT_EQ(result.size(), 1ul);
498 EXPECT_TRUE(result.front() == lanelets.at(2005));
500 result = graph->conflicting(lanelets.at(2032));
501 EXPECT_EQ(result.size(), 0ul);
506 auto result = graph->conflicting(lanelets.at(2020));
507 ASSERT_EQ(result.size(), 1ul);
508 EXPECT_NE(result.front().lanelet()->inverted(), lanelets.at(2020).inverted());
510 result = graph->conflicting(lanelets.at(2020).invert());
511 ASSERT_EQ(result.size(), 1ul);
512 EXPECT_EQ(result.front().lanelet()->inverted(), lanelets.at(2020).inverted());
516 auto result = graph->conflicting(lanelets.at(2005));
517 ASSERT_EQ(result.size(), 1ul);
518 EXPECT_EQ(result.front(), lanelets.at(2006));
522 auto result = graph->conflicting(lanelets.at(2008));
523 ASSERT_EQ(result.size(), 1ul);
524 EXPECT_EQ(result.front(), lanelets.at(2009));
531 auto llt = [&](
auto id) ->
ConstLanelet {
return lanelets.at(
id); };
532 EXPECT_EQ(graph->left(lanelets.at(2012)), llt(2011));
533 EXPECT_EQ(graph->adjacentLeft(lanelets.at(2015)), llt(2014));
534 EXPECT_EQ(graph->right(lanelets.at(2011)), llt(2012));
535 EXPECT_EQ(graph->adjacentRight(lanelets.at(2014)), llt(2015));