Defines right of way restrictions. More...
#include <BasicRegulatoryElements.h>
Public Types | |
using | Ptr = std::shared_ptr< RightOfWay > |
![]() | |
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 | addRightOfWayLanelet (const Lanelet &lanelet) |
Adds a lanelet for RightOfWay. More... | |
void | addYieldLanelet (const Lanelet &lanelet) |
Add yielding lanelet. More... | |
ManeuverType | getManeuver (const ConstLanelet &lanelet) const |
returns whether a lanelet has to yield or has right of way More... | |
bool | removeRightOfWayLanelet (const Lanelet &lanelet) |
Removes a right of way lanelet and returns true on success. More... | |
void | removeStopLine () |
Removes the stop line. More... | |
bool | removeYieldLanelet (const Lanelet &lanelet) |
Removes a yielding lanelet and returns true no success. More... | |
Lanelets | rightOfWayLanelets () |
ConstLanelets | rightOfWayLanelets () const |
get the lanelets have right of way More... | |
void | setStopLine (const LineString3d &stopLine) |
Overwrites the stop line. More... | |
Optional< LineString3d > | stopLine () |
Optional< ConstLineString3d > | stopLine () const |
get the stop line for the yield lanelets, if present More... | |
Lanelets | yieldLanelets () |
ConstLanelets | yieldLanelets () const |
get the lanelets that have to yield 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 Lanelets &rightOfWay, const Lanelets &yield, const Optional< LineString3d > &stopLine={}) |
Create a valid Right of Way object. More... | |
Static Public Attributes | |
static constexpr char | RuleName [] = "right_of_way" |
![]() | |
static constexpr char | RuleName [] = "basic_regulatory_element" |
![]() | |
static constexpr bool | IsConst |
Friends | |
class | RegisterRegulatoryElement< RightOfWay > |
Defines right of way restrictions.
Definition at line 87 of file BasicRegulatoryElements.h.
using lanelet::RightOfWay::Ptr = std::shared_ptr<RightOfWay> |
Definition at line 89 of file BasicRegulatoryElements.h.
|
protected |
Definition at line 214 of file BasicRegulatoryElements.cpp.
|
explicitprotected |
Definition at line 205 of file BasicRegulatoryElements.cpp.
void lanelet::RightOfWay::addRightOfWayLanelet | ( | const Lanelet & | lanelet | ) |
Adds a lanelet for RightOfWay.
Definition at line 254 of file BasicRegulatoryElements.cpp.
void lanelet::RightOfWay::addYieldLanelet | ( | const Lanelet & | lanelet | ) |
Add yielding lanelet.
Definition at line 258 of file BasicRegulatoryElements.cpp.
ManeuverType lanelet::RightOfWay::getManeuver | ( | const ConstLanelet & | lanelet | ) | const |
returns whether a lanelet has to yield or has right of way
Definition at line 218 of file BasicRegulatoryElements.cpp.
|
inlinestatic |
Create a valid Right of Way object.
id | id for this rule |
attributes | for this rule. Might be extended if necessary |
rightOfWay | the lanelets that have right of way |
yield | the lanelets that have to yield |
stopLine | line where to stop. If there is none, stop at the end of the lanelet. |
Definition at line 101 of file BasicRegulatoryElements.h.
bool lanelet::RightOfWay::removeRightOfWayLanelet | ( | const Lanelet & | lanelet | ) |
Removes a right of way lanelet and returns true on success.
Definition at line 260 of file BasicRegulatoryElements.cpp.
void lanelet::RightOfWay::removeStopLine | ( | ) |
Removes the stop line.
Definition at line 268 of file BasicRegulatoryElements.cpp.
bool lanelet::RightOfWay::removeYieldLanelet | ( | const Lanelet & | lanelet | ) |
Removes a yielding lanelet and returns true no success.
Definition at line 264 of file BasicRegulatoryElements.cpp.
Lanelets lanelet::RightOfWay::rightOfWayLanelets | ( | ) |
Lanelets lanelet::RightOfWay::rightOfWayLanelets | ( | ) | const |
get the lanelets have right of way
Definition at line 228 of file BasicRegulatoryElements.cpp.
void lanelet::RightOfWay::setStopLine | ( | const LineString3d & | stopLine | ) |
Overwrites the stop line.
Definition at line 252 of file BasicRegulatoryElements.cpp.
Optional<LineString3d> lanelet::RightOfWay::stopLine | ( | ) |
Optional< LineString3d > lanelet::RightOfWay::stopLine | ( | ) | const |
get the stop line for the yield lanelets, if present
Definition at line 236 of file BasicRegulatoryElements.cpp.
Lanelets lanelet::RightOfWay::yieldLanelets | ( | ) |
Lanelets lanelet::RightOfWay::yieldLanelets | ( | ) | const |
get the lanelets that have to yield
Definition at line 232 of file BasicRegulatoryElements.cpp.
|
friend |
Definition at line 140 of file BasicRegulatoryElements.h.
|
staticconstexpr |
Definition at line 90 of file BasicRegulatoryElements.h.