Class AllWayStop

Inheritance Relationships

Base Type

Class Documentation

class AllWayStop : public lanelet::RegulatoryElement

Defines an all way stop. These are a special form of right of way, where all lanelets have to yield, depending on the order of arrival and the route through the intersection.

The distance to the intersection is represented either by the distance to the stop line, if present, otherwise the distance to the end of the lanelet.

Public Types

using Ptr = std::shared_ptr<AllWayStop>

Public Functions

ConstLanelets lanelets() const

get the lanelets that potentially have to yield

Lanelets lanelets()
void addLanelet(const LaneletWithStopLine &lltWithStop)

Adds a new lanelet with stop line. This will throw if the other lanelets did not have a stop line and vice versa

Throws:

InvalidInputError – if stop line is inconsistent

bool removeLanelet(const Lanelet &llt)

Removes a lanelet and the associated stop line, if there is one.

ConstLineStrings3d stopLines() const

get the stop lines

LineStrings3d stopLines()
Optional<ConstLineString3d> getStopLine(const ConstLanelet &llt) const

gets the stop line for a lanelet, if there is one

Optional<LineString3d> getStopLine(const ConstLanelet &llt)
ConstLineStringsOrPolygons3d trafficSigns() const

get list of traffic signs that constitute this AllWayStop if existing

LineStringsOrPolygons3d trafficSigns()
void addTrafficSign(const LineStringOrPolygon3d &sign)

Adds another traffic sign.

Traffic signs are represented as linestrings that start at the left edge and end at the right edge of a traffic sign.

bool removeTrafficSign(const LineStringOrPolygon3d &sign)

removes a traffic sign and returns true on success

Public Static Functions

static inline Ptr make(Id id, const AttributeMap &attributes, const LaneletsWithStopLines &lltsWithStop, const LineStringsOrPolygons3d &signs = {})

Create a valid all way stop object.

Parameters:
  • id – id for this rule

  • attributes – for this rule. Might be extended if necessary

  • lltsWithStop – lanelets with stop line. Either all lanelets have a stop line or none.

  • signs – traffic signs that constitute this rule

Public Static Attributes

static constexpr char RuleName[] = "all_way_stop"

Protected Functions

AllWayStop(Id id, const AttributeMap &attributes, const LaneletsWithStopLines &lltsWithStop, const LineStringsOrPolygons3d &signs)
explicit AllWayStop(const RegulatoryElementDataPtr &data)

Friends

friend class RegisterRegulatoryElement< AllWayStop >