Go to the documentation of this file.
13 return !lhs.expired() && !rhs.expired() && lhs.lock() == rhs.lock();
20 auto parameterIt = parameters.find(role);
21 if (parameterIt == parameters.end()) {
24 auto& parameter = parameterIt->second;
26 if (it == parameter.end()) {
30 if (parameter.empty()) {
31 parameters.erase(parameterIt);
37 Optional<T> tryGetFront(
const std::vector<T>& vec) {
45 RuleParameters toRuleParameters(
const std::vector<T>& primitives) {
50 RuleParameters toRuleParameters(
const std::vector<LineStringOrPolygon3d>& primitives) {
51 return utils::transform(primitives, [](
const auto& elem) {
return elem.asRuleParameter(); });
55 auto params = paramsMap.find(role);
56 if (params == paramsMap.end()) {
61 for (
const auto& param : params->second) {
62 const auto* l = boost::get<LineString3d>(¶m);
66 const auto*
p = boost::get<Polygon3d>(¶m);
76 [](
auto& lsOrPoly) {
return static_cast<ConstLineStringOrPolygon3d
>(lsOrPoly); });
79 void updateTrafficSigns(TrafficSignsWithType trafficSigns) {
80 if (!trafficSigns.type.empty()) {
81 for (
auto& sign : trafficSigns.trafficSigns) {
90 const Optional<LineString3d>& stopLine) {
95 auto data = std::make_shared<RegulatoryElementData>(
id, std::move(rpm), attributes);
101 const TrafficSignsWithType& trafficSigns,
102 const TrafficSignsWithType& cancellingTrafficSigns,
104 updateTrafficSigns(trafficSigns);
105 updateTrafficSigns(cancellingTrafficSigns);
110 auto data = std::make_shared<RegulatoryElementData>(
id, std::move(rpm), attributes);
116 const TrafficSignsWithType& trafficSigns,
117 const TrafficSignsWithType& cancellingTrafficSigns,
119 auto data = constructTrafficSignData(
id, attributes, trafficSigns, cancellingTrafficSigns, refLines, cancelLines);
124 const Lanelets& yield,
const Optional<LineString3d>& stopLine) {
127 auto data = std::make_shared<RegulatoryElementData>(
id, std::move(rpm), attributes);
140 auto sl = utils::createReserved<RuleParameters>(lltWithStop.size());
142 if (!!stop.stopLine) {
143 sl.push_back(static_cast<RuleParameter>(*stop.stopLine));
148 auto data = std::make_shared<RegulatoryElementData>(
id, std::move(rpm), attributes);
160 #if __cplusplus < 201703L
179 :
TrafficLight(constructTrafficLightData(
id, attributes, trafficLights, stopLine)) {}
207 throw InvalidInputError(
"A maneuver must refer to at least one lanelet that has right of way!");
210 throw InvalidInputError(
"A maneuver must refer to at least one lanelet that has to yield!");
216 :
RightOfWay(constructRightOfWayData(
id, attributes, rightOfWay, yield, stopLine)) {}
278 constructTrafficSignData(
id, attributes, trafficSigns, cancellingTrafficSigns, refLines, cancelLines)) {}
288 if (!signs.empty() &&
289 signs.front().applyVisitor([](
auto& prim) { return prim.hasAttribute(AttributeName::Subtype); })) {
290 const auto& attr = signs.front().applyVisitor([](
auto& prim) {
return prim.attribute(
AttributeName::Subtype); });
293 if (!signs.empty()) {
294 throw InvalidInputError(
"Regulatory element has a traffic sign without subtype attribute!");
299 throw InvalidInputError(
"Regulatory element can not determine the type of the traffic sign!");
332 constructSpeedLimitData(
id, attributes, trafficSigns, cancellingTrafficSigns, refLines, cancelLines)) {}
337 updateTrafficSigns(signs);
355 std::vector<std::string> types;
356 types.reserve(signs.size());
357 for (
auto& sign : signs) {
358 types.push_back(sign.applyVisitor([](
auto& prim) { return prim.attribute(AttributeName::Subtype); }).value());
360 std::sort(types.begin(), types.end());
361 types.erase(std::unique(types.begin(), types.end()), types.end());
383 auto it =
std::find(llts.begin(), llts.end(), llt);
384 if (it == llts.end()) {
396 auto it =
std::find(llts.begin(), llts.end(), llt);
397 if (it == llts.end()) {
420 throw InvalidInputError(
"A lanelet with stop line was added, but existing lanelets don't have a stop line!");
422 if (!sl.empty() && !lltWithStop.
stopLine) {
423 throw InvalidInputError(
"A lanelet without stopline was added, but existing lanelets have a stop line!");
436 auto& yieldLLts = yieldIt->second;
438 if (lltIt == yieldLLts.end()) {
442 if (linesIt !=
parameters().
end() && !linesIt->second.empty()) {
443 linesIt->second.erase(linesIt->second.begin() +
std::distance(yieldLLts.begin(), lltIt));
445 yieldLLts.erase(lltIt);
457 if (row != parameters().end() && !row->second.empty()) {
458 throw InvalidInputError(
"An all way stop must not have a lanelet with right of way!");
460 if (lines == parameters().end() || lines->second.empty()) {
463 if (yields == parameters().end() || lines->second.size() != yields->second.size()) {
464 throw InvalidInputError(
465 "Inconsistent number of lanelets and stop lines found! Either one stop line per lanelet or no stop lines!");
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
@ Cancels
primitive(s) that invalidate a rule (eg end of speed zone)
std::vector< LineString3d > LineStrings3d
ConstLineStrings3d refLines() const
gets the line(s) from which a sign becomes valid.
@ RefLine
The referring line where the rule becomes active.
std::vector< ConstLineStringOrPolygon3d > ConstLineStringsOrPolygons3d
bool removeRightOfWayLanelet(const Lanelet &lanelet)
Removes a right of way lanelet and returns true on success.
void forEach(Container &&c, Func &&f)
void addRefLine(const LineString3d &line)
Add a new reference line.
void addCancellingTrafficSign(const TrafficSignsWithType &signs)
Add new cancelling traffic sign.
bool empty() const
returns true if this object contains no parameters
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.
@ Yield
A lanelet that has to yield.
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map > AttributeMap
bool hasAttribute(const std::string &name) const noexcept
check whether this primitive has a specific attribute
RoleName
Typical role names within lanelet (for faster lookup)
const Attribute & attribute(const std::string &name) const
retrieve an attribute
void removeStopLine()
Deletes the stop line.
ConstLineStringsOrPolygons3d trafficSigns() const
returns the traffic signs
static RegisterRegulatoryElement< TrafficSign > regTrafficSign
void addYieldLanelet(const Lanelet &lanelet)
Add yielding lanelet.
static constexpr const char AllWayStop[]
static RegisterRegulatoryElement< AllWayStop > regAllWayStop
std::shared_ptr< RegulatoryElementData > RegulatoryElementDataPtr
void addTrafficSign(const LineStringOrPolygon3d &sign)
Adds another traffic sign.
static constexpr const char RightOfWay[]
auto transform(Iterator begin, Iterator end, const Func f)
const std::string & value() const
gets the value of this attribute
@ Unknown
Lanelet ist not part of relation.
size_t size() const
get the number of roles in this regulatoryElement
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
static RegisterRegulatoryElement< TrafficLight > regTraffic
Expresses a generic traffic sign rule.
std::vector< RuleParameter > RuleParameters
Multiple parameters can have the same role in a rule (eg traffic_lights)
static constexpr const char RegulatoryElement[]
static RegisterRegulatoryElement< SpeedLimit > regSpeedLimit
static constexpr char RuleName[]
static constexpr const char SignType[]
TrafficLight(Id id, const AttributeMap &attributes, const LineStringsOrPolygons3d &trafficLights, const Optional< LineString3d > &stopLine)
RuleParameter asRuleParameter() const
iterator find(const key_type &k)
static constexpr const char Refers[]
static constexpr const char TrafficLight[]
void addTrafficSign(const LineStringOrPolygon3d &sign)
Adds another traffic sign.
auto strong(std::vector< WeakT > v)
transforms a vector of weak_ptrs to a vector of shared_ptrs
ConstLineStringsOrPolygons3d cancellingTrafficSigns() const
get list of cancellingTrafficSigns, if existing
Defines right of way restrictions.
boost::optional< T > Optional
The famous (mutable) lanelet class.
Represents a traffic light restriction on the lanelet.
std::vector< std::string > cancelTypes() const
Types of the cancelling traffic signs if they exist.
Optional< ConstLineString3d > getStopLine(const ConstLanelet &llt) const
gets the stop line for a lanelet, if there is one
static constexpr const char Cancels[]
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.
static constexpr const char CancelLine[]
@ RightOfWay
Lanelet has right of way
const_iterator end() const
static constexpr char RuleName[]
Used as input argument to create TrafficSign regElem.
std::weak_ptr< const LaneletData > LaneletDataConstWptr
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
bool operator==(const lanelet::LaneletDataConstWptr &lhs, const lanelet::LaneletDataConstWptr &rhs)
LineStringsOrPolygons3d trafficSigns
Lists relevant traffic signs.
bool contains(const Container &c, const Value &v)
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
const RuleParameterMap & parameters() const
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
@ RightOfWay
A lanelet that has right of way in a relation.
std::string type() const
get the id/number of the sign(s)
@ CancelLine
The line from which a rule is invalidated.
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.
This class holds either a LineString3d or a Polygon3d.
static RegisterRegulatoryElement< RightOfWay > regRightOfWay
static constexpr const char Yield[]
static constexpr const char RefLine[]
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.
Optional< double > distance
RegulatoryElementDataPtr data()
RightOfWay(Id id, const AttributeMap &attributes, const Lanelets &rightOfWay, const Lanelets &yield, const Optional< LineString3d > &stopLine={})
static constexpr const char SpeedLimit[]
@ Refers
The primitive(s) that are the origin of this rule (ie signs)
bool removeCancellingTrafficSign(const LineStringOrPolygon3d &sign)
remove a cancelling traffic sign, returns true on success
void addLanelet(const LaneletWithStopLine &lltWithStop)
auto find(ContainerT &&c, const ValueT &val)
bool removeLanelet(const Lanelet &llt)
Removes a lanelet and the associated stop line, if there is one.
A normal 3d linestring with mutable data.
void addTrafficLight(const LineStringOrPolygon3d &primitive)
add a new traffic light
boost::variant< Point3d, LineString3d, Polygon3d, WeakLanelet, WeakArea > RuleParameter
static constexpr const char TrafficSign[]
std::vector< ConstLanelet > ConstLanelets
HybridMap< RuleParameters, decltype(RoleNameString::Map)&, RoleNameString::Map > RuleParameterMap
Rules are stored in a map internally.
ConstLineStrings3d cancelLines() const
gets the line(s) from which a sign becomes invalid.
static constexpr const char RightOfWay[]
lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52