Go to the documentation of this file.
69 mutable std::shared_ptr<CompoundPolygon3d>
polygon_;
101 :
data_{std::make_shared<LaneletSequenceData>(std::move(ls))} {}
123 bool empty() const noexcept {
return data_->lanelets().empty(); }
126 size_t size() const noexcept {
return data_->lanelets().size(); }
160 template <
typename RegElemT>
163 [](
const auto& elem) {
return elem.template regulatoryElementsAs<RegElemT>(); });
217 return *std::next(
begin(), idx);
241 std::shared_ptr<const LaneletSequenceData>
data_;
265 auto ids = obj.
ids();
269 std::copy(ids.begin(), ids.end(), std::ostream_iterator<Id>(stream,
" "));
272 stream <<
", inverted";
274 return stream <<
"]";
const CompoundLineString3d & rightBound3d() const
LaneletSequence(ConstLanelets ls=ConstLanelets())
Construct from a vector of ConstLineString3d.
CompoundLineString2d rightBound2d() const
Combines multiple linestrings to one polygon in 3d.
BoundingBox2d to2D(const BoundingBox3d &primitive)
auto concatenate(ContainerT &&c)
overload assuming that c is a container of containers. The return type will be the type of the inner ...
std::shared_ptr< CompoundLineString3d > centerline_
combined centerline
CompoundLineString3d rightBound3d() const
get the combined right bounds of all lanelets
A collection of Lanelets.
std::shared_ptr< const LaneletSequenceData > LaneletSequenceDataConstPtr
Container invert(const Container &cont)
bool operator==(const Attribute &lhs, const Attribute &rhs)
LaneletSequence(LaneletSequenceDataConstPtr data, bool inverted)
CompoundLineString3d leftBound3d() const
std::ostream & operator<<(std::ostream &stream, const Attribute &obj)
auto transform(Iterator begin, Iterator end, const Func f)
iterator begin() const noexcept
Returns iterator to the first lanelet (or to the last, if inverted)
CompoundLineString3d centerline3d() const
const CompoundLineString3d & leftBound() const
LaneletSequence invert() const
returns the respective inverted LaneletSequence
iterator end(bool inverted) const noexcept
A Compound linestring in 3d (returns Point3d)
CompoundLineString3d rightBound() const
get the combined right bounds of all lanelets
CompoundLineString3d leftBound() const
get the combined left bounds of all lanelets
LaneletSequenceDataConstPtr constData() const
returns the internal data on the linestrings managed by this object
const CompoundLineString3d leftBound_
< Cached data
CompoundLineString2d leftBound2d() const
std::vector< std::shared_ptr< const RegElemT > > regulatoryElementsAs() const
get all regulatory elements of type RegElemT
CompoundPolygon2d polygon2d() const
returns the surface covered by the lanelets as 2-dimensional polygon.
ConstLanelets lanelets() const
returns the lanelets that are part of this object
internal::ReverseAndForwardIterator< ConstLanelets::const_iterator > iterator
CompoundLineString2d rightBound2d() const
get the right bound in 2d. To be used over rightBound where geometric calculations are required.
const CompoundLineString3d rightBound_
Ids ids() const
returns the ids of all lanelets in order
CompoundLineString3d centerline() const
computes the centerline. Result is cached
CompoundPolygon3d polygon() const
Get the bounding polygon around all lanelets. Result is cached.
Combines multiple linestrings to one polygon in 2d.
RegulatoryElementConstPtrs regulatoryElements() const
get a list of all regulatory elements that affect one of the lanelets
CompoundLineString3d centerline() const
get the centerline of this lanelet
bool operator!=(const Attribute &lhs, const Attribute &rhs)
iterator end() const noexcept
Returns iterator to the last lanelet (or to the first, if inverted)
bool inverted_
Flag that indicates this lanelet is inverted.
size_t size() const noexcept
Returns number of lanelets.
const ConstLanelets lanelets_
LaneletSequenceData(ConstLanelets lanelets)
Constructs a new, valid LaneletData object.
void resetCache()
call this function if one of the contained Lanelets was modified to give this object the opportunity ...
std::shared_ptr< CompoundPolygon3d > polygon_
combined polygon
CompoundLineString2d leftBound2d() const
get the left bound in 2d. To be used over leftBound where geometric calculations are required.
bool has(const ConstArea &ll, Id id)
returns true if element of a regulatory element has a matching Id
std::shared_ptr< const LaneletSequenceData > data_
internal data
const ConstLanelet & operator[](size_t idx) const
Access an individual lanelet.
CompoundPolygon3d polygon3d() const
returns the surface covered by the lanelets as 3-dimensional polygon. The result of the computation i...
std::vector< LaneletSequence > LaneletSequences
A Compound linestring in 2d (returns Point2d)
const ConstLanelets & lanelets() const
bool empty() const noexcept
Returns wether this holds any lanelets.
std::vector< RegulatoryElementConstPtr > RegulatoryElementConstPtrs
const CompoundLineString3d & rightBound() const
iterator begin(bool inverted) const noexcept
bool inverted() const
returns out if this is an inverted lanelets.
LaneletSequence(const LaneletSequences &ls)
Create a compound lanelet from other compound lanelets.
Common data management class for LaneletSequences.
VectorT concatenate(ContainerT &&c)
CompoundLineString2d centerline2d() const
const CompoundLineString3d & leftBound3d() const
std::vector< ConstLanelet > ConstLanelets
lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52