Go to the documentation of this file.
19 using Ptr = std::shared_ptr<TrafficLight>;
20 static constexpr
char RuleName[] =
"traffic_light";
32 Optional<ConstLineString3d>
stopLine()
const;
89 using Ptr = std::shared_ptr<RightOfWay>;
90 static constexpr
char RuleName[] =
"right_of_way";
118 Optional<ConstLineString3d>
stopLine()
const;
165 using Ptr = std::shared_ptr<AllWayStop>;
186 void addLanelet(
const LaneletWithStopLine& lltWithStop);
196 Optional<ConstLineString3d>
getStopLine(
const ConstLanelet& llt)
const;
197 Optional<LineString3d>
getStopLine(
const ConstLanelet& llt);
232 using Ptr = std::shared_ptr<TrafficSign>;
266 std::string
type()
const;
338 using Ptr = std::shared_ptr<SpeedLimit>;
SpeedLimit(Id id, const AttributeMap &attributes, const TrafficSignsWithType &trafficSigns, const TrafficSignsWithType &cancellingTrafficSigns={}, const LineStrings3d &refLines={}, const LineStrings3d &cancelLines={})
ManeuverType
Enum to distinguish maneuver types.
std::vector< ConstLineString3d > ConstLineStrings3d
ConstLanelets rightOfWayLanelets() const
get the lanelets have right of way
std::vector< LineString3d > LineStrings3d
ConstLineStrings3d refLines() const
gets the line(s) from which a sign becomes valid.
std::vector< ConstLineStringOrPolygon3d > ConstLineStringsOrPolygons3d
bool removeRightOfWayLanelet(const Lanelet &lanelet)
Removes a right of way lanelet and returns true on success.
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.
void addRefLine(const LineString3d &line)
Add a new reference line.
void addCancellingTrafficSign(const TrafficSignsWithType &signs)
Add new cancelling traffic sign.
ConstLineStringsOrPolygons3d trafficSigns() const
get list of traffic signs that constitute this AllWayStop if existing
ConstLanelets lanelets() const
get the lanelets that potentially have to yield
bool removeTrafficLight(const LineStringOrPolygon3d &primitive)
remove a traffic light
const AttributeMap & attributes() const
get the attributes of this primitive
Optional< ConstLineString3d > stopLine() const
get the stop line for the traffic light
bool removeCancellingRefLine(const LineString3d &line)
Remove a cancelling line. Returns true on success.
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map > AttributeMap
void removeStopLine()
Deletes the stop line.
std::pair< iterator, bool > insert(const value_type &v)
ConstLineStringsOrPolygons3d trafficSigns() const
returns the traffic signs
void addYieldLanelet(const Lanelet &lanelet)
Add yielding lanelet.
std::shared_ptr< RegulatoryElementData > RegulatoryElementDataPtr
void addTrafficSign(const LineStringOrPolygon3d &sign)
Adds another traffic sign.
@ Unknown
Lanelet ist not part of relation.
std::vector< Lanelet > Lanelets
A general rule or limitation for a lanelet (abstract base class)
void setStopLine(const LineString3d &stopLine)
set a new stop line, overwrite the old one
Represents a speed limit that affects a lanelet.
Expresses a generic traffic sign rule.
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.
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.
static constexpr char RuleName[]
static constexpr const char SignType[]
TrafficLight(Id id, const AttributeMap &attributes, const LineStringsOrPolygons3d &trafficLights, const Optional< LineString3d > &stopLine)
std::shared_ptr< AllWayStop > Ptr
void addTrafficSign(const LineStringOrPolygon3d &sign)
Adds another traffic sign.
ConstLineStringsOrPolygons3d cancellingTrafficSigns() const
get list of cancellingTrafficSigns, if existing
Defines right of way restrictions.
boost::optional< T > Optional
The famous (mutable) lanelet class.
std::shared_ptr< TrafficLight > Ptr
Represents a traffic light restriction on the lanelet.
std::vector< std::string > cancelTypes() const
Types of the cancelling traffic signs if they exist.
std::shared_ptr< TrafficSign > Ptr
Optional< ConstLineString3d > getStopLine(const ConstLanelet &llt) const
gets the stop line for a lanelet, if there is one
void addCancellingRefLine(const LineString3d &line)
Add a new line from where the sign becomes inactive.
std::vector< LineStringOrPolygon3d > LineStringsOrPolygons3d
static constexpr char RuleName[]
void removeStopLine()
Removes the stop line.
void addRightOfWayLanelet(const Lanelet &lanelet)
Adds a lanelet for RightOfWay.
@ RightOfWay
Lanelet has right of way
static constexpr char RuleName[]
Used as input argument to create TrafficSign regElem.
Optional< LineString3d > stopLine
static constexpr char RuleName[]
AllWayStop(Id id, const AttributeMap &attributes, const LaneletsWithStopLines &lltsWithStop, const LineStringsOrPolygons3d &signs)
bool removeTrafficSign(const LineStringOrPolygon3d &sign)
removes a traffic sign and returns true on success
Defines an all way stop. These are a special form of right of way, where all lanelets have to yield,...
std::vector< LaneletWithStopLine > LaneletsWithStopLines
LineStringsOrPolygons3d trafficSigns
Lists relevant traffic signs.
ManeuverType getManeuver(const ConstLanelet &lanelet) const
returns whether a lanelet has to yield or has right of way
ConstLineStringsOrPolygons3d trafficLights() const
get the relevant traffic lights
static constexpr char RuleName[]
bool removeTrafficSign(const LineStringOrPolygon3d &sign)
remove a traffic sign and returns true on success
template class for registering new RegulatoryElements.
bool removeRefLine(const LineString3d &line)
Remove a reference line. Returns true on success.
ConstLanelets yieldLanelets() const
get the lanelets that have to yield
ConstLineStrings3d stopLines() const
get the stop lines
std::shared_ptr< SpeedLimit > Ptr
std::string type() const
get the id/number of the sign(s)
Optional< ConstLineString3d > stopLine() const
get the stop line for the yield lanelets, if present
bool removeYieldLanelet(const Lanelet &lanelet)
Removes a yielding lanelet and returns true no success.
TrafficSign(Id id, const AttributeMap &attributes, const TrafficSignsWithType &trafficSigns, const TrafficSignsWithType &cancellingTrafficSigns={}, const LineStrings3d &refLines={}, const LineStrings3d &cancelLines={})
void setStopLine(const LineString3d &stopLine)
Overwrites the stop line.
std::shared_ptr< RightOfWay > Ptr
RegulatoryElementDataPtr data()
RightOfWay(Id id, const AttributeMap &attributes, const Lanelets &rightOfWay, const Lanelets &yield, const Optional< LineString3d > &stopLine={})
bool removeCancellingTrafficSign(const LineStringOrPolygon3d &sign)
remove a cancelling traffic sign, returns true on success
void addLanelet(const LaneletWithStopLine &lltWithStop)
bool removeLanelet(const Lanelet &llt)
Removes a lanelet and the associated stop line, if there is one.
void addTrafficLight(const LineStringOrPolygon3d &primitive)
add a new traffic light
Optional< ConstLineString3d > stopLine
std::vector< ConstLanelet > ConstLanelets
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 LineStringsOrPolygons3d &trafficLights, const Optional< LineString3d > &stopLine={})
static Ptr make(Id id, const AttributeMap &attributes, const LaneletsWithStopLines &lltsWithStop, const LineStringsOrPolygons3d &signs={})
Create a valid all way stop object.
ConstLineStrings3d cancelLines() const
gets the line(s) from which a sign becomes invalid.
lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52