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. More...
#include <BasicRegulatoryElements.h>
Public Types | |
using | Ptr = std::shared_ptr< AllWayStop > |
![]() | |
using | Category = traits::RegulatoryElementTag |
using | const_iterator = RuleParameterMap::const_iterator |
using | ConstType = RegulatoryElement |
using | iterator = RuleParameterMap::iterator |
using | MutableType = GenericRegulatoryElement |
using | ThreeDType = RegulatoryElement |
using | TwoDType = RegulatoryElement |
![]() | |
using | DataType = RegulatoryElementData |
Public Member Functions | |
void | addLanelet (const LaneletWithStopLine &lltWithStop) |
void | addTrafficSign (const LineStringOrPolygon3d &sign) |
Adds another traffic sign. More... | |
Optional< LineString3d > | getStopLine (const ConstLanelet &llt) |
Optional< ConstLineString3d > | getStopLine (const ConstLanelet &llt) const |
gets the stop line for a lanelet, if there is one More... | |
Lanelets | lanelets () |
ConstLanelets | lanelets () const |
get the lanelets that potentially have to yield More... | |
bool | removeLanelet (const Lanelet &llt) |
Removes a lanelet and the associated stop line, if there is one. More... | |
bool | removeTrafficSign (const LineStringOrPolygon3d &sign) |
removes a traffic sign and returns true on success More... | |
LineStrings3d | stopLines () |
ConstLineStrings3d | stopLines () const |
get the stop lines More... | |
LineStringsOrPolygons3d | trafficSigns () |
ConstLineStringsOrPolygons3d | trafficSigns () const |
get list of traffic signs that constitute this AllWayStop if existing More... | |
![]() | |
void | applyVisitor (RuleParameterVisitor &visitor) const |
applies a visitor to every parameter in the regulatory element More... | |
bool | empty () const |
returns true if this object contains no parameters More... | |
template<typename T > | |
Optional< T > | find (Id id) const |
Finds a parameter by its id, independent of the role. More... | |
template<> | |
Optional< ConstRuleParameter > | find (Id id) const |
template<> | |
boost::optional< ConstLanelet > | find (Id id) const |
template<> | |
boost::optional< ConstArea > | find (Id id) const |
ConstRuleParameterMap | getParameters () const |
Returns all parameters as const object (coversion overhead for const) More... | |
template<typename T > | |
std::vector< T > | getParameters (const std::string &role) const |
Returns a vector of all RuleParameters that could be converted to T. More... | |
template<> | |
std::vector< ConstLanelet > | getParameters (const std::string &role) const |
template<typename T > | |
std::vector< T > | getParameters (RoleName role) const |
template<> | |
std::vector< ConstLanelet > | getParameters (RoleName role) const |
std::vector< std::string > | roles () const |
returns all the roles this regulatory element has More... | |
void | setId (Id id) noexcept |
size_t | size () const |
get the number of roles in this regulatoryElement More... | |
virtual | ~RegulatoryElement () |
![]() | |
const Attribute & | attribute (AttributeName name) const |
retrieve an attribute (enum version) More... | |
const Attribute & | attribute (const std::string &name) const |
retrieve an attribute More... | |
T | attributeOr (AttributeName name, T defaultVal) const |
retrieve an attribute (enum version) More... | |
T | attributeOr (const std::string &name, T defaultVal) const noexcept |
retrieve an attribute (string version) More... | |
const AttributeMap & | attributes () const |
get the attributes of this primitive More... | |
const std::shared_ptr< const RegulatoryElementData > & | constData () const |
get the internal data of this primitive More... | |
ConstPrimitive (const std::shared_ptr< const RegulatoryElementData > &data) | |
Construct from a pointer to the data. More... | |
bool | hasAttribute (AttributeName name) const noexcept |
check for an attribute (enum version) More... | |
bool | hasAttribute (const std::string &name) const noexcept |
check whether this primitive has a specific attribute More... | |
Id | id () const noexcept |
get the unique id of this primitive More... | |
bool | operator!= (const ConstPrimitive &rhs) const |
bool | operator== (const ConstPrimitive &rhs) const |
Static Public Member Functions | |
static Ptr | make (Id id, const AttributeMap &attributes, const LaneletsWithStopLines &lltsWithStop, const LineStringsOrPolygons3d &signs={}) |
Create a valid all way stop object. More... | |
Static Public Attributes | |
static constexpr char | RuleName [] = "all_way_stop" |
![]() | |
static constexpr char | RuleName [] = "basic_regulatory_element" |
![]() | |
static constexpr bool | IsConst |
Friends | |
class | RegisterRegulatoryElement< AllWayStop > |
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.
Definition at line 163 of file BasicRegulatoryElements.h.
using lanelet::AllWayStop::Ptr = std::shared_ptr<AllWayStop> |
Definition at line 165 of file BasicRegulatoryElements.h.
|
protected |
Definition at line 449 of file BasicRegulatoryElements.cpp.
|
explicitprotected |
Definition at line 453 of file BasicRegulatoryElements.cpp.
void lanelet::AllWayStop::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
InvalidInputError | if stop line is inconsistent |
Definition at line 417 of file BasicRegulatoryElements.cpp.
void lanelet::AllWayStop::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.
Definition at line 409 of file BasicRegulatoryElements.cpp.
Optional< LineString3d > lanelet::AllWayStop::getStopLine | ( | const ConstLanelet & | llt | ) |
Definition at line 390 of file BasicRegulatoryElements.cpp.
Optional< ConstLineString3d > lanelet::AllWayStop::getStopLine | ( | const ConstLanelet & | llt | ) | const |
gets the stop line for a lanelet, if there is one
Definition at line 377 of file BasicRegulatoryElements.cpp.
Lanelets lanelet::AllWayStop::lanelets | ( | ) |
Lanelets lanelet::AllWayStop::lanelets | ( | ) | const |
get the lanelets that potentially have to yield
Definition at line 369 of file BasicRegulatoryElements.cpp.
|
inlinestatic |
Create a valid all way stop object.
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 |
Definition at line 175 of file BasicRegulatoryElements.h.
bool lanelet::AllWayStop::removeLanelet | ( | const Lanelet & | llt | ) |
Removes a lanelet and the associated stop line, if there is one.
Definition at line 431 of file BasicRegulatoryElements.cpp.
bool lanelet::AllWayStop::removeTrafficSign | ( | const LineStringOrPolygon3d & | sign | ) |
removes a traffic sign and returns true on success
Definition at line 413 of file BasicRegulatoryElements.cpp.
LineStrings3d lanelet::AllWayStop::stopLines | ( | ) |
LineStrings3d lanelet::AllWayStop::stopLines | ( | ) | const |
get the stop lines
Definition at line 373 of file BasicRegulatoryElements.cpp.
LineStringsOrPolygons3d lanelet::AllWayStop::trafficSigns | ( | ) |
LineStringsOrPolygons3d lanelet::AllWayStop::trafficSigns | ( | ) | const |
get list of traffic signs that constitute this AllWayStop if existing
Definition at line 403 of file BasicRegulatoryElements.cpp.
|
friend |
Definition at line 213 of file BasicRegulatoryElements.h.
|
staticconstexpr |
Definition at line 166 of file BasicRegulatoryElements.h.