Go to the documentation of this file.
7 leftBound_{
utils::transform(lanelets_, [](
const auto& l) {
return l.leftBound(); })},
8 rightBound_{
utils::transform(lanelets_, [](
const auto& l) {
return l.rightBound(); })} {}
11 auto centerline = std::atomic_load_explicit(¢erline_, std::memory_order_acquire);
13 centerline = std::make_shared<CompoundLineString3d>(
15 std::atomic_store_explicit(¢erline_, centerline, std::memory_order_release);
21 auto polygon = std::atomic_load_explicit(&polygon_, std::memory_order_acquire);
23 polygon = std::make_shared<CompoundPolygon3d>(
CompoundLineStrings3d{leftBound_, rightBound_.invert()});
24 std::atomic_store_explicit(&polygon_, polygon, std::memory_order_release);
Combines multiple linestrings to one polygon in 3d.
auto concatenate(ContainerT &&c)
overload assuming that c is a container of containers. The return type will be the type of the inner ...
auto transform(Iterator begin, Iterator end, const Func f)
A Compound linestring in 3d (returns Point3d)
std::vector< CompoundLineString3d > CompoundLineStrings3d
ConstLanelets lanelets() const
returns the lanelets that are part of this object
CompoundLineString3d centerline() const
computes the centerline. Result is cached
CompoundPolygon3d polygon() const
Get the bounding polygon around all lanelets. Result is cached.
RegulatoryElementConstPtrs regulatoryElements() const
get a list of all regulatory elements that affect one of the lanelets
LaneletSequenceData(ConstLanelets lanelets)
Constructs a new, valid LaneletData object.
const ConstLanelets & lanelets() const
std::vector< RegulatoryElementConstPtr > RegulatoryElementConstPtrs
std::vector< ConstLanelet > ConstLanelets
lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52