3 #include <lanelet2_core/primitives/Lanelet.h> 47 assert(trafficRules->canPass(
right));
48 assert(!pedestrianRules->canPass(
right));
50 assert(!trafficRules->canPass(
right.invert()));
53 assert(!trafficRules->canPass(
right,
left));
57 assert(limit.speedLimit == 50_kmh);
58 assert(limit.isMandatory);
71 assert(trafficRules->canChangeLane(
right,
left));
72 assert(trafficRules->canChangeLane(
left,
right));
75 assert(trafficRules->canPass(
left.invert()));
77 assert(!trafficRules->canChangeLane(
left,
right.invert()));
78 assert(!trafficRules->canChangeLane(
left.invert(),
right.invert()));
81 limit = trafficRules->speedLimit(
right);
82 assert(limit.speedLimit == 100_kmh);
88 right.addRegulatoryElement(speedLimit);
89 assert(trafficRules->speedLimit(
right).speedLimit == 60_kmh);
93 assert(!trafficRules->canPass(
right));
96 assert(pedestrianRules->canPass(
right));
static constexpr char Germany[]
static constexpr const char Road[]
static constexpr const char Nonurban[]
static constexpr const char Vehicle[]
Optional< ConstLaneletOrArea > next
static constexpr const char Lanelet[]
static constexpr const char LineThin[]
static TrafficRulesUPtr create(const std::string &location, const std::string &participant, TrafficRules::Configuration configuration=TrafficRules::Configuration())
static constexpr const char Pedestrian[]
void part1UsingTrafficRules()
static Ptr make(Id id, const AttributeMap &attributes, const TrafficSignsWithType &trafficSigns, const TrafficSignsWithType &cancellingTrafficSigns={}, const LineStrings3d &refLines={}, const LineStrings3d &cancelLines={})
LineString3d getLineStringAtY(double y)
static constexpr const char Crosswalk[]
LineString3d getLineStringAtX(double x)
static constexpr const char Dashed[]
std::shared_ptr< TrafficRules > TrafficRulesPtr
std::shared_ptr< SpeedLimit > Ptr