LaneletSequence.cpp
Go to the documentation of this file.
2 
3 namespace lanelet {
4 
6  : lanelets_{std::move(lanelets)},
7  leftBound_{utils::transform(lanelets_, [](const auto& l) { return l.leftBound(); })},
8  rightBound_{utils::transform(lanelets_, [](const auto& l) { return l.rightBound(); })} {}
9 
11  auto centerline = std::atomic_load_explicit(&centerline_, std::memory_order_acquire);
12  if (!centerline) {
13  centerline = std::make_shared<CompoundLineString3d>(
14  utils::transform(lanelets_, [](const auto& l) { return l.centerline(); }));
15  std::atomic_store_explicit(&centerline_, centerline, std::memory_order_release);
16  }
17  return *centerline;
18 }
19 
21  auto polygon = std::atomic_load_explicit(&polygon_, std::memory_order_acquire);
22  if (!polygon) {
23  polygon = std::make_shared<CompoundPolygon3d>(CompoundLineStrings3d{leftBound_, rightBound_.invert()});
24  std::atomic_store_explicit(&polygon_, polygon, std::memory_order_release);
25  }
26  return *polygon;
27 }
28 
30  return utils::concatenate(lanelets(), [](const auto& elem) { return elem.regulatoryElements(); });
31 }
32 
33 } // namespace lanelet
CompoundPolygon3d polygon() const
Get the bounding polygon around all lanelets. Result is cached.
LaneletSequenceData(ConstLanelets lanelets)
Constructs a new, valid LaneletData object.
A Compound linestring in 3d (returns Point3d)
auto transform(Iterator begin, Iterator end, const Func f)
Definition: Utilities.h:176
std::vector< CompoundLineString3d > CompoundLineStrings3d
Definition: Forward.h:77
const ConstLanelets & lanelets() const
std::shared_ptr< CompoundLineString3d > centerline_
combined centerline
CompoundLineString3d centerline() const
computes the centerline. Result is cached
CompoundLineString3d invert() const noexcept
create a new, inverted linestring from this one
Combines multiple linestrings to one polygon in 3d.
const CompoundLineString3d leftBound_
< Cached data
RegulatoryElementConstPtrs regulatoryElements() const
get a list of all regulatory elements that affect one of the lanelets
auto concatenate(ContainerT &&c)
overload assuming that c is a container of containers. The return type will be the type of the inner ...
Definition: Utilities.h:260
std::vector< RegulatoryElementConstPtr > RegulatoryElementConstPtrs
Definition: Forward.h:195
const ConstLanelets lanelets_
std::shared_ptr< CompoundPolygon3d > polygon_
combined polygon
const CompoundLineString3d rightBound_
std::vector< ConstLanelet > ConstLanelets
Definition: Forward.h:114


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Tue Jun 6 2023 02:23:32