lanelet2_traffic_rules.cpp
Go to the documentation of this file.
2 #include <lanelet2_core/primitives/Lanelet.h>
4 
5 #include "gtest/gtest.h"
8 
13 
14 lanelet::RegulatoryElementPtr getSpeedLimit(const std::string& type, const lanelet::AttributeMap& attributes = {}) {
15  using namespace lanelet;
16  Point3d p1{10, 0, -1};
17 
18  Point3d p2{11, 0, -2};
19  LineString3d sign{7, {p1, p2}};
20  return SpeedLimit::make(5, attributes, {{sign}, type});
21 }
22 
24  using namespace lanelet;
26 }
27 
29  using namespace lanelet;
31 }
32 
34  using namespace lanelet;
36 }
37 
38 class TrafficRules : public ::testing::Test {
39  /* looks like this:
40  * p1----ls4----p8
41  *
42  * left
43  *
44  * p5----ls3----p6----ls6----p10
45  *
46  * lanelet next
47  *
48  * p3----ls2----p4----ls5----p9-----ls9--\
49  * | | \
50  * right ls7 area ls8 nextArea p12
51  * | | /
52  * p1----ls1----p2----ls8----p11----ls9--/
53  */
54  public:
55  lanelet::Point3d p1{1, 0, 0}, p2{2, 2, 0}, p3{3, 0, 2}, p4{4, 2, 2}, p5{5, 0, 4}, p6{6, 2, 4}, p7{7, 0, 6},
56  p8{8, 2, 6}, p9{9, 4, 2}, p10{10, 4, 4}, p11{11, 4, 0}, p12{12, 5, 1};
57  lanelet::LineString3d ls1{1, {p1, p2}}, ls2{2, {p3, p4}}, ls3{3, {p5, p6}}, ls4{4, {p7, p8}}, ls5{5, {p4, p9}},
58  ls6{6, {p6, p10}}, ls7{7, {p2, p4}}, ls8{8, {p9, p11, p2}}, ls9{9, {p9, p12, p11}};
64 };
65 
67  public:
69 };
70 
72  public:
74 };
75 
77  public:
79  lanelet.attributes() = pedestrianAttr;
83  }
85 };
86 
87 namespace can_drive {
88 TEST_F(GermanTrafficRulesVehicle, vehicleCanPassRoadLanelet) { // NOLINT
89  using namespace std::string_literals;
90  lanelet.setAttribute(Attr::Subtype, Value::Road);
91  EXPECT_TRUE(germanVehicle->canPass(lanelet));
92  EXPECT_TRUE(germanVehicle->isOneWay(lanelet));
93 }
94 
95 TEST_F(GermanTrafficRulesVehicle, vehicleCanNotPassNonRoadLanelet) { // NOLINT
96  lanelet.setAttribute(Attr::Subtype, Value::Walkway);
97  EXPECT_FALSE(germanVehicle->canPass(lanelet));
98 }
99 
100 TEST_F(GermanTrafficRulesVehicle, vehicleCanPassVehicleLanelet) { // NOLINT
101  using namespace std::string_literals;
102  lanelet.setAttribute(Attr::Subtype, Value::Road);
103  lanelet.setAttribute(Participants::tag(Participants::Vehicle), true);
104  EXPECT_TRUE(germanVehicle->canPass(lanelet));
105  EXPECT_TRUE(germanVehicle->isOneWay(lanelet));
106 }
107 
108 TEST_F(GermanTrafficRulesVehicle, vehicleCanNotPassNonVehicleLanelet) { // NOLINT
109  lanelet.setAttribute(Attr::Subtype, Value::Road);
110  lanelet.setAttribute(Participants::tag(Participants::Vehicle), false);
111  EXPECT_FALSE(germanVehicle->canPass(lanelet));
112 }
113 
114 TEST_F(GermanTrafficRulesVehicle, oneWayLanelet) { // NOLINT
115  lanelet.setAttribute(Attr::OneWay, false);
116  EXPECT_FALSE(germanVehicle->isOneWay(lanelet));
117 }
118 
119 TEST_F(GermanTrafficRulesVehicle, vehicleCanDriveIntoNextLanelet) { // NOLINT
120  EXPECT_TRUE(germanVehicle->canPass(lanelet, next));
121 }
122 
123 TEST_F(GermanTrafficRulesVehicle, vehicleCanNotDriveBackwardsFromLanelet) { // NOLINT
124  EXPECT_FALSE(germanVehicle->canPass(next, lanelet));
125 }
126 
127 TEST_F(GermanTrafficRulesVehicle, vehicleCanNotDriveAgainstDrivingDirection) { // NOLINT
128  EXPECT_FALSE(germanVehicle->canPass(next.invert(), lanelet.invert()));
129 }
130 
131 TEST_F(GermanTrafficRulesVehicle, vehicleCanNotDriveWhereCarsDrive) { // NOLINT
132  lanelet.setAttribute(Attr::Subtype, Value::Road);
133  lanelet.setAttribute(Participants::tag(Participants::VehicleCar), true);
134  EXPECT_FALSE(germanVehicle->canPass(lanelet));
135 }
136 
137 TEST_F(GermanTrafficRulesVehicle, carsCanDriveWhereCarsDrive) { // NOLINT
138  using namespace lanelet;
139  lanelet.setAttribute(Attr::Subtype, Value::Road);
140  lanelet.setAttribute(Participants::tag(Participants::VehicleCar), true);
141  auto germanCar = traffic_rules::TrafficRulesFactory::create(Locations::Germany, Participants::VehicleCar);
142  EXPECT_TRUE(germanCar->canPass(lanelet));
143 }
144 
145 TEST_F(GermanTrafficRulesVehicle, vehicleCanDriveBackwardsFromTwoWayLanelet) { // NOLINT
146  lanelet.setAttribute(Attr::OneWay, false);
147  next.setAttribute(Attr::OneWay, false);
148  EXPECT_FALSE(germanVehicle->canPass(next, lanelet));
149  EXPECT_TRUE(germanVehicle->canPass(next.invert(), lanelet.invert()));
150 }
151 
152 TEST_F(GermanTrafficRulesVehicle, vehicleCanNotDriveBackwardsFromSpecialTwoWayLanelet) { // NOLINT
153  using namespace std::string_literals;
154  lanelet.setAttribute(AttrStr::OneWay + ":"s + Participants::Bicycle, false);
155  next.setAttribute(AttrStr::OneWay + ":"s + Participants::Bicycle, false);
156  EXPECT_FALSE(germanVehicle->canPass(next, lanelet));
157  EXPECT_FALSE(germanVehicle->canPass(next.invert(), lanelet.invert()));
158 }
159 
160 TEST_F(GermanTrafficRulesVehicle, canNotDriveToRandomLanelet) { // NOLINT
161  EXPECT_FALSE(germanVehicle->canPass(left, right));
162 }
163 
164 TEST_F(GermanTrafficRulesBike, bikeCanNotPassVehicleLanelet) { // NOLINT
165  lanelet.setAttribute(Attr::Subtype, Value::Road);
166  lanelet.setAttribute(Participants::tag(Participants::Vehicle), true);
167  EXPECT_FALSE(germanBike->canPass(lanelet));
168  EXPECT_TRUE(germanBike->isOneWay(lanelet));
169 }
170 
171 TEST_F(GermanTrafficRulesBike, bikeCanPassBikeLaneLanelet) { // NOLINT
173  EXPECT_TRUE(germanBike->canPass(lanelet));
174  EXPECT_TRUE(germanBike->isOneWay(lanelet));
175 }
176 
177 TEST_F(GermanTrafficRulesBike, bikeCanNotPassNonVehicleLanelet) { // NOLINT
179  lanelet.setAttribute(Participants::tag(Participants::Vehicle), false);
180  EXPECT_FALSE(germanBike->canPass(lanelet));
181 }
182 
183 TEST_F(GermanTrafficRulesBike, oneWayLanelet) { // NOLINT
184  lanelet.setAttribute(Attr::OneWay, false);
185  EXPECT_FALSE(germanBike->isOneWay(lanelet));
186 }
187 
188 TEST_F(GermanTrafficRulesBike, bikeCanDriveIntoNextLanelet) { // NOLINT
190  next.setAttribute(Attr::Subtype, Value::BicycleLane);
191  EXPECT_TRUE(germanBike->canPass(lanelet, next));
192 }
193 
194 TEST_F(GermanTrafficRulesBike, bikeCanNotDriveBackwardsFromLanelet) { // NOLINT
196  next.setAttribute(Attr::Subtype, Value::BicycleLane);
197  EXPECT_FALSE(germanBike->canPass(next, lanelet));
198 }
199 
200 TEST_F(GermanTrafficRulesBike, bikeCanNotDriveAgainstDrivingDirection) { // NOLINT
202  next.setAttribute(Attr::Subtype, Value::BicycleLane);
203  EXPECT_FALSE(germanBike->canPass(next.invert(), lanelet.invert()));
204 }
205 
206 TEST_F(GermanTrafficRulesBike, bikeCanDriveBackwardsFromTwoWayLanelet) { // NOLINT
208  next.setAttribute(Attr::Subtype, Value::BicycleLane);
209  lanelet.setAttribute(Attr::OneWay, false);
210  next.setAttribute(Attr::OneWay, false);
211  EXPECT_FALSE(germanBike->canPass(next, lanelet));
212  EXPECT_TRUE(germanBike->canPass(next.invert(), lanelet.invert()));
213 }
214 
215 TEST_F(GermanTrafficRulesBike, bikeCanDriveBackwardsFromSpecialTwoWayLanelet) { // NOLINT
216  using namespace std::string_literals;
217  lanelet.setAttribute(Attr::Subtype, Value::Road);
218  next.setAttribute(Attr::Subtype, Value::Road);
220  next.setAttribute(Attr::Subtype, Value::BicycleLane);
221  lanelet.setAttribute(AttrStr::OneWay + ":"s + Participants::Bicycle, false);
222  next.setAttribute(AttrStr::OneWay + ":"s + Participants::Bicycle, false);
223  EXPECT_FALSE(germanBike->canPass(next, lanelet));
224  EXPECT_TRUE(germanBike->canPass(next.invert(), lanelet.invert()));
225 }
226 
227 TEST_F(GermanTrafficRulesBike, canNotDriveToRandomLanelet) { // NOLINT
228  EXPECT_FALSE(germanBike->canPass(left, right));
229 }
230 
231 TEST_F(GermanTrafficRulesBike, canNotDriveBikeExplicitlyForbidden) { // NOLINT
232  lanelet.setAttribute(Attr::Subtype, Value::Road);
233  lanelet.setAttribute(Participants::tag(Participants::Bicycle), false);
234  EXPECT_FALSE(germanBike->canPass(lanelet));
235 }
236 
237 TEST_F(GermanTrafficRulesBike, canNotDriveBikeExplicitlyForbiddenVehiclesAllowed) { // NOLINT
238  lanelet.setAttribute(Attr::Subtype, Value::Road);
239  lanelet.setAttribute(Participants::tag(Participants::Bicycle), false);
240  lanelet.setAttribute(Participants::tag(Participants::Vehicle), true);
241  EXPECT_FALSE(germanBike->canPass(lanelet));
242 }
243 
244 TEST_F(GermanTrafficRulesBike, canNotDriveIntoBikeExplicitlyForbidden) { // NOLINT
245  lanelet.setAttribute(Participants::tag(Participants::Bicycle), true);
246  next.setAttribute(Participants::tag(Participants::Bicycle), false);
247  next.setAttribute(Participants::tag(Participants::Vehicle), true);
248  EXPECT_FALSE(germanBike->canPass(lanelet, next));
249 }
250 
251 TEST_F(GermanTrafficRulesPedestrian, canGoToNextLanelet) { // NOLINT
252  EXPECT_TRUE(germanPedestrian->canPass(lanelet, next));
253 }
254 
255 TEST_F(GermanTrafficRulesPedestrian, canNotWalkOnVehicleLanelet) { // NOLINT
256  EXPECT_FALSE(germanPedestrian->canPass(left));
257 }
258 
259 TEST_F(GermanTrafficRulesPedestrian, canNotGoBackFromOneWayLanelet) { // NOLINT
260  next.setAttribute(AttrStr::OneWay + std::string(":") + Participants::Pedestrian, true);
261  EXPECT_FALSE(germanPedestrian->canPass(next.invert(), lanelet.invert()));
262 }
263 
264 TEST_F(GermanTrafficRulesPedestrian, canGoBackFromTwoWayLanelet) { // NOLINT
265  lanelet.setAttribute(Attr::OneWay, false);
266  next.setAttribute(Attr::OneWay, false);
267  EXPECT_TRUE(germanPedestrian->canPass(next.invert(), lanelet.invert()));
268 }
269 
270 TEST_F(GermanTrafficRulesPedestrian, canStandOnPedestrianArea) { // NOLINT
271  area.attributes() = pedestrianAttr;
272  EXPECT_TRUE(germanPedestrian->canPass(area));
273 }
274 
275 TEST_F(GermanTrafficRulesPedestrian, canNotGoIntoUnknownArea) { // NOLINT
276  area.attributes() = pedestrianAttr;
277  right.attributes() = pedestrianAttr;
278  EXPECT_FALSE(germanPedestrian->canPass(area, right));
279 }
280 
281 TEST_F(GermanTrafficRulesPedestrian, canGoAcrossLowCurbstone) { // NOLINT
282  area.attributes() = pedestrianAttr;
283  right.attributes() = pedestrianAttr;
284  ls7.setAttribute(Attr::Type, Value::Curbstone);
285  ls7.setAttribute(Attr::Subtype, Value::Low);
286  right.setAttribute(Attr::OneWay, false);
287  EXPECT_TRUE(germanPedestrian->canPass(area, right.invert()));
288  EXPECT_FALSE(germanPedestrian->canPass(area, right));
289  EXPECT_TRUE(germanPedestrian->canPass(right, area));
290 }
291 
292 TEST_F(GermanTrafficRulesPedestrian, canGoAcrossLowCurbstonetoNextArea) { // NOLINT
293  area.attributes() = pedestrianAttr;
294  nextArea.attributes() = pedestrianAttr;
295  ls8.setAttribute(Attr::Type, Value::Curbstone);
296  ls8.setAttribute(Attr::Subtype, Value::Low);
297  EXPECT_TRUE(germanPedestrian->canPass(area, nextArea));
298  EXPECT_TRUE(germanPedestrian->canPass(nextArea, area));
299 }
300 
301 TEST_F(GermanTrafficRulesPedestrian, canGoRightAcrossLowCurbstone) { // NOLINT
302  area.attributes() = pedestrianAttr;
303  next.attributes() = pedestrianAttr;
304  ls5.setAttribute(Attr::Type, Value::Curbstone);
305  ls5.setAttribute(Attr::Subtype, Value::Low);
306  EXPECT_TRUE(germanPedestrian->canPass(area, next));
307  EXPECT_TRUE(germanPedestrian->canPass(next, area));
308 }
309 
310 TEST_F(GermanTrafficRulesPedestrian, cannotCrossUnrelated) { // NOLINT
311  area.attributes() = pedestrianAttr;
312  left.attributes() = pedestrianAttr;
313  ls5.setAttribute(Attr::Type, Value::Curbstone);
314  ls5.setAttribute(Attr::Subtype, Value::Low);
315  EXPECT_FALSE(germanPedestrian->canPass(area, left));
316  EXPECT_FALSE(germanPedestrian->canPass(left, area));
317 }
318 } // namespace can_drive
319 
320 namespace speed_limits {
321 using namespace lanelet::units::literals;
322 TEST_F(GermanTrafficRulesVehicle, defaultUrbanSpeedlimitIfNoSpeedLimitSet) { // NOLINT
323  lanelet.setAttribute(Attr::Location, Value::Urban);
324  auto limit = germanVehicle->speedLimit(lanelet);
325  EXPECT_EQ(limit.speedLimit, 50_kmh);
326  EXPECT_TRUE(limit.isMandatory);
327 }
328 
329 TEST_F(GermanTrafficRulesVehicle, defaultNonUrbanSpeedlimitIfNoSpeedLimitSet) { // NOLINT
330  lanelet.setAttribute(Attr::Location, Value::Nonurban);
331  auto limit = germanVehicle->speedLimit(lanelet);
332  EXPECT_EQ(limit.speedLimit, 100_kmh);
333  EXPECT_TRUE(limit.isMandatory);
334 }
335 
336 TEST_F(GermanTrafficRulesVehicle, NoSpeedLimitIfOnHighway) { // NOLINT
337  lanelet.setAttribute(Attr::Location, Value::Nonurban);
338  lanelet.setAttribute(Attr::Subtype, Value::Highway);
339  auto limit = germanVehicle->speedLimit(lanelet);
340  EXPECT_EQ(limit.speedLimit, 130_kmh);
341  EXPECT_FALSE(limit.isMandatory);
342 }
343 
344 TEST_F(GermanTrafficRulesVehicle, OverrideMandatoryLimit) { // NOLINT
345  lanelet.setAttribute(Attr::Location, Value::Nonurban);
346  lanelet.setAttribute(Attr::Subtype, Value::Highway);
347  lanelet.setAttribute(AttrStr::SpeedLimitMandatory, true);
348  auto limit = germanVehicle->speedLimit(lanelet);
349  EXPECT_EQ(limit.speedLimit, 0_kmh);
350  EXPECT_TRUE(limit.isMandatory);
351 }
352 
353 TEST_F(GermanTrafficRulesVehicle, OverrideSpeedLimit) { // NOLINT
354  using namespace lanelet::units::literals;
355  lanelet.setAttribute(Attr::Location, Value::Nonurban);
356  lanelet.setAttribute(Attr::Subtype, Value::Highway);
357  lanelet.attributes()[Attr::SpeedLimit] = 50_kmh;
358  auto limit = germanVehicle->speedLimit(lanelet);
359  EXPECT_EQ(limit.speedLimit, 50_kmh);
360  EXPECT_TRUE(limit.isMandatory);
361 }
362 
363 TEST_F(GermanTrafficRulesVehicle, OverrideSpecialSpeedLimit) { // NOLINT
364  using namespace std::string_literals;
365  using namespace lanelet::units::literals;
366  lanelet.setAttribute(Attr::Location, Value::Nonurban);
367  lanelet.setAttribute(Attr::Subtype, Value::Highway);
368  lanelet.attributes()[AttrStr::SpeedLimit] = 1_kmh;
369  lanelet.attributes()[AttrStr::SpeedLimit + ":"s + Participants::Vehicle] = 50_kmh;
370  auto limit = germanVehicle->speedLimit(lanelet);
371  EXPECT_EQ(limit.speedLimit, 50_kmh);
372  EXPECT_TRUE(limit.isMandatory);
373 }
374 
375 TEST_F(GermanTrafficRulesVehicle, OverrideDifferentSpecialSpeedLimit) { // NOLINT
376  using namespace std::string_literals;
377  using namespace lanelet::units::literals;
378  lanelet.setAttribute(Attr::Location, Value::Nonurban);
379  lanelet.setAttribute(Attr::Subtype, Value::Highway);
380  lanelet.attributes()[AttrStr::SpeedLimit] = 100_kmh;
381  lanelet.attributes()[AttrStr::SpeedLimit + ":"s + Participants::Bicycle] = 50_kmh;
382  auto limit = germanVehicle->speedLimit(lanelet);
383  EXPECT_EQ(limit.speedLimit, 100_kmh);
384  EXPECT_TRUE(limit.isMandatory);
385 }
386 
387 TEST_F(GermanTrafficRulesVehicle, determinesSpeedLimit30) { // NOLINT
388  lanelet.addRegulatoryElement(getSpeedLimit("de274"));
389  auto limit = germanVehicle->speedLimit(lanelet);
390  EXPECT_EQ(limit.speedLimit, 30_kmh);
391  EXPECT_TRUE(limit.isMandatory);
392 }
393 
394 TEST_F(GermanTrafficRulesVehicle, determinesSpeedLimitFromTag) { // NOLINT
395  lanelet.addRegulatoryElement(lanelet::SpeedLimit::make(12, {}, "55 kmh"));
396  auto limit = germanVehicle->speedLimit(lanelet);
397  EXPECT_EQ(limit.speedLimit, 55_kmh);
398  EXPECT_TRUE(limit.isMandatory);
399 }
400 
401 TEST_F(GermanTrafficRulesVehicle, determinesSpeedLimit50) { // NOLINT
402  lanelet.setAttribute(Attr::Location, Value::Nonurban);
403  lanelet.addRegulatoryElement(getSpeedLimit("de274-50"));
404  auto limit = germanVehicle->speedLimit(lanelet);
405  EXPECT_EQ(limit.speedLimit, 50_kmh);
406  EXPECT_TRUE(limit.isMandatory);
407 }
408 
409 TEST_F(GermanTrafficRulesVehicle, determinesSpeedLimit120) { // NOLINT
410  lanelet.setAttribute(Attr::Location, Value::Nonurban);
411  lanelet.setAttribute(Attr::Subtype, Value::Highway);
412  lanelet.addRegulatoryElement(getSpeedLimit("de274-120"));
413  auto limit = germanVehicle->speedLimit(lanelet);
414  EXPECT_EQ(limit.speedLimit, 120_kmh);
415  EXPECT_TRUE(limit.isMandatory);
416 }
417 } // namespace speed_limits
418 
419 namespace lane_change {
420 
421 TEST_F(GermanTrafficRulesVehicle, canNotLaneChangeLeftWithDefaultLine) { // NOLINT
422  EXPECT_FALSE(germanVehicle->canChangeLane(lanelet, left));
423 }
424 
425 TEST_F(GermanTrafficRulesVehicle, canNotLaneChangeToUnconnectedLanelet) { // NOLINT
426  EXPECT_FALSE(germanVehicle->canChangeLane(right, left));
427 }
428 
429 TEST_F(GermanTrafficRulesVehicle, canLaneChangeLeftViaDashedLine) { // NOLINT
430  ls3.setAttribute(Attr::Type, Value::LineThin);
431  ls3.setAttribute(Attr::Subtype, Value::Dashed);
432  EXPECT_TRUE(germanVehicle->canChangeLane(lanelet, left));
433 }
434 
435 TEST_F(GermanTrafficRulesVehicle, canLaneChangeRightViaDashedLine) { // NOLINT
436  ls3.setAttribute(Attr::Type, Value::LineThin);
437  ls3.setAttribute(Attr::Subtype, Value::Dashed);
438  EXPECT_TRUE(germanVehicle->canChangeLane(left, lanelet));
439 }
440 
441 TEST_F(GermanTrafficRulesVehicle, canNotLaneChangeToInvertedLanelet) { // NOLINT
442  ls3.setAttribute(Attr::Type, Value::LineThin);
443  ls3.setAttribute(Attr::Subtype, Value::Dashed);
444  EXPECT_FALSE(germanVehicle->canChangeLane(lanelet, left.invert()));
445 }
446 TEST_F(GermanTrafficRulesVehicle, canNotLaneChangeLaneIfNotDrivable) { // NOLINT
447  ls3.setAttribute(Attr::Type, Value::LineThin);
448  ls3.setAttribute(Attr::Subtype, Value::Dashed);
449  left.setAttribute(Participants::tag(Participants::Vehicle), false);
450  EXPECT_FALSE(germanVehicle->canChangeLane(lanelet, left));
451 }
452 TEST_F(GermanTrafficRulesVehicle, canLaneChangeRightViaDashedSolidLine) { // NOLINT
453  ls3.setAttribute(Attr::Type, Value::LineThin);
454  ls3.setAttribute(Attr::Subtype, Value::DashedSolid);
455  EXPECT_TRUE(germanVehicle->canChangeLane(left, lanelet));
456  EXPECT_FALSE(germanVehicle->canChangeLane(lanelet, left));
457 }
458 TEST_F(GermanTrafficRulesVehicle, canNotLaneChangeViaSolidLine) { // NOLINT
459  ls3.setAttribute(Attr::Type, Value::LineThin);
460  ls3.setAttribute(Attr::Subtype, Value::Solid);
461  EXPECT_FALSE(germanVehicle->canChangeLane(lanelet, left));
462 }
463 TEST_F(GermanTrafficRulesVehicle, canNotLaneChangeViaSolidSolidLine) { // NOLINT
464  ls3.setAttribute(Attr::Type, Value::LineThin);
465  ls3.setAttribute(Attr::Subtype, Value::SolidSolid);
466  EXPECT_FALSE(germanVehicle->canChangeLane(lanelet, left));
467 }
468 
469 TEST_F(GermanTrafficRulesVehicle, canNotLaneChangeIfOverridden) { // NOLINT
470  ls3.setAttribute(Attr::Type, Value::LineThin);
471  ls3.setAttribute(Attr::Subtype, Value::Dashed);
472  ls3.setAttribute(AttrStr::LaneChange, false);
473  EXPECT_FALSE(germanVehicle->canChangeLane(lanelet, left));
474 }
475 
476 TEST_F(GermanTrafficRulesVehicle, canLaneChangeInverted) { // NOLINT
477  ls3.setAttribute(Attr::Type, Value::LineThin);
478  ls3.setAttribute(Attr::Subtype, Value::SolidDashed);
479  lanelet.setAttribute(Attr::OneWay, false);
480  left.setAttribute(Attr::OneWay, false);
481  EXPECT_TRUE(germanVehicle->canChangeLane(lanelet.invert(), left.invert()));
482  EXPECT_FALSE(germanVehicle->canChangeLane(left.invert(), lanelet.invert()));
483 }
484 
485 TEST_F(GermanTrafficRulesVehicle, canNotLaneChangeOnVirtualLine) { // NOLINT
486  ls3.setAttribute(Attr::Type, Value::Virtual);
487  EXPECT_FALSE(germanVehicle->canChangeLane(lanelet, left));
488  EXPECT_FALSE(germanVehicle->canChangeLane(left, lanelet));
489 }
490 
491 TEST_F(GermanTrafficRulesVehicle, canLaneChangeBothSidesExplicitly) { // NOLINT
492  ls3.setAttribute(Attr::Type, Value::LineThin);
493  ls3.setAttribute(Attr::Subtype, Value::Solid);
494  ls3.setAttribute(AttrStr::LaneChange, true);
495  EXPECT_TRUE(germanVehicle->canChangeLane(lanelet, left));
496  EXPECT_TRUE(germanVehicle->canChangeLane(left, lanelet));
497 }
498 
499 TEST_F(GermanTrafficRulesVehicle, canLaneChangeBothSidesBothExplicitly) { // NOLINT
500  ls3.setAttribute(Attr::Type, Value::Virtual);
501  ls3.setAttribute(AttrStr::LaneChangeLeft, true);
502  ls3.setAttribute(AttrStr::LaneChangeRight, true);
503  EXPECT_TRUE(germanVehicle->canChangeLane(lanelet, left));
504  EXPECT_TRUE(germanVehicle->canChangeLane(left, lanelet));
505 }
506 TEST_F(GermanTrafficRulesVehicle, canLaneChangeLeftSideBothExplicitly) { // NOLINT
507  ls3.setAttribute(Attr::Type, Value::Virtual);
508  ls3.setAttribute(AttrStr::LaneChangeLeft, true);
509  ls3.setAttribute(AttrStr::LaneChangeRight, false);
510  EXPECT_TRUE(germanVehicle->canChangeLane(lanelet, left));
511  EXPECT_FALSE(germanVehicle->canChangeLane(left, lanelet));
512 }
513 TEST_F(GermanTrafficRulesVehicle, canLaneChangeRightSideBothExplicitly) { // NOLINT
514  ls3.setAttribute(Attr::Type, Value::Virtual);
515  ls3.setAttribute(AttrStr::LaneChangeLeft, false);
516  ls3.setAttribute(AttrStr::LaneChangeRight, true);
517  EXPECT_FALSE(germanVehicle->canChangeLane(lanelet, left));
518  EXPECT_TRUE(germanVehicle->canChangeLane(left, lanelet));
519 }
520 
521 TEST_F(GermanTrafficRulesVehicle, canLaneChangeLeftExplicitly) { // NOLINT
522  ls3.setAttribute(Attr::Type, Value::Virtual);
523  ls3.setAttribute(AttrStr::LaneChangeLeft, true);
524  EXPECT_TRUE(germanVehicle->canChangeLane(lanelet, left));
525  EXPECT_FALSE(germanVehicle->canChangeLane(left, lanelet));
526 }
527 TEST_F(GermanTrafficRulesVehicle, canLaneChangeRightExplicitly) { // NOLINT
528  ls3.setAttribute(Attr::Type, Value::Virtual);
529  ls3.setAttribute(AttrStr::LaneChangeRight, true);
530  EXPECT_FALSE(germanVehicle->canChangeLane(lanelet, left));
531  EXPECT_TRUE(germanVehicle->canChangeLane(left, lanelet));
532 }
533 } // namespace lane_change
534 
535 namespace other {
536 
537 TEST_F(GermanTrafficRulesVehicle, normalRegelemIsNotDynamic) { // NOLINT
538  lanelet.addRegulatoryElement(getSpeedLimit("de274-60"));
539  EXPECT_FALSE(germanVehicle->hasDynamicRules(lanelet));
540 }
541 
542 TEST_F(GermanTrafficRulesVehicle, dynamicRegelemIsDynamic) { // NOLINT
543  auto regelem = getSpeedLimit("de274", {{AttrStr::Dynamic, true}});
544  lanelet.addRegulatoryElement(regelem);
545  EXPECT_TRUE(germanVehicle->hasDynamicRules(lanelet));
546 }
547 
548 TEST_F(GermanTrafficRulesVehicle, locationIsGermany) { // NOLINT
549  using namespace lanelet;
550  EXPECT_EQ(germanVehicle->location(), Locations::Germany);
551 }
552 
553 TEST_F(GermanTrafficRulesPedestrian, locationIsGermany) { // NOLINT
554  using namespace lanelet;
555  EXPECT_EQ(germanPedestrian->location(), Locations::Germany);
556 }
557 
558 TEST_F(GermanTrafficRulesVehicle, factoryReturnsVehicleForCar) { // NOLINT
559  using namespace lanelet;
560  auto trafficRules = traffic_rules::TrafficRulesFactory::create(Locations::Germany, Participants::VehicleCar, {});
561  EXPECT_EQ(trafficRules->participant(), Participants::VehicleCar);
562 }
563 } // namespace other
speed_limits
Definition: lanelet2_traffic_rules.cpp:320
germanBikeRules
lanelet::traffic_rules::TrafficRulesPtr germanBikeRules()
Definition: lanelet2_traffic_rules.cpp:28
GermanTrafficRulesVehicle
Definition: lanelet2_traffic_rules.cpp:66
can_drive
Definition: lanelet2_traffic_rules.cpp:87
GermanTrafficRulesPedestrian::germanPedestrian
lanelet::traffic_rules::TrafficRulesPtr germanPedestrian
Definition: lanelet2_traffic_rules.cpp:84
lanelet::SpeedLimit::make
static Ptr make(Id id, AttributeMap attributes, const std::string &signType, const LineStrings3d &refLines={}, const LineStrings3d &cancelLines={})
lane_change
Definition: lanelet2_traffic_rules.cpp:419
lanelet::AttributeValueString::BicycleLane
static constexpr const char BicycleLane[]
lanelet
lanelet::RegulatoryElementPtr
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
lanelet::AttributeNamesString::LaneChange
static constexpr const char LaneChange[]
TrafficRules::p2
lanelet::Point3d p2
Definition: lanelet2_traffic_rules.cpp:55
lanelet::AttributeNamesString::SpeedLimit
static constexpr const char SpeedLimit[]
lanelet::Participants::Pedestrian
static constexpr const char Pedestrian[]
lanelet::AttributeValueString::Highway
static constexpr const char Highway[]
TrafficRules::area
lanelet::Area area
Definition: lanelet2_traffic_rules.cpp:63
p2
BasicPoint p2
TrafficRules::p8
lanelet::Point3d p8
Definition: lanelet2_traffic_rules.cpp:56
TrafficRules::right
lanelet::Lanelet right
Definition: lanelet2_traffic_rules.cpp:61
lanelet::AttributeName::OneWay
@ OneWay
lanelet::AttributeValueString::Low
static constexpr const char Low[]
TrafficRules::p11
lanelet::Point3d p11
Definition: lanelet2_traffic_rules.cpp:56
GermanTrafficRulesPedestrian
Definition: lanelet2_traffic_rules.cpp:76
TrafficRules::ls9
lanelet::LineString3d ls9
Definition: lanelet2_traffic_rules.cpp:58
lanelet::AttributeValueString::LineThin
static constexpr const char LineThin[]
TrafficRulesFactory.h
lanelet::AttributeName::SpeedLimit
@ SpeedLimit
lanelet::AttributeNamesString::Dynamic
static constexpr const char Dynamic[]
getSpeedLimit
lanelet::RegulatoryElementPtr getSpeedLimit(const std::string &type, const lanelet::AttributeMap &attributes={})
Definition: lanelet2_traffic_rules.cpp:14
Primitive< ConstLanelet >::attributes
AttributeMap & attributes() noexcept
GermanTrafficRulesBike::germanBike
lanelet::traffic_rules::TrafficRulesPtr germanBike
Definition: lanelet2_traffic_rules.cpp:73
TrafficRules::ls3
lanelet::LineString3d ls3
Definition: lanelet2_traffic_rules.cpp:57
TrafficRules::ls5
lanelet::LineString3d ls5
Definition: lanelet2_traffic_rules.cpp:57
germanVehicleRules
lanelet::traffic_rules::TrafficRulesPtr germanVehicleRules()
Definition: lanelet2_traffic_rules.cpp:23
TrafficRules::p3
lanelet::Point3d p3
Definition: lanelet2_traffic_rules.cpp:55
BasicRegulatoryElements.h
TrafficRules::p12
lanelet::Point3d p12
Definition: lanelet2_traffic_rules.cpp:56
Units.h
lanelet::Area
lanelet::AttributeValueString::Walkway
static constexpr const char Walkway[]
lanelet::AttributeNamesString::LaneChangeRight
static constexpr const char LaneChangeRight[]
GermanTrafficRulesPedestrian::GermanTrafficRulesPedestrian
GermanTrafficRulesPedestrian()
Definition: lanelet2_traffic_rules.cpp:78
lanelet::AttributeValueString::Virtual
static constexpr const char Virtual[]
TrafficRules::ls4
lanelet::LineString3d ls4
Definition: lanelet2_traffic_rules.cpp:57
lanelet::Lanelet
TrafficRules::ls7
lanelet::LineString3d ls7
Definition: lanelet2_traffic_rules.cpp:58
lanelet::AttributeName::Type
@ Type
lanelet::AttributeNamesString::Subtype
static constexpr const char Subtype[]
lanelet::Locations::Germany
static constexpr char Germany[]
Definition: TrafficRulesFactory.h:6
TrafficRules::ls6
lanelet::LineString3d ls6
Definition: lanelet2_traffic_rules.cpp:58
TrafficRules::p10
lanelet::Point3d p10
Definition: lanelet2_traffic_rules.cpp:56
lanelet::AttributeNamesString::OneWay
static constexpr const char OneWay[]
lanelet::AttributeNamesString
lanelet::Participants
TrafficRules::p1
lanelet::Point3d p1
Definition: lanelet2_traffic_rules.cpp:55
lanelet::LineString3d::invert
LineString3d invert() const noexcept
lanelet::AttributeValueString::DashedSolid
static constexpr const char DashedSolid[]
TrafficRules::p9
lanelet::Point3d p9
Definition: lanelet2_traffic_rules.cpp:56
TrafficRules::p4
lanelet::Point3d p4
Definition: lanelet2_traffic_rules.cpp:55
p1
BasicPoint p1
lanelet::AttributeNamesString::LaneChangeLeft
static constexpr const char LaneChangeLeft[]
lanelet::AttributeNamesString::SpeedLimitMandatory
static constexpr const char SpeedLimitMandatory[]
lanelet::AttributeValueString::Solid
static constexpr const char Solid[]
TrafficRules::next
lanelet::Lanelet next
Definition: lanelet2_traffic_rules.cpp:62
lanelet::AttributeValueString::Curbstone
static constexpr const char Curbstone[]
lanelet::AttributeName::Location
@ Location
lanelet::AttributeValueString::SolidDashed
static constexpr const char SolidDashed[]
TrafficRules::left
lanelet::Lanelet left
Definition: lanelet2_traffic_rules.cpp:61
GermanTrafficRulesVehicle::germanVehicle
lanelet::traffic_rules::TrafficRulesPtr germanVehicle
Definition: lanelet2_traffic_rules.cpp:68
lanelet::AttributeValueString::SolidSolid
static constexpr const char SolidSolid[]
lanelet::Point3d
TrafficRules
Definition: lanelet2_traffic_rules.cpp:38
other
Definition: lanelet2_traffic_rules.cpp:535
lanelet::Participants::Bicycle
static constexpr const char Bicycle[]
lanelet::Participants::Vehicle
static constexpr const char Vehicle[]
lanelet::AttributeValueString::Road
static constexpr const char Road[]
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map >
lanelet::AttributeValueString::Nonurban
static constexpr const char Nonurban[]
TrafficRules::nextArea
lanelet::Area nextArea
Definition: lanelet2_traffic_rules.cpp:63
TrafficRules::pedestrianAttr
lanelet::AttributeMap pedestrianAttr
Definition: lanelet2_traffic_rules.cpp:60
lanelet::traffic_rules::TrafficRulesFactory::create
static TrafficRulesUPtr create(const std::string &location, const std::string &participant, TrafficRules::Configuration configuration=TrafficRules::Configuration())
Definition: TrafficRulesFactory.cpp:10
lanelet::AttributeValueString
TrafficRules::ls8
lanelet::LineString3d ls8
Definition: lanelet2_traffic_rules.cpp:58
lanelet::AttributeValueString::Urban
static constexpr const char Urban[]
TrafficRules::ls2
lanelet::LineString3d ls2
Definition: lanelet2_traffic_rules.cpp:57
TrafficRules::ls1
lanelet::LineString3d ls1
Definition: lanelet2_traffic_rules.cpp:57
TrafficRules::p7
lanelet::Point3d p7
Definition: lanelet2_traffic_rules.cpp:55
can_drive::TEST_F
TEST_F(GermanTrafficRulesVehicle, vehicleCanPassRoadLanelet)
Definition: lanelet2_traffic_rules.cpp:88
germanPedestrianRules
lanelet::traffic_rules::TrafficRulesPtr germanPedestrianRules()
Definition: lanelet2_traffic_rules.cpp:33
lanelet::units::literals
lanelet::AttributeValueString::Dashed
static constexpr const char Dashed[]
TrafficRules::vehicleAttr
lanelet::AttributeMap vehicleAttr
Definition: lanelet2_traffic_rules.cpp:59
TrafficRules::p5
lanelet::Point3d p5
Definition: lanelet2_traffic_rules.cpp:55
lanelet::AttributeName
AttributeName
GermanTrafficRulesBike
Definition: lanelet2_traffic_rules.cpp:71
lanelet::LineString3d
lanelet::AttributeName::Subtype
@ Subtype
TrafficRules::p6
lanelet::Point3d p6
Definition: lanelet2_traffic_rules.cpp:55
TrafficRules.h
lanelet::AttributeNamesString::Location
static constexpr const char Location[]
lanelet::traffic_rules::TrafficRulesPtr
std::shared_ptr< TrafficRules > TrafficRulesPtr
Definition: GenericTrafficRules.h:22


lanelet2_traffic_rules
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:07