Go to the documentation of this file.
46 template <
typename RegElemT>
50 template <
typename RegElemT>
181 template <
typename RegElemT>
183 return constData()->regulatoryElementsAs<RegElemT>();
228 Lanelet(
const std::shared_ptr<const LaneletData>&,
bool inverted) =
delete;
234 using Primitive::leftBound;
235 using Primitive::leftBound2d;
236 using Primitive::leftBound3d;
246 using Primitive::rightBound;
247 using Primitive::rightBound2d;
248 using Primitive::rightBound3d;
287 if (regElem ==
nullptr) {
290 data()->regulatoryElements().push_back(std::move(regElem));
295 auto& regElems =
data()->regulatoryElements();
296 auto remove =
std::find(regElems.begin(), regElems.end(), regElem);
297 if (remove != regElems.end()) {
298 regElems.erase(remove);
304 using Primitive::regulatoryElements;
305 using Primitive::regulatoryElementsAs;
308 template <
typename RegElemT>
310 return data()->regulatoryElementsAs<RegElemT>();
366 bool has(
const ConstLanelet& ll,
Id id);
377 std::ostream&
operator<<(std::ostream& stream,
const ConstLanelet& obj);
380 template <
typename T>
382 return isCategory<T, traits::LaneletTag>();
386 template <
typename T,
typename RetT>
387 using IfLL = std::enable_if_t<traits::isLaneletT<T>(), RetT>;
398 template <
typename T,
typename U>
399 struct hash<
std::pair<U, T>> {
401 return std::hash<U>()(x.first) ^ std::hash<T>()(x.second);
WeakLanelet(const Lanelet &llet)
constexpr Id InvalId
indicates a primitive that is not part of a map
bool removeRegulatoryElement(const RegulatoryElementPtr ®Elem)
Removes a regulatory element, returns true on success.
Base class for all mutable Primitives of lanelet2.
RegulatoryElementPtrs regulatoryElements_
regulatory elements
LineString3d leftBound3d()
get the left bound in 3d. To be used over leftBound where geometric calculations are required.
std::vector< RegulatoryElementPtr > RegulatoryElementPtrs
ConstWeakLanelet()=default
void resetCache() const
call this to indicate that the objects data has been modified.
Lanelet invert() const
non-const version to invert a lanelet
Common data class for all lanelet primitives.
Common data management class for all Lanelet-Typed objects.
Combines multiple linestrings to one polygon in 3d.
ConstLineString2d centerline2d() const
get the (cached) centerline of this lanelet in 2d. To be used in context of geometric calculations.
LineString3d rightBound3d()
get the right bound in 3d. To be used over rightBound where geometric calculations are required.
BoundingBox2d to2D(const BoundingBox3d &primitive)
ConstLineString2d leftBound2d() const
get the left bound in 2d. To be used over leftBound where geometric calculations are required.
bool hasCustomCenterline() const
Returns whether the centerline has been overridden by setCenterline.
std::enable_if_t< traits::isLaneletT< T >(), RetT > IfLL
ConstLineString3d rightBound3d() const
get the right bound in 3d. To be used over rightBound where geometric calculations are required.
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
ConstLanelet invert() const
returns the inverted lanelet
const AttributeMap & attributes() const
get the attributes of this primitive
ConstLineString3d centerline() const
get the (cached) centerline of this lanelet.
const RegulatoryElementPtrs & regulatoryElements()
Return regulatoryElements that affect this lanelet.
void setCenterline(const LineString3d ¢erline)
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map > AttributeMap
ConstLineString2d rightBound2d() const
get the right bound in 2d. To be used over rightBound where geometric calculations are required.
bool inverted() const
returns if this is an inverted lanelet
LineString3d rightBound_
represents the right bound
LineString2d rightBound2d()
get the right bound in 2d. To be used over rightBound where geometric calculations are required.
bool operator==(const Attribute &lhs, const Attribute &rhs)
bool inverted_
indicates if this lanelet is inverted
std::ostream & operator<<(std::ostream &stream, const Attribute &obj)
size_t operator()(const std::pair< U, T > x) const noexcept
void setLeftBound(const LineString3d &bound)
Sets a new left bound. Resets all cached data of this object.
auto transform(Iterator begin, Iterator end, const Func f)
std::weak_ptr< const LaneletData > laneletData_
Lanelet lock() const
Obtains the original Lanelet.
void setRightBound(const LineString3d &bound)
Sets a new right bound and resets the cached centerline.
RegulatoryElementConstPtrs regulatoryElements() const
get a list of regulatory elements that affect this lanelet
RegulatoryElementConstPtrs regulatoryElements() const
bool hasCustomCenterline() const
Returns whether the centerline has been overridden by setCenterline.
A normal 2d linestring with immutable data.
void resetCache() const
resets the internal cache of the centerline
A normal 2d linestring with mutable data.
const std::shared_ptr< const LaneletData > & constData() const
get the internal data of this primitive
ConstLineString3d rightBound() const
get the right bound.
The famous (mutable) lanelet class.
bool expired() const noexcept
tests whether the WeakLanelet is still valid
const LineString3d & rightBound()
std::shared_ptr< ConstLineString3d > centerline_
ConstWeakLanelet(const ConstLanelet &llet)
AttributeMap attributes
attributes of this primitive
ConstLanelet(Id id=InvalId)
Constructs an empty or invalid lanelet.
Lanelet(const LaneletDataPtr &data, bool inverted)
CompoundPolygon2d polygon2d() const
returns the surface covered by this lanelet as 2-dimensional polygon.
LineString3d invert() const noexcept
create a new, inverted linestring from this one
ConstLanelet lock() const
Obtains the original ConstLanelet.
ConstLineString3d invert() const noexcept
create a new, inverted linestring from this one
Combines multiple linestrings to one polygon in 2d.
bool operator!=(const Attribute &lhs, const Attribute &rhs)
ConstLineString3d leftBound3d() const
get the left bound in 3d. To be used over leftBound where geometric calculations are required.
ConstLineString3d centerline() const
Returns centerline by computing it, if necessary. Result is cached.
void setRightBound(const LineString3d &bound)
Sets a new right bound. Resets all cached data of this object.
std::vector< std::shared_ptr< const RegElemT > > regulatoryElementsAs() const
get the regulatoryElements that could be converted to RegElemT
void addRegulatoryElement(RegulatoryElementPtr regElem)
Add a new regulatory element.
void setLeftBound(const LineString3d &bound)
Sets a new left bound and resets the cached centerline.
std::shared_ptr< const RegulatoryElement > RegulatoryElementConstPtr
constexpr bool isLaneletT()
Identifies PolygonPrimitives.
LineString3d rightBound()
Get the right bound.
bool has(const ConstArea &ll, Id id)
returns true if element of a regulatory element has a matching Id
std::shared_ptr< LaneletData > LaneletDataPtr
Basic Primitive class for all primitives of lanelet2.
ConstLineString3d centerline3d() const
get the (cached) centerline of this lanelet in 3d. To be used in context of geometric calculations.
LineString3d leftBound_
represents the left bound
LineString2d leftBound2d()
get the left bound in 2d. To be used over leftBound where geometric calculations are required.
std::vector< RegulatoryElementConstPtr > RegulatoryElementConstPtrs
A normal 3d linestring with immutable data.
ConstLanelet(Id id, const LineString3d &leftBound, const LineString3d &rightBound, const AttributeMap &attributes=AttributeMap(), const RegulatoryElementPtrs ®ulatoryElements=RegulatoryElementPtrs())
Constructs a lanelet from id, attributes, regulatoryElements and bounds.
std::vector< std::shared_ptr< RegElemT > > regulatoryElementsAs()
LineString3d leftBound()
Get the left bound.
const ConstLineString3d & leftBound() const
SharedPtrs in lanelet2 must never point to null. If this is violated, this exception is thrown (usual...
Id id
Id of this primitive (unique across one map)
void setCenterline(const LineString3d ¢erline)
Sets a new right bound. Resets all cached data of this object.
ConstLineString3d leftBound() const
get the left bound.
CompoundPolygon3d polygon() const
Get the bounding polygon of this lanelet. Result is cached.
const LineString3d & leftBound()
std::shared_ptr< DataType > data() const
auto find(ContainerT &&c, const ValueT &val)
const ConstLineString3d & rightBound() const
std::vector< std::shared_ptr< const RegElemT > > regulatoryElementsAs() const
A normal 3d linestring with mutable data.
ConstLanelet(const std::shared_ptr< const LaneletData > &data, bool inverted=false)
Construct from the data of a different Lanelet.
Id id() const noexcept
get the unique id of this primitive
CompoundPolygon3d polygon3d() const
returns the surface covered by this lanelet as 3-dimensional polygon.
ConstLineString3d rightBound() const
get the right bound.
LaneletData(Id id, LineString3d leftBound, LineString3d rightBound, const AttributeMap &attributes=AttributeMap(), RegulatoryElementPtrs regulatoryElements=RegulatoryElementPtrs())
Constructs a new, valid LaneletData object.
std::vector< std::shared_ptr< RegElemT > > regulatoryElementsAs()
Get the regulatoryElements that could be converted to RegElemT.
RegulatoryElementPtrs & regulatoryElements()
lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52