test_relations.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 
3 #include <boost/optional/optional_io.hpp>
4 
6 #include "test_routing_map.h"
7 
8 using namespace lanelet;
9 using namespace lanelet::routing::tests;
10 
11 TEST_F(GermanVehicleGraph, LaneChangesLeft) { // NOLINT
12  // Multiple1
13  Optional<ConstLanelet> left = graph->left(lanelets.at(2001));
14  EXPECT_TRUE((!!left));
15  EXPECT_TRUE(*left == lanelets.at(2003));
16 
17  left = graph->left(lanelets.at(2002));
18  EXPECT_FALSE((!!left));
19 }
20 
21 TEST_F(GermanVehicleGraph, LaneChangesLeftMerging) { // NOLINT
22  Optional<ConstLanelet> left = graph->left(lanelets.at(2005));
23  EXPECT_FALSE((!!left));
24 
25  left = graph->left(lanelets.at(2006));
26  EXPECT_FALSE((!!left));
27 }
28 
29 TEST_F(GermanVehicleGraph, LaneChangesLeftDiverging) { // NOLINT
30  Optional<ConstLanelet> left = graph->left(lanelets.at(2008));
31  EXPECT_FALSE((!!left));
32 
33  left = graph->left(lanelets.at(2009));
34  EXPECT_FALSE((!!left));
35 }
36 
37 TEST_F(GermanVehicleGraph, LaneChangesLeftMaxHose) { // NOLINT
38  Optional<ConstLanelet> left = graph->left(lanelets.at(2016));
39  EXPECT_FALSE((!!left));
40 
41  left = graph->left(lanelets.at(2020));
42  EXPECT_FALSE((!!left));
43 }
44 
45 TEST_F(GermanVehicleGraph, LaneChangesLeftInvalid) { // NOLINT
46  ConstLanelet invalidLanelet;
47  Optional<ConstLanelet> left = graph->left(invalidLanelet);
48  EXPECT_FALSE((!!left));
49 }
50 
51 TEST_F(GermanVehicleGraph, LaneChangesRight) { // NOLINT
52  // Multiple1
53  Optional<ConstLanelet> right = graph->right(lanelets.at(2003));
54  EXPECT_TRUE((!!right));
55  EXPECT_TRUE(*right == lanelets.at(2001));
56 
57  right = graph->right(lanelets.at(2004));
58  EXPECT_FALSE((!!right));
59 
60  right = graph->right(lanelets.at(2001));
61  EXPECT_FALSE((!!right));
62 
63  right = graph->right(lanelets.at(2002));
64  EXPECT_FALSE((!!right));
65 }
66 
67 TEST_F(GermanVehicleGraph, LaneChangesRightMerging) { // NOLINT
68  Optional<ConstLanelet> right = graph->right(lanelets.at(2006));
69  EXPECT_FALSE((!!right));
70 
71  right = graph->right(lanelets.at(2005));
72  EXPECT_FALSE((!!right));
73 }
74 
75 TEST_F(GermanVehicleGraph, LaneChangesRightDiverging) { // NOLINT
76  Optional<ConstLanelet> right = graph->right(lanelets.at(2008));
77  EXPECT_FALSE((!!right));
78 
79  right = graph->right(lanelets.at(2009));
80  EXPECT_FALSE((!!right));
81 }
82 
83 TEST_F(GermanVehicleGraph, LaneChangesRightMaxHose) { // NOLINT
84  Optional<ConstLanelet> right = graph->right(lanelets.at(2016));
85  EXPECT_FALSE((!!right));
86 
87  right = graph->right(lanelets.at(2020));
88  EXPECT_FALSE((!!right));
89 }
90 
91 TEST_F(GermanVehicleGraph, LaneChangesRightInvalid) { // NOLINT
92  // Invalid
93  ConstLanelet invalidLanelet;
94  Optional<ConstLanelet> right = graph->right(invalidLanelet);
95  EXPECT_FALSE((!!right));
96 }
97 
98 TEST_F(GermanVehicleGraph, AllLaneChangesLeft) { // NOLINT
99  // Multiple2
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());
104 
105  left = graph->lefts(lanelets.at(2011));
106  EXPECT_TRUE(left.empty());
107 
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());
111 
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());
116 }
117 
118 TEST_F(GermanVehicleGraph, AllLaneChangesRight) { // NOLINT
119  // Multiple2
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());
124 
125  right = graph->rights(lanelets.at(2012));
126  EXPECT_TRUE(right.empty());
127 
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());
132 
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());
136 }
137 
138 TEST_F(GermanVehicleGraph, FollowingWithoutLaneChange) { // NOLINT
139  // Multiple1
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());
143 
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());
147 
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());
151 
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());
155 }
156 
157 TEST_F(GermanVehicleGraph, FollowingWithoutLaneChangeMerging) { // NOLINT
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());
161 }
162 
163 TEST_F(GermanVehicleGraph, FollowingWithoutLaneChangeDiverging) { // NOLINT
164  // Single Lane -> Diverging
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());
169 }
170 
171 TEST_F(GermanVehicleGraph, FollowingWithoutLaneChangeMaxHose) { // NOLINT
172  // Max Hose Problem
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());
176 
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());
180 
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());
184 
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());
188 
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());
192 
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());
196 }
197 
198 TEST_F(GermanVehicleGraph, FollowingWithoutLaneChangeInvalid) { // NOLINT
199  // Invalid
200  ConstLanelet invalidLanelet;
201  ConstLanelets following = graph->following(invalidLanelet, false);
202  EXPECT_TRUE(following.empty());
203 }
204 
205 TEST_F(GermanVehicleGraph, FollowingWithLaneChange) { // NOLINT
206  // Multiple1
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());
211 
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());
216 
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());
220 
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());
224 }
225 
226 TEST_F(GermanVehicleGraph, FollowingWithLaneChangeMerging) { // NOLINT
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());
230 
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());
234 }
235 
236 TEST_F(GermanVehicleGraph, FollowingWithLaneChangeDiverging) { // NOLINT
237  // Single Lane -> Diverging
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());
242 }
243 
244 TEST_F(GermanVehicleGraph, FollowingWithLaneChangeMaxHose) { // NOLINT
245  // Max Hose Problem
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());
249 
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());
253 
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());
257 
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());
261 
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());
265 
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());
269 }
270 
271 TEST_F(GermanVehicleGraph, PreviousWithoutLaneChange) { // NOLINT
272  // Multiple1
273  ConstLanelets previous;
274  previous = graph->previous(lanelets.at(2001), false);
275  EXPECT_EQ(previous.size(), 0ul);
276 
277  previous = graph->previous(lanelets.at(2003), false);
278  EXPECT_EQ(previous.size(), 0ul);
279 
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());
283 
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());
287 }
288 
289 TEST_F(GermanVehicleGraph, PreviousWithoutLaneChangeMerging) { // NOLINT
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());
293 
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());
297 }
298 
299 TEST_F(GermanVehicleGraph, PreviousWithoutLaneChangeSingleLane) { // NOLINT
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());
304 }
305 
306 TEST_F(GermanVehicleGraph, PreviousWithoutLaneChangeDiverging) { // NOLINT
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());
310 
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());
314 }
315 
316 TEST_F(GermanVehicleGraph, PreviousWithoutLaneChangeMaxHose) { // NOLINT
317  // Max Hose Problem
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());
321 
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());
325 
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());
329 
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());
333 
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());
337 
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());
341 
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());
345 
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());
349 }
350 
351 TEST_F(GermanVehicleGraph, PreviousWithoutLaneChangeInvalid) { // NOLINT
352  ConstLanelet invalidLanelet;
353  ConstLanelets previous = graph->previous(invalidLanelet, false);
354  EXPECT_TRUE(previous.empty());
355 }
356 
357 TEST_F(GermanVehicleGraph, PreviousWithLaneChange) { // NOLINT
358  // Multiple1
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());
362 
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());
366 
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());
370 
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());
374 }
375 
376 TEST_F(GermanVehicleGraph, PreviousWithLaneChangeMerging) { // NOLINT
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());
380 
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());
384 }
385 
386 TEST_F(GermanVehicleGraph, PreviousWithLaneChangeSingleLane) { // NOLINT
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());
391 }
392 
393 TEST_F(GermanVehicleGraph, PreviousWithLaneChangeDiverging) { // NOLINT
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());
397 
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());
401 }
402 
403 TEST_F(GermanVehicleGraph, PreviousWithLaneChangeMaxHose) { // NOLINT
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());
407 
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());
411 
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());
415 
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());
419 
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());
423 
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());
427 
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());
431 
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());
435 }
436 
437 TEST_F(GermanVehicleGraph, PreviousWithLaneChangeInvalid) { // NOLINT
438  ConstLanelet invalidLanelet;
439  ConstLanelets previous = graph->previous(invalidLanelet, true);
440  EXPECT_TRUE(previous.empty());
441 }
442 
443 TEST_F(GermanVehicleGraph, GetBesides) { // NOLINT
444  // Diverging2
445  ConstLanelets laneletSet;
446  laneletSet = graph->besides(lanelets.at(2010));
447  ASSERT_EQ(1ul, laneletSet.size());
448  EXPECT_EQ(laneletSet[0], lanelets.at(2010));
449 
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));
454 
455  // Multiple2
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));
461 
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));
467 
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));
473 }
474 
475 TEST_F(GermanVehicleGraph, conflicting) { // NOLINT
476  // Normal Lanelets
477  auto result = graph->conflicting(lanelets.at(2007));
478  EXPECT_EQ(result.size(), 0ul);
479 
480  result = graph->conflicting(lanelets.at(2012));
481  EXPECT_EQ(result.size(), 0ul);
482 
483  result = graph->conflicting(lanelets.at(2001));
484  EXPECT_EQ(result.size(), 0ul);
485 
486  result = graph->conflicting(lanelets.at(2005));
487  EXPECT_EQ(result.size(), 1ul);
488 }
489 
490 TEST_F(GermanVehicleGraph, conflicting3d) { // NOLINT
491  // Bridge lanelet
492  auto result = graph->conflicting(lanelets.at(2005));
493  ASSERT_EQ(result.size(), 1ul);
494  EXPECT_TRUE(result.front() == lanelets.at(2006));
495 
496  result = graph->conflicting(lanelets.at(2006));
497  ASSERT_EQ(result.size(), 1ul);
498  EXPECT_TRUE(result.front() == lanelets.at(2005));
499 
500  result = graph->conflicting(lanelets.at(2032));
501  EXPECT_EQ(result.size(), 0ul);
502 }
503 
504 TEST_F(GermanVehicleGraph, conflictingBothWays) { // NOLINT
505  // Both ways Lanelet
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());
509 
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());
513 }
514 
515 TEST_F(GermanVehicleGraph, conflictingMerging) { // NOLINT
516  auto result = graph->conflicting(lanelets.at(2005));
517  ASSERT_EQ(result.size(), 1ul);
518  EXPECT_EQ(result.front(), lanelets.at(2006));
519 }
520 
521 TEST_F(GermanVehicleGraph, conflictingDiverging) { // NOLINT
522  auto result = graph->conflicting(lanelets.at(2008));
523  ASSERT_EQ(result.size(), 1ul);
524  EXPECT_EQ(result.front(), lanelets.at(2009));
525 }
526 
527 TEST_F(RoutingGraphTest, routingCostOnLaneChange) { // NOLINT
528  // tests that all lane changes are not possible when the space for a lane change is too small according to the routing
529  // cost object
530  auto graph = setUpGermanVehicleGraph(*testData.laneletMap, 2, 2, 3);
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));
536 }
RoutingGraph.h
lanelet::routing::tests::RoutingGraphTest
Definition: test_routing_map.h:484
lanelet
lanelet::routing::tests
Definition: test_routing_map.h:17
id
Id id
right
BasicPolygon3d right
Definition: LaneletPath.cpp:99
lanelet::routing::tests::GermanVehicleGraph
Definition: test_routing_map.h:493
lanelet::routing::tests::setUpGermanVehicleGraph
RoutingGraphPtr setUpGermanVehicleGraph(LaneletMap &map, double laneChangeCost=2., double participantHeight=2., double minLaneChangeLength=0.)
Definition: test_routing_map.h:19
Optional
boost::optional< T > Optional
TEST_F
TEST_F(GermanVehicleGraph, LaneChangesLeft)
Definition: test_relations.cpp:11
left
BasicPolygon3d left
Definition: LaneletPath.cpp:98
lanelet::ConstLanelet
test_routing_map.h
ConstLanelets
std::vector< ConstLanelet > ConstLanelets


lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Sun Oct 27 2024 02:27:49