test_routing_map.h
Go to the documentation of this file.
1 #include <gtest/gtest.h>
3 #include <lanelet2_core/primitives/Point.h>
6 
7 #include <memory>
8 #include <utility>
9 
12 
15 namespace lanelet {
16 namespace routing {
17 namespace tests {
18 
19 inline RoutingGraphPtr setUpGermanVehicleGraph(LaneletMap& map, double laneChangeCost = 2.,
20  double participantHeight = 2., double minLaneChangeLength = 0.) {
23  RoutingCostPtrs costPtrs{std::make_shared<RoutingCostDistance>(laneChangeCost, minLaneChangeLength),
24  std::make_shared<RoutingCostTravelTime>(laneChangeCost)};
25  RoutingGraph::Configuration configuration;
26  configuration.insert(std::make_pair(RoutingGraph::ParticipantHeight, participantHeight));
27  return RoutingGraph::build(map, *trafficRules, costPtrs, configuration);
28 }
29 
30 inline RoutingGraphPtr setUpGermanPedestrianGraph(LaneletMap& map, double laneChangeCost = 2.) {
31  traffic_rules::TrafficRulesPtr trafficRules{
33  RoutingCostPtrs costPtrs{std::make_shared<RoutingCostDistance>(laneChangeCost)};
34  return RoutingGraph::build(map, *trafficRules, costPtrs);
35 }
36 
37 inline RoutingGraphPtr setUpGermanBicycleGraph(LaneletMap& map, double laneChangeCost = 2.) {
38  traffic_rules::TrafficRulesPtr trafficRules{
40  RoutingCostPtrs costPtrs{std::make_shared<RoutingCostDistance>(laneChangeCost)};
41  return RoutingGraph::build(map, *trafficRules, costPtrs);
42 }
43 
45  public:
47  initPoints();
49  initLanelets();
50  initAreas();
51  laneletMap = std::make_shared<LaneletMap>(lanelets, areas, std::unordered_map<Id, RegulatoryElementPtr>(),
52  std::unordered_map<Id, Polygon3d>(), lines, points);
56  }
57 
58  void addPoint(double x, double y, double z) {
59  pointId++;
60  points.insert(std::pair<Id, Point3d>(pointId, Point3d(pointId, x, y, z)));
61  }
62 
63  void addLine(const Points3d& points) {
64  lineId++;
65  lines.insert(std::pair<Id, LineString3d>(lineId, LineString3d(lineId, points)));
66  }
67 
69  laneletId++;
72  lanelets.insert(std::make_pair(laneletId, ll));
73  }
74 
76  laneletId++;
79  lanelets.insert(std::make_pair(laneletId, ll));
80  }
81 
82  void addAreaPedestrian(const LineStrings3d& outerBound) {
83  Area area(areaId, outerBound);
85  areas.emplace(areaId, area);
86  areaId++;
87  }
88 
89  Id pointId{0};
90  Id lineId{1000};
91  Id laneletId{2000};
92  Id areaId{3000};
93  std::unordered_map<Id, Lanelet> lanelets;
94  std::unordered_map<Id, Point3d> points;
95  std::unordered_map<Id, LineString3d> lines;
96  std::unordered_map<Id, Area> areas;
97  const double laneChangeCost{2.};
100 
101  private:
102  void initPoints() {
103  points.clear();
104  addPoint(0., 1., 0.); // p1
105  addPoint(1., 1., 0.);
106  addPoint(2., 1.5, 0.);
107  addPoint(0., 0., 0.);
108  addPoint(1., 0., 0.);
109  addPoint(2., 0.5, 0.);
110  addPoint(0., 2., 0.);
111  addPoint(1., 2., 0.);
112  addPoint(2., 2.5, 0.); // p9
113  addPoint(5., 3.5, 0.);
114  addPoint(5., 1.5, 0.); // p11
115  addPoint(7., 3.5, 0.);
116  addPoint(7., 1.5, 0.); // p13
117  addPoint(10., 5., 0.);
118  addPoint(10., 3., 0.);
119  addPoint(10., 1., 0.); // p16
120  addPoint(13., 7., 0.);
121  addPoint(13., 5., 0.);
122  addPoint(13., 3., 0.);
123  addPoint(13., 1., 0.); // p20
124  addPoint(15., 7., 0.);
125  addPoint(15., 5., 0.);
126  addPoint(15., 3., 0.);
127  addPoint(15., 1., 0.); // p24
128  addPoint(5., 14., 0.);
129  addPoint(5., 12., 0.);
130  addPoint(5., 10., 0.);
131  addPoint(7., 14., 0.);
132  addPoint(7., 12., 0.);
133  addPoint(7., 10., 0.);
134  addPoint(10., 13., 0.); // p31
135  addPoint(10., 11., 0.);
136  addPoint(12., 13., 0.);
137  addPoint(12., 11., 0.);
138  addPoint(15., 14., 0.);
139  addPoint(15., 12., 0.);
140  addPoint(15., 10., 0.);
141  addPoint(17., 14., 0.);
142  addPoint(17., 12., 0.);
143  addPoint(17., 10., 0.); // p40
144  addPoint(17., 8., 0.);
145  addPoint(19., 12., 0.);
146  addPoint(19., 10., 0.);
147  addPoint(19., 8., 0.); // p44
148  addPoint(21., 12., 0.);
149  addPoint(21., 10., 0.); // p46
150  addPoint(21., 8., 0.);
151  addPoint(23., 12., 0.); // p48
152  addPoint(23., 10., 0.); // p49
153  addPoint(23., 8., 0.); // p50
154  addPoint(10.5, 14., 0.); // p51
155  addPoint(11.5, 14., 0.); // p52
156  addPoint(10.5, 10., 0.); // p53
157  addPoint(11.5, 10., 0.); // p54
158  addPoint(3., 5., 3.); // p55
159  addPoint(4., 5., 3.); // p56
160  addPoint(3., -1., 3.); // p57
161  addPoint(4., -1., 3.); // p58
162  addPoint(26., 10., 0.); // p59
163  addPoint(28., 10., 0.); // p60
164  addPoint(30., 10., 0.); // p61
165  addPoint(25., 11., 0.); // p62
166  addPoint(26., 12., 0.); // p63
167  addPoint(28., 12., 0.); // p64
168  addPoint(30., 12., 0.); // p65
169  addPoint(25., 13., 0.); // p66
170  addPoint(28., 14., 0.); // p67
171  addPoint(30., 14., 0.); // p68
172  addPoint(32., 10., 0.); // p69
173  addPoint(33., 9., 0.); // p70
174  addPoint(32., 8., 0.); // p71
175  addPoint(33., 7., 0.); // p72
176  addPoint(28., 8., 0.); // p73
177  addPoint(30., 8., 0.); // p74
178  addPoint(35., 10., 0.); // p75
179  addPoint(35., 8., 0.); // p76
180  addPoint(35., 6., 0.); // p77
181  addPoint(37., 9., 0.); // p78
182  addPoint(37., 7., 0.); // p79
183  addPoint(37., 5., 0.); // p80
184  addPoint(38., 10., 0.); // p81
185  addPoint(38., 8., 0.); // p82
186  addPoint(41., 10., 0.); // p83
187  addPoint(41., 8., 0.); // p84
188  addPoint(41., 6., 0.); // p85
189  addPoint(43., 10., 0.); // p86
190  addPoint(43., 8., 0.); // p87
191 
192  // points around areas
193  pointId = 88;
194  addPoint(24, 4, 0); // p89
195  addPoint(26, 4, 0); // p90
196  addPoint(24, 2, 0); // p91
197  addPoint(26, 2, 0); // p92
198  addPoint(27, 5, 0); // p93
199  addPoint(28, 5, 0); // p94
200  addPoint(29, 4, 0); // p95
201  addPoint(29, 2, 0); // p96
202  addPoint(28, 1, 0); // p97
203  addPoint(27, 1, 0); // p98
204  addPoint(27, 0, 0); // p99
205  addPoint(28, 0, 0); // p100
206  addPoint(27, 6, 0); // p101
207  addPoint(28, 6, 0); // p102
208  addPoint(31, 4, 0); // p103
209  addPoint(33, 4, 0); // p104
210  addPoint(31, 2, 0); // p105
211  addPoint(33, 2, 0); // p106
212  addPoint(31, 0, 0); // p107
213 
214  // points on the conflicting and circular section
215  pointId = 119;
216  addPoint(33, 11, 0); // p120
217  addPoint(37, 16, 0); // p121
218  addPoint(37, 14, 0); // p122
219  addPoint(37, 12, 0); // p123
220  addPoint(41, 12, 0); // p124
221  addPoint(32, 16, 0); // p125
222  addPoint(34, 16, 0); // p126
223  addPoint(28, 18, 0); // p127
224  addPoint(28, 20, 0); // p128
225  addPoint(21, 14, 0); // p129
226  addPoint(23, 14, 0); // p130
227  addPoint(19, 14, 0); // p131
228  }
229 
231  lines.clear();
232  addLine(Points3d{points.at(1), points.at(2)}); // l1001
233  lines.at(1001).setAttribute(AttributeNamesString::LaneChange, true);
234  addLine(Points3d{points.at(4), points.at(5)});
235  addLine(Points3d{points.at(2), points.at(3)});
236  addLine(Points3d{points.at(5), points.at(6)});
237  addLine(Points3d{points.at(7), points.at(8)});
238  addLine(Points3d{points.at(8), points.at(9)}); // ls1006
239  addLine(Points3d{points.at(9), points.at(10)});
240  addLine(Points3d{points.at(3), points.at(11)});
242  addLine(Points3d{points.at(3), points.at(10)});
244  addLine(Points3d{points.at(6), points.at(11)}); // ls1010
245  addLine(Points3d{points.at(10), points.at(12)});
246  addLine(Points3d{points.at(11), points.at(13)}); // ls1012
247  addLine(Points3d{points.at(12), points.at(14)});
248  addLine(Points3d{points.at(12), points.at(15)});
249  addLine(Points3d{points.at(13), points.at(15)});
251  addLine(Points3d{points.at(13), points.at(16)}); // ls1016
252  addLine(Points3d{points.at(14), points.at(17)});
253  addLine(Points3d{points.at(14), points.at(18)});
254  addLine(Points3d{points.at(15), points.at(18)});
256  addLine(Points3d{points.at(15), points.at(19)});
257  lines.at(1020).setAttribute(AttributeNamesString::LaneChange, true);
258  addLine(Points3d{points.at(16), points.at(20)}); // ls1021
259  addLine(Points3d{points.at(17), points.at(21)});
260  addLine(Points3d{points.at(18), points.at(22)});
261  lines.at(1023).setAttribute(AttributeNamesString::LaneChange, true);
262  addLine(Points3d{points.at(19), points.at(23)});
263  lines.at(1024).setAttribute(AttributeNamesString::LaneChange, true);
264  addLine(Points3d{points.at(20), points.at(24)});
265  addLine(Points3d{points.at(25), points.at(28)}); // ls1026
266  addLine(Points3d{points.at(26), points.at(29)});
267  addLine(Points3d{points.at(27), points.at(30)});
268  addLine(Points3d{points.at(28), points.at(31)});
269  addLine(Points3d{points.at(29), points.at(31)}); // ls1030
271  addLine(Points3d{points.at(29), points.at(32)});
273  addLine(Points3d{points.at(30), points.at(32)});
274  addLine(Points3d{points.at(31), points.at(33)});
275  addLine(Points3d{points.at(32), points.at(34)});
276  addLine(Points3d{points.at(33), points.at(35)});
277  addLine(Points3d{points.at(33), points.at(36)});
279  addLine(Points3d{points.at(34), points.at(36)});
281  addLine(Points3d{points.at(34), points.at(37)});
282  addLine(Points3d{points.at(35), points.at(38)});
283  addLine(Points3d{points.at(36), points.at(39)});
284  addLine(Points3d{points.at(37), points.at(40)}); // ls1041
285  addLine(Points3d{points.at(39), points.at(42)});
286  addLine(Points3d{points.at(40), points.at(43)});
289  addLine(Points3d{points.at(41), points.at(44)}); // ls1044
290  addLine(Points3d{points.at(42), points.at(45)});
291  addLine(Points3d{points.at(43), points.at(46)}); // ls1046
292  addLine(Points3d{points.at(44), points.at(47)});
293  addLine(Points3d{points.at(45), points.at(48)});
294  addLine(Points3d{points.at(46), points.at(49)});
297  addLine(Points3d{points.at(47), points.at(50)}); // ls1050
298  addLine(Points3d{points.at(51), points.at(53)}); // ls1051
299  addLine(Points3d{points.at(52), points.at(54)}); // ls1052
300  addLine(Points3d{points.at(55), points.at(57)}); // ls1053
301  addLine(Points3d{points.at(56), points.at(58)}); // ls1054
302  addLine(Points3d{points.at(49), points.at(59)}); // ls1055
303  addLine(Points3d{points.at(59), points.at(60)}); // ls1056
304  addLine(Points3d{points.at(60), points.at(61)}); // ls1057
307  addLine(Points3d{points.at(49), points.at(62)}); // ls1058
309  addLine(Points3d{points.at(62), points.at(64)}); // ls1059
311  addLine(Points3d{points.at(48), points.at(63)}); // ls1060
313  addLine(Points3d{points.at(63), points.at(64)}); // ls1061
315  addLine(Points3d{points.at(64), points.at(65)}); // ls1062
316  lines.at(1062).setAttribute(AttributeNamesString::LaneChange, true);
317  addLine(Points3d{points.at(48), points.at(66)}); // ls1063
318  addLine(Points3d{points.at(66), points.at(67)}); // ls1064
319  addLine(Points3d{points.at(67), points.at(68)}); // ls1065
320  addLine(Points3d{points.at(61), points.at(69)}); // ls1066
321  addLine(Points3d{points.at(61), points.at(70)}); // ls1067
322  addLine(Points3d{points.at(74), points.at(71)}); // ls1068
323  addLine(Points3d{points.at(74), points.at(72)}); // ls1069
324  addLine(Points3d{points.at(73), points.at(74)}); // ls1070
325  addLine(Points3d{points.at(69), points.at(75)}); // ls1071
326  addLine(Points3d{points.at(70), points.at(76)}); // ls1072
327  addLine(Points3d{points.at(71), points.at(76)}); // ls1073
328  addLine(Points3d{points.at(72), points.at(77)}); // ls1074
329  addLine(Points3d{points.at(75), points.at(81)}); // ls1075
330  addLine(Points3d{points.at(76), points.at(78)}); // ls1076
331  addLine(Points3d{points.at(76), points.at(82)}); // ls1077
332  addLine(Points3d{points.at(77), points.at(79)}); // ls1078
333  addLine(Points3d{points.at(81), points.at(83)}); // ls1079
334  addLine(Points3d{points.at(78), points.at(83)}); // ls1080
335  addLine(Points3d{points.at(82), points.at(84)}); // ls1081
336  addLine(Points3d{points.at(79), points.at(84)}); // ls1082
339  addLine(Points3d{points.at(80), points.at(85)}); // ls1083
340  addLine(Points3d{points.at(83), points.at(86)}); // ls1084
341  addLine(Points3d{points.at(84), points.at(87)}); // ls1085
342 
343  // linestrings around areas
344  addLine({points.at(89), points.at(90)}); // ls1086
345  addLine({points.at(91), points.at(92)}); // ls1087
346  addLine({points.at(90), points.at(93)}); // ls1088
347  addLine({points.at(93), points.at(94)}); // ls1089
348  addLine({points.at(94), points.at(95)}); // ls1090
349  addLine({points.at(95), points.at(96)}); // ls1091
351  addLine({points.at(96), points.at(97)}); // ls1092
354  addLine({points.at(97), points.at(98)}); // ls1093
357  addLine({points.at(98), points.at(92)}); // ls1094
358  addLine({points.at(95), points.at(103)}); // ls1095
359  addLine({points.at(96), points.at(105)}); // ls1096
360  lines.at(1096).setAttribute(AttributeName::Type, AttributeValueString::Wall);
361  addLine({points.at(103), points.at(105)}); // ls1097
363  addLine({points.at(103), points.at(104)}); // ls1098
364  addLine({points.at(105), points.at(106)}); // ls1099
365  addLine({points.at(99), points.at(100)}); // ls1100
366  addLine({points.at(101), points.at(102)}); // ls1101
367  addLine({points.at(92), points.at(90)}); // ls1102
369  addLine({points.at(97), points.at(107)}); // ls1103
370  addLine({points.at(107), points.at(105)}); // ls1104
371 
372  // lines on the conflicting and circular section
373  lineId = 1199;
374  addLine({points.at(61), points.at(120)}); // ls1200
375  addLine({points.at(74), points.at(70)}); // ls1201
376  addLine({points.at(120), points.at(122)}); // ls1202
377  addLine({points.at(70), points.at(123)}); // ls1203
378  addLine({points.at(121), points.at(124)}); // ls1204
379  addLine({points.at(122), points.at(83)}); // ls1205
380  addLine({points.at(123), points.at(84)}); // ls1206
381  addLine({points.at(68), points.at(125)}); // ls1207
382  addLine({points.at(65), points.at(126)}); // ls1208
383  addLine({points.at(125), points.at(127)}); // ls1209
384  addLine({points.at(126), points.at(128)}); // ls1210
385  addLine({points.at(127), points.at(130)}); // ls1211
386  addLine({points.at(128), points.at(129)}); // ls1212
387  addLine({points.at(130), points.at(48)}); // ls1213
388  addLine({points.at(129), points.at(49)}); // ls1214
389  addLine({points.at(129), points.at(131)}); // ls1215
390  addLine({points.at(130), points.at(42)}); // ls1216
393  }
394  void initLanelets() {
395  lanelets.clear();
396  addLaneletVehicle(lines.at(1001), lines.at(1002)); // ll2001
397  addLaneletVehicle(lines.at(1003), lines.at(1004));
398  addLaneletVehicle(lines.at(1005), lines.at(1001));
399  addLaneletVehicle(lines.at(1006), lines.at(1003)); // ll2004
400  addLaneletVehicle(lines.at(1007), lines.at(1008));
401  addLaneletVehicle(lines.at(1009), lines.at(1010)); // ll2006
402  addLaneletVehicle(lines.at(1011), lines.at(1012)); // ll2007
403  addLaneletVehicle(lines.at(1013), lines.at(1015)); // ll2008
404  addLaneletVehicle(lines.at(1014), lines.at(1016)); // ll2009
405  addLaneletVehicle(lines.at(1017), lines.at(1019)); // ll2010
406  addLaneletVehicle(lines.at(1018), lines.at(1020)); // ll2011
407  addLaneletVehicle(lines.at(1020), lines.at(1021)); // ll2012
408  addLaneletVehicle(lines.at(1022), lines.at(1023)); // ll2013
409  addLaneletVehicle(lines.at(1023), lines.at(1024)); // ll2014
410  addLaneletVehicle(lines.at(1024), lines.at(1025)); // ll2015
411  addLaneletVehicle(lines.at(1027).invert(), lines.at(1026).invert());
412  addLaneletVehicle(lines.at(1027), lines.at(1028));
413  addLaneletVehicle(lines.at(1031).invert(), lines.at(1029).invert());
414  addLaneletVehicle(lines.at(1030), lines.at(1032));
415  addLaneletVehicle(lines.at(1033), lines.at(1034));
416  lanelets.at(2020).setAttribute(AttributeName::OneWay, false);
417  addLaneletVehicle(lines.at(1037).invert(), lines.at(1035).invert());
418  addLaneletVehicle(lines.at(1036), lines.at(1038));
420  addLaneletVehicle(lines.at(1040).invert(), lines.at(1039).invert());
421  addLaneletVehicle(lines.at(1040), lines.at(1041)); // ll2024
422  addLaneletVehicle(lines.at(1042), lines.at(1043));
423  addLaneletVehicle(lines.at(1043), lines.at(1044));
424  addLaneletVehicle(lines.at(1045), lines.at(1046)); // ll2027
425  addLaneletVehicle(lines.at(1046), lines.at(1047));
426  addLaneletVehicle(lines.at(1048), lines.at(1049));
427  addLaneletVehicle(lines.at(1049), lines.at(1050)); // ll2030
428  addLaneletPedestrian(lines.at(1051), lines.at(1052)); // ll2031
429  addLaneletVehicle(lines.at(1053), lines.at(1054)); // ll2032
430  addLaneletVehicle(lines.at(1060), lines.at(1055)); // ll2033
431  addLaneletVehicle(lines.at(1061), lines.at(1056)); // ll2034
432  addLaneletVehicle(lines.at(1062), lines.at(1057)); // ll2035
433  addLaneletVehicle(lines.at(1063), lines.at(1058)); // ll2036
434  addLaneletVehicle(lines.at(1064), lines.at(1059)); // ll2037
435  addLaneletVehicle(lines.at(1065), lines.at(1062)); // ll2038
436  addLaneletVehicle(lines.at(1066), lines.at(1068)); // ll2039
437  addLaneletVehicle(lines.at(1067), lines.at(1069)); // ll2040
438  addLaneletVehicle(lines.at(1057), lines.at(1070)); // ll2041
439  addLaneletVehicle(lines.at(1071), lines.at(1073)); // ll2042
440  addLaneletVehicle(lines.at(1072), lines.at(1074)); // ll2043
441  addLaneletVehicle(lines.at(1075), lines.at(1077)); // ll2044
442  addLaneletVehicle(lines.at(1076), lines.at(1078)); // ll2045
443  addLaneletVehicle(lines.at(1079), lines.at(1081)); // ll2046
444  addLaneletVehicle(lines.at(1080), lines.at(1082)); // ll2047
445  addLaneletVehicle(lines.at(1082), lines.at(1083)); // ll2048
446  addLaneletVehicle(lines.at(1084), lines.at(1085)); // ll2049
447 
448  // area
449  addLaneletPedestrian(lines.at(1086), lines.at(1087)); // ll2050
450  lanelets.at(2050).setAttribute(AttributeName::OneWay, true);
451  addLaneletPedestrian(lines.at(1101), lines.at(1089)); // ll2051
452  addLaneletPedestrian(lines.at(1093).invert(), lines.at(1100)); // ll2052
453  lanelets.at(2052).setAttribute(AttributeName::OneWay, true);
454  addLaneletPedestrian(lines.at(1098), lines.at(1099)); // ll2053
455 
456  // lanelets on conflicting section
457  laneletId = 2059;
458  addLaneletVehicle(lines.at(1200), lines.at(1201)); // ll2060
459  addLaneletVehicle(lines.at(1202), lines.at(1203)); // ll2061
460  addLaneletVehicle(lines.at(1204), lines.at(1205)); // ll2062
461  addLaneletVehicle(lines.at(1205), lines.at(1206)); // ll2063
462  addLaneletVehicle(lines.at(1207), lines.at(1208)); // ll2064
463  addLaneletVehicle(lines.at(1209), lines.at(1210)); // ll2065
464  addLaneletVehicle(lines.at(1211), lines.at(1212)); // ll2066
465  addLaneletVehicle(lines.at(1213), lines.at(1214)); // ll2067
466  addLaneletVehicle(lines.at(1216), lines.at(1215)); // ll2068
467  }
468 
469  void initAreas() {
470  addAreaPedestrian({lines.at(1102), lines.at(1088), lines.at(1089), lines.at(1090), lines.at(1091), lines.at(1092),
471  lines.at(1093), lines.at(1094)}); // ar3000
472  addAreaPedestrian({lines.at(1095), lines.at(1097), lines.at(1096), lines.at(1091).invert()}); // ar3001
473  // addAreaPedestrian({lines.at(1096).invert(), lines.at(1092), lines.at(1103), lines.at(1104)}); // ar3002
475  {lines.at(1096), lines.at(1104).invert(), lines.at(1103).invert(), lines.at(1092).invert()}); // ar3002
477  }
478 };
479 
480 namespace { // NOLINT
481 static RoutingGraphTestData testData; // NOLINT
482 } // namespace
483 
484 class RoutingGraphTest : public ::testing::Test {
485  public:
486  const std::unordered_map<Id, Lanelet>& lanelets{testData.lanelets};
487  const std::unordered_map<Id, Area>& areas{testData.areas};
488  const std::unordered_map<Id, Point3d>& points{testData.points};
489  const std::unordered_map<Id, LineString3d>& lines{testData.lines};
490  const LaneletMapConstPtr laneletMap{testData.laneletMap};
491 };
492 
494  protected:
495  GermanVehicleGraph() { EXPECT_NO_THROW(graph->checkValidity()); } // NOLINT
496 
497  public:
498  RoutingGraphConstPtr graph{testData.vehicleGraph};
499  uint8_t numCostModules{2};
500 };
501 
503  protected:
504  GermanPedestrianGraph() { EXPECT_NO_THROW(graph->checkValidity()); } // NOLINT
505 
506  public:
507  RoutingGraphConstPtr graph{testData.pedestrianGraph};
508  uint8_t numCostModules{2};
509 };
510 
512  protected:
513  GermanBicycleGraph() { EXPECT_NO_THROW(graph->checkValidity()); } // NOLINT
514 
515  public:
516  RoutingGraphConstPtr graph{testData.bicycleGraph};
517  uint8_t numCostModules{2};
518 };
519 
520 template <typename T>
521 class AllGraphsTest : public T {};
522 
523 using AllGraphs = testing::Types<GermanVehicleGraph, GermanPedestrianGraph, GermanBicycleGraph>;
524 
525 #ifndef TYPED_TEST_SUITE
526 // backwards compability with old gtest versions
527 #define TYPED_TEST_SUITE TYPED_TEST_CASE
528 #endif
529 
530 TYPED_TEST_SUITE(AllGraphsTest, AllGraphs);
531 } // namespace tests
532 } // namespace routing
533 } // namespace lanelet
lanelet::routing::tests::RoutingGraphTest::areas
const std::unordered_map< Id, Area > & areas
Definition: test_routing_map.h:487
lanelet::LineStrings3d
std::vector< LineString3d > LineStrings3d
lanelet::routing::tests::RoutingGraphTestData::vehicleGraph
RoutingGraphPtr vehicleGraph
Definition: test_routing_map.h:98
lanelet::routing::tests::RoutingGraphTest::lanelets
const std::unordered_map< Id, Lanelet > & lanelets
Definition: test_routing_map.h:486
RoutingGraph.h
lanelet::routing::tests::RoutingGraphTest
Definition: test_routing_map.h:484
LaneletMap.h
lanelet::LaneletMapPtr
std::shared_ptr< LaneletMap > LaneletMapPtr
lanelet::routing::tests::RoutingGraphTestData::addPoint
void addPoint(double x, double y, double z)
Definition: test_routing_map.h:58
lanelet
lanelet::AttributeNamesString::LaneChange
static constexpr const char LaneChange[]
lanelet::routing::RoutingGraph::ParticipantHeight
static constexpr const char ParticipantHeight[]
Defined configuration attributes.
Definition: RoutingGraph.h:74
TrafficRulesFactory.h
lanelet::routing::RoutingCostPtrs
std::vector< RoutingCostPtr > RoutingCostPtrs
Definition: Forward.h:43
lanelet::routing::tests::GermanVehicleGraph::GermanVehicleGraph
GermanVehicleGraph()
Definition: test_routing_map.h:495
lanelet::routing::RoutingGraph::build
static RoutingGraphUPtr build(const LaneletMap &laneletMap, const traffic_rules::TrafficRules &trafficRules, const RoutingCostPtrs &routingCosts=defaultRoutingCosts(), const Configuration &config=Configuration())
Main constructor with optional configuration.
Definition: RoutingGraph.cpp:375
lanelet::routing::tests::GermanVehicleGraph::graph
RoutingGraphConstPtr graph
Definition: test_routing_map.h:498
lanelet::Participants::Pedestrian
static constexpr const char Pedestrian[]
lanelet::AttributeValueString::Highway
static constexpr const char Highway[]
lanelet::routing::tests::RoutingGraphTest::laneletMap
const LaneletMapConstPtr laneletMap
Definition: test_routing_map.h:490
lanelet::routing::tests::RoutingGraphTestData::initPoints
void initPoints()
Definition: test_routing_map.h:102
lanelet::AttributeName::OneWay
@ OneWay
lanelet::AttributeValueString::Low
static constexpr const char Low[]
lanelet::routing::tests::GermanPedestrianGraph
Definition: test_routing_map.h:502
lanelet::routing::tests::RoutingGraphTest::lines
const std::unordered_map< Id, LineString3d > & lines
Definition: test_routing_map.h:489
lanelet::routing::tests::GermanBicycleGraph::numCostModules
uint8_t numCostModules
Definition: test_routing_map.h:517
lanelet::routing::tests::AllGraphs
testing::Types< GermanVehicleGraph, GermanPedestrianGraph, GermanBicycleGraph > AllGraphs
Definition: test_routing_map.h:523
lanelet::AttributeValueString::LineThin
static constexpr const char LineThin[]
lanelet::Id
int64_t Id
lanelet::LaneletMapConstPtr
std::shared_ptr< const LaneletMap > LaneletMapConstPtr
right
BasicPolygon3d right
Definition: LaneletPath.cpp:99
lanelet::routing::tests::RoutingGraphTestData::addAreaPedestrian
void addAreaPedestrian(const LineStrings3d &outerBound)
Definition: test_routing_map.h:82
lanelet::routing::tests::AllGraphsTest
Definition: test_routing_map.h:521
lanelet::routing::tests::GermanVehicleGraph
Definition: test_routing_map.h:493
lanelet::routing::tests::RoutingGraphTestData::areas
std::unordered_map< Id, Area > areas
Definition: test_routing_map.h:96
lanelet::Area
lanelet::routing::tests::setUpGermanPedestrianGraph
RoutingGraphPtr setUpGermanPedestrianGraph(LaneletMap &map, double laneChangeCost=2.)
Definition: test_routing_map.h:30
lanelet::AttributeValueString::Walkway
static constexpr const char Walkway[]
lanelet::routing::tests::setUpGermanVehicleGraph
RoutingGraphPtr setUpGermanVehicleGraph(LaneletMap &map, double laneChangeCost=2., double participantHeight=2., double minLaneChangeLength=0.)
Definition: test_routing_map.h:19
lanelet::routing::tests::RoutingGraphTestData::areaId
Id areaId
Definition: test_routing_map.h:92
lanelet::routing::tests::RoutingGraphTestData::bicycleGraph
RoutingGraphPtr bicycleGraph
Definition: test_routing_map.h:98
lanelet::LaneletMap
GermanTrafficRules.h
lanelet::routing::tests::RoutingGraphTestData::lanelets
std::unordered_map< Id, Lanelet > lanelets
Definition: test_routing_map.h:93
lanelet::AttributeValueString::Virtual
static constexpr const char Virtual[]
lanelet::AttributeValueString::Wall
static constexpr const char Wall[]
lanelet::Lanelet
lanelet::AttributeName::Type
@ Type
lanelet::AttributeNamesString::Subtype
static constexpr const char Subtype[]
lanelet::routing::tests::RoutingGraphTest::points
const std::unordered_map< Id, Point3d > & points
Definition: test_routing_map.h:488
lanelet::AttributeValueString::Crosswalk
static constexpr const char Crosswalk[]
lanelet::Locations::Germany
static constexpr char Germany[]
lanelet::Points3d
std::vector< Point3d > Points3d
lanelet::routing::RoutingGraphPtr
std::shared_ptr< RoutingGraph > RoutingGraphPtr
Definition: Forward.h:25
lanelet::AttributeValueString::DashedSolid
static constexpr const char DashedSolid[]
lanelet::routing::tests::setUpGermanBicycleGraph
RoutingGraphPtr setUpGermanBicycleGraph(LaneletMap &map, double laneChangeCost=2.)
Definition: test_routing_map.h:37
lanelet::routing::tests::RoutingGraphTestData::addLaneletVehicle
void addLaneletVehicle(const LineString3d &left, const LineString3d &right)
Definition: test_routing_map.h:68
lanelet::routing::tests::GermanVehicleGraph::numCostModules
uint8_t numCostModules
Definition: test_routing_map.h:499
lanelet::AttributeValueString::Solid
static constexpr const char Solid[]
lanelet::routing::tests::RoutingGraphTestData::laneletId
Id laneletId
Definition: test_routing_map.h:91
lanelet::routing::tests::RoutingGraphTestData::laneletMap
LaneletMapPtr laneletMap
Definition: test_routing_map.h:99
lanelet::routing::tests::RoutingGraphTestData::initLanelets
void initLanelets()
Definition: test_routing_map.h:394
lanelet::AttributeValueString::Curbstone
static constexpr const char Curbstone[]
lanelet::routing::tests::RoutingGraphTestData::pedestrianGraph
RoutingGraphPtr pedestrianGraph
Definition: test_routing_map.h:98
lanelet::routing::tests::GermanPedestrianGraph::numCostModules
uint8_t numCostModules
Definition: test_routing_map.h:508
lanelet::routing::tests::GermanBicycleGraph
Definition: test_routing_map.h:511
lanelet::AttributeValueString::SolidDashed
static constexpr const char SolidDashed[]
lanelet::routing::tests::TYPED_TEST_SUITE
TYPED_TEST_SUITE(AllGraphsTest, AllGraphs)
lanelet::Point3d
lanelet::routing::tests::RoutingGraphTestData::RoutingGraphTestData
RoutingGraphTestData()
Definition: test_routing_map.h:46
left
BasicPolygon3d left
Definition: LaneletPath.cpp:98
lanelet::Participants::Bicycle
static constexpr const char Bicycle[]
lanelet::Participants::Vehicle
static constexpr const char Vehicle[]
lanelet::routing::tests::RoutingGraphTestData::initAreas
void initAreas()
Definition: test_routing_map.h:469
lanelet::routing::tests::RoutingGraphTestData::laneChangeCost
const double laneChangeCost
Definition: test_routing_map.h:97
lanelet::AttributeValueString::Road
static constexpr const char Road[]
lanelet::traffic_rules::TrafficRulesFactory::create
static TrafficRulesUPtr create(const std::string &location, const std::string &participant, TrafficRules::Configuration configuration=TrafficRules::Configuration())
lanelet::routing::tests::GermanBicycleGraph::GermanBicycleGraph
GermanBicycleGraph()
Definition: test_routing_map.h:513
lanelet::routing::tests::RoutingGraphTestData::pointId
Id pointId
Definition: test_routing_map.h:89
lanelet::traffic_rules::TrafficRules::Configuration
std::map< std::string, Attribute > Configuration
lanelet::AttributeValueString::Dashed
static constexpr const char Dashed[]
lanelet::routing::tests::RoutingGraphTestData::addLine
void addLine(const Points3d &points)
Definition: test_routing_map.h:63
lanelet::routing::RoutingGraph::Configuration
std::map< std::string, Attribute > Configuration
Definition: RoutingGraph.h:72
lanelet::routing::RoutingGraphConstPtr
std::shared_ptr< const RoutingGraph > RoutingGraphConstPtr
Definition: Forward.h:27
Primitive< ConstArea >::setAttribute
void setAttribute(AttributeName name, const Attribute &attribute)
lanelet::routing::tests::GermanPedestrianGraph::graph
RoutingGraphConstPtr graph
Definition: test_routing_map.h:507
lanelet::routing::tests::RoutingGraphTestData::lineId
Id lineId
Definition: test_routing_map.h:90
Forward.h
lanelet::routing::tests::RoutingGraphTestData::lines
std::unordered_map< Id, LineString3d > lines
Definition: test_routing_map.h:95
lanelet::routing::tests::RoutingGraphTestData::points
std::unordered_map< Id, Point3d > points
Definition: test_routing_map.h:94
lanelet::routing::tests::RoutingGraphTestData
Definition: test_routing_map.h:44
lanelet::LineString3d
lanelet::routing::tests::RoutingGraphTestData::addLaneletPedestrian
void addLaneletPedestrian(const LineString3d &left, const LineString3d &right)
Definition: test_routing_map.h:75
lanelet::AttributeName::Subtype
@ Subtype
lanelet::routing::tests::RoutingGraphTestData::initLineStrings
void initLineStrings()
Definition: test_routing_map.h:230
ll
LaneletAdjacency ll
Definition: LaneletPath.cpp:88
lanelet::routing::tests::GermanBicycleGraph::graph
RoutingGraphConstPtr graph
Definition: test_routing_map.h:516
lanelet::routing::tests::GermanPedestrianGraph::GermanPedestrianGraph
GermanPedestrianGraph()
Definition: test_routing_map.h:504
lanelet::traffic_rules::TrafficRulesPtr
std::shared_ptr< TrafficRules > TrafficRulesPtr


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