19 using Ptr = std::shared_ptr<TrafficLight>;
20 static constexpr
char RuleName[] =
"traffic_light";
89 using Ptr = std::shared_ptr<RightOfWay>;
90 static constexpr
char RuleName[] =
"right_of_way";
125 void addRightOfWayLanelet(
const Lanelet& lanelet);
128 void addYieldLanelet(
const Lanelet& lanelet);
131 bool removeRightOfWayLanelet(
const Lanelet& lanelet);
134 bool removeYieldLanelet(
const Lanelet& lanelet);
165 using Ptr = std::shared_ptr<AllWayStop>;
166 static constexpr
char RuleName[] =
"all_way_stop";
177 return Ptr{
new AllWayStop(
id, attributes, lltsWithStop, signs)};
189 bool removeLanelet(
const Lanelet& llt);
232 using Ptr = std::shared_ptr<TrafficSign>;
233 static constexpr
char RuleName[] =
"traffic_sign";
253 return Ptr(
new TrafficSign(
id, attributes, trafficSigns, cancellingTrafficSigns, refLines, cancelLines));
266 std::string
type()
const;
281 std::vector<std::string> cancelTypes()
const;
338 using Ptr = std::shared_ptr<SpeedLimit>;
339 static constexpr
char RuleName[] =
"speed_limit";
345 return Ptr(
new SpeedLimit(
id, attributes, trafficSigns, cancellingTrafficSigns, refLines, cancelLines));
352 return Ptr(
new SpeedLimit(
id, attributes, {}, {}, refLines, cancelLines));
template class for registering new RegulatoryElements.
std::vector< ConstLineString3d > ConstLineStrings3d
ManeuverType
Enum to distinguish maneuver types.
std::vector< ConstLineStringOrPolygon3d > ConstLineStringsOrPolygons3d
Represents a speed limit that affects a laneletA speed limit is defined by one ore more traffic signs...
Optional< ConstLineString3d > stopLine() const
get the stop line for the traffic light
static Ptr make(Id id, const AttributeMap &attributes, const LineStringsOrPolygons3d &trafficLights, const Optional< LineString3d > &stopLine={})
std::pair< iterator, bool > insert(const value_type &v)
Optional< ConstLineString3d > stopLine
const AttributeMap & attributes() const
get the attributes of this primitive
This class holds either a LineString3d or a Polygon3d.
The famous (mutable) lanelet class.
std::vector< Lanelet > Lanelets
Optional< LineString3d > stopLine
std::shared_ptr< RegulatoryElementData > RegulatoryElementDataPtr
Defines right of way restrictions.
Represents a traffic light restriction on the lanelet.
ConstLineStringsOrPolygons3d trafficLights() const
get the relevant traffic lights
RegulatoryElementDataPtr data()
static Ptr make(Id id, const AttributeMap &attributes, const LaneletsWithStopLines &lltsWithStop, const LineStringsOrPolygons3d &signs={})
Create a valid all way stop object.
Used as input argument to create TrafficSign regElem.
A normal 3d linestring with mutable data.
boost::optional< T > Optional
static Ptr make(Id id, const AttributeMap &attributes, const TrafficSignsWithType &trafficSigns, const TrafficSignsWithType &cancellingTrafficSigns={}, const LineStrings3d &refLines={}, const LineStrings3d &cancelLines={})
Create a speed limit regulatory element. Similar to a traffic sign.
static Ptr make(Id id, const AttributeMap &attributes, const Lanelets &rightOfWay, const Lanelets &yield, const Optional< LineString3d > &stopLine={})
Create a valid Right of Way object.
std::vector< LaneletWithStopLine > LaneletsWithStopLines
std::vector< LineStringOrPolygon3d > LineStringsOrPolygons3d
static constexpr char RuleName[]
void removeStopLine()
Deletes the stop line.
std::shared_ptr< RightOfWay > Ptr
void setStopLine(const LineString3d &stopLine)
set a new stop line, overwrite the old one
static Ptr make(Id id, const AttributeMap &attributes, const TrafficSignsWithType &trafficSigns, const TrafficSignsWithType &cancellingTrafficSigns={}, const LineStrings3d &refLines={}, const LineStrings3d &cancelLines={})
Create a valid TrafficSign object.
Lanelet ist not part of relation.
A general rule or limitation for a lanelet (abstract base class)
LineStringsOrPolygons3d trafficSigns
Lists relevant traffic signs.
bool removeTrafficLight(const LineStringOrPolygon3d &primitive)
remove a traffic light
std::shared_ptr< AllWayStop > Ptr
std::shared_ptr< TrafficLight > Ptr
TrafficLight(Id id, const AttributeMap &attributes, const LineStringsOrPolygons3d &trafficLights, const Optional< LineString3d > &stopLine)
Expresses a generic traffic sign rule.
void addTrafficLight(const LineStringOrPolygon3d &primitive)
add a new traffic light
static constexpr const char SignType[]
Defines an all way stop. These are a special form of right of way, where all lanelets have to yield...
std::shared_ptr< TrafficSign > Ptr
std::vector< LineString3d > LineStrings3d
static Ptr make(Id id, AttributeMap attributes, const std::string &signType, const LineStrings3d &refLines={}, const LineStrings3d &cancelLines={})
Create a speed limit regulatory element only from a type or speed limit without actual sign...
std::vector< ConstLanelet > ConstLanelets