LaneletSequence.h
Go to the documentation of this file.
1 #pragma once
2 #include <utility>
3 
7 
8 namespace lanelet {
9 
22 class LaneletSequenceData : public boost::noncopyable {
23  public:
24  using iterator = // NOLINT
31 
32  const CompoundLineString3d& leftBound() const { return leftBound3d(); }
33  const CompoundLineString3d& leftBound3d() const { return leftBound_; }
35 
36  const CompoundLineString3d& rightBound() const { return rightBound3d(); }
37  const CompoundLineString3d& rightBound3d() const { return rightBound_; }
39  const ConstLanelets& lanelets() const { return lanelets_; }
40 
47 
53  CompoundPolygon3d polygon() const;
54 
55  iterator begin(bool inverted) const noexcept {
56  return inverted ? iterator(lanelets_.rbegin()) : iterator(lanelets_.begin());
57  }
58 
59  iterator end(bool inverted) const noexcept {
60  return inverted ? iterator(lanelets_.rend()) : iterator(lanelets_.end());
61  }
62 
63  private:
64  const ConstLanelets lanelets_; // NOLINT
68  mutable std::shared_ptr<CompoundLineString3d> centerline_;
69  mutable std::shared_ptr<CompoundPolygon3d> polygon_;
70 };
71 
86  public:
88  using TwoDType = void;
89  using ThreeDType = void;
90  using HybridType = void;
92  using MutableType = void;
94 
101  : data_{std::make_shared<LaneletSequenceData>(std::move(ls))} {}
102 
107  explicit LaneletSequence(const LaneletSequences& ls)
108  : LaneletSequence(utils::concatenate(ls, [](const auto& e) { return e.lanelets(); })) {}
109 
111 
120  bool inverted() const { return inverted_; }
121 
123  bool empty() const noexcept { return data_->lanelets().empty(); }
124 
126  size_t size() const noexcept { return data_->lanelets().size(); }
127 
134  LaneletSequence invert() const { return {constData(), !inverted()}; }
135 
141  return inverted() ? constData()->rightBound().invert() : constData()->leftBound();
142  }
143 
150  return inverted() ? constData()->leftBound().invert() : constData()->rightBound();
151  }
152 
155 
160  template <typename RegElemT>
161  std::vector<std::shared_ptr<const RegElemT>> regulatoryElementsAs() const {
162  return utils::concatenate(lanelets(),
163  [](const auto& elem) { return elem.template regulatoryElementsAs<RegElemT>(); });
164  }
165 
182  return inverted() ? constData()->centerline().invert() : constData()->centerline();
183  }
185 
194  CompoundPolygon3d polygon3d() const { return constData()->polygon(); }
195 
201 
206  ConstLanelets lanelets() const { return inverted() ? utils::invert(data_->lanelets()) : data_->lanelets(); }
207 
209  iterator begin() const noexcept { return data_->begin(inverted()); }
210 
212  iterator end() const noexcept { return data_->end(inverted()); }
213 
215  const ConstLanelet& operator[](size_t idx) const {
216  assert(idx < data_->lanelets().size());
217  return *std::next(begin(), idx);
218  }
219 
224  Ids ids() const {
225  return utils::transform(lanelets(), [](const auto& ls) { return ls.id(); });
226  }
227 
232 
238  void resetCache() { data_ = std::make_shared<LaneletSequenceData>(data_->lanelets()); }
239 
240  private:
241  std::shared_ptr<const LaneletSequenceData> data_;
242  bool inverted_{false};
243 };
244 
245 namespace utils {
256 inline bool has(const LaneletSequence& ll, Id id) { return has(ll.leftBound(), id) || has(ll.rightBound(), id); }
257 } // namespace utils
258 
259 inline bool operator==(const LaneletSequence& lhs, const LaneletSequence& rhs) {
260  return lhs.lanelets() == rhs.lanelets();
261 }
262 inline bool operator!=(const LaneletSequence& lhs, const LaneletSequence& rhs) { return !(rhs == lhs); }
263 
264 inline std::ostream& operator<<(std::ostream& stream, const LaneletSequence& obj) {
265  auto ids = obj.ids();
266  stream << "[";
267  if (!ids.empty()) {
268  stream << "ids: ";
269  std::copy(ids.begin(), ids.end(), std::ostream_iterator<Id>(stream, " "));
270  }
271  if (obj.inverted()) {
272  stream << ", inverted";
273  }
274  return stream << "]";
275 }
276 } // namespace lanelet
lanelet::LaneletSequenceData::rightBound3d
const CompoundLineString3d & rightBound3d() const
Definition: LaneletSequence.h:37
lanelet::LaneletSequence::LaneletSequence
LaneletSequence(ConstLanelets ls=ConstLanelets())
Construct from a vector of ConstLineString3d.
Definition: LaneletSequence.h:100
lanelet::LaneletSequenceData::rightBound2d
CompoundLineString2d rightBound2d() const
Definition: LaneletSequence.h:38
lanelet::CompoundPolygon3d
Combines multiple linestrings to one polygon in 3d.
Definition: CompoundPolygon.h:40
lanelet::traits::to2D
BoundingBox2d to2D(const BoundingBox3d &primitive)
Definition: primitives/BoundingBox.h:304
lanelet
Definition: Attribute.h:13
lanelet::utils::concatenate
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
lanelet::LaneletSequenceData::centerline_
std::shared_ptr< CompoundLineString3d > centerline_
combined centerline
Definition: LaneletSequence.h:68
lanelet::LaneletSequence::rightBound3d
CompoundLineString3d rightBound3d() const
get the combined right bounds of all lanelets
Definition: LaneletSequence.h:149
lanelet::LaneletSequence
A collection of Lanelets.
Definition: LaneletSequence.h:85
lanelet::LaneletSequenceDataConstPtr
std::shared_ptr< const LaneletSequenceData > LaneletSequenceDataConstPtr
Definition: Forward.h:94
lanelet::utils::invert
Container invert(const Container &cont)
Definition: Utilities.h:169
lanelet::operator==
bool operator==(const Attribute &lhs, const Attribute &rhs)
Definition: Attribute.h:179
lanelet::LaneletSequence::LaneletSequence
LaneletSequence(LaneletSequenceDataConstPtr data, bool inverted)
Definition: LaneletSequence.h:110
lanelet::LaneletSequence::leftBound3d
CompoundLineString3d leftBound3d() const
Definition: LaneletSequence.h:140
lanelet::Id
int64_t Id
Definition: Forward.h:198
lanelet::operator<<
std::ostream & operator<<(std::ostream &stream, const Attribute &obj)
Definition: Attribute.h:369
lanelet::Ids
std::vector< Id > Ids
Definition: Forward.h:200
lanelet::utils::transform
auto transform(Iterator begin, Iterator end, const Func f)
Definition: Utilities.h:176
lanelet::LaneletSequence::begin
iterator begin() const noexcept
Returns iterator to the first lanelet (or to the last, if inverted)
Definition: LaneletSequence.h:209
lanelet::LaneletSequence::centerline3d
CompoundLineString3d centerline3d() const
Definition: LaneletSequence.h:181
lanelet::LaneletSequenceData::leftBound
const CompoundLineString3d & leftBound() const
Definition: LaneletSequence.h:32
lanelet::LaneletSequence::invert
LaneletSequence invert() const
returns the respective inverted LaneletSequence
Definition: LaneletSequence.h:134
lanelet::LaneletSequence::TwoDType
void TwoDType
Definition: LaneletSequence.h:88
lanelet::LaneletSequenceData::end
iterator end(bool inverted) const noexcept
Definition: LaneletSequence.h:59
lanelet::CompoundLineString3d
A Compound linestring in 3d (returns Point3d)
Definition: CompoundLineString.h:285
lanelet::LaneletSequence::rightBound
CompoundLineString3d rightBound() const
get the combined right bounds of all lanelets
Definition: LaneletSequence.h:145
lanelet::LaneletSequence::leftBound
CompoundLineString3d leftBound() const
get the combined left bounds of all lanelets
Definition: LaneletSequence.h:137
lanelet::LaneletSequence::constData
LaneletSequenceDataConstPtr constData() const
returns the internal data on the linestrings managed by this object
Definition: LaneletSequence.h:231
lanelet::LaneletSequenceData::leftBound_
const CompoundLineString3d leftBound_
< Cached data
Definition: LaneletSequence.h:66
lanelet::LaneletSequenceData::leftBound2d
CompoundLineString2d leftBound2d() const
Definition: LaneletSequence.h:34
lanelet::LaneletSequence::regulatoryElementsAs
std::vector< std::shared_ptr< const RegElemT > > regulatoryElementsAs() const
get all regulatory elements of type RegElemT
Definition: LaneletSequence.h:161
lanelet::LaneletSequence::polygon2d
CompoundPolygon2d polygon2d() const
returns the surface covered by the lanelets as 2-dimensional polygon.
Definition: LaneletSequence.h:200
lanelet::LaneletSequence::lanelets
ConstLanelets lanelets() const
returns the lanelets that are part of this object
Definition: LaneletSequence.h:206
lanelet::LaneletSequenceData::iterator
internal::ReverseAndForwardIterator< ConstLanelets::const_iterator > iterator
Definition: LaneletSequence.h:25
lanelet::LaneletSequence::rightBound2d
CompoundLineString2d rightBound2d() const
get the right bound in 2d. To be used over rightBound where geometric calculations are required.
Definition: LaneletSequence.h:147
lanelet::LaneletSequenceData::rightBound_
const CompoundLineString3d rightBound_
Definition: LaneletSequence.h:67
lanelet::LaneletSequence::ids
Ids ids() const
returns the ids of all lanelets in order
Definition: LaneletSequence.h:224
lanelet::LaneletSequenceData::centerline
CompoundLineString3d centerline() const
computes the centerline. Result is cached
Definition: LaneletSequence.cpp:10
lanelet::LaneletSequenceData::polygon
CompoundPolygon3d polygon() const
Get the bounding polygon around all lanelets. Result is cached.
Definition: LaneletSequence.cpp:20
lanelet::CompoundPolygon2d
Combines multiple linestrings to one polygon in 2d.
Definition: CompoundPolygon.h:11
lanelet::LaneletSequence::regulatoryElements
RegulatoryElementConstPtrs regulatoryElements() const
get a list of all regulatory elements that affect one of the lanelets
Definition: LaneletSequence.cpp:29
lanelet::LaneletSequence::centerline
CompoundLineString3d centerline() const
get the centerline of this lanelet
Definition: LaneletSequence.h:180
lanelet::operator!=
bool operator!=(const Attribute &lhs, const Attribute &rhs)
Definition: Attribute.h:180
lanelet::LaneletSequence::end
iterator end() const noexcept
Returns iterator to the last lanelet (or to the first, if inverted)
Definition: LaneletSequence.h:212
lanelet::LaneletSequence::inverted_
bool inverted_
Flag that indicates this lanelet is inverted.
Definition: LaneletSequence.h:242
CompoundPolygon.h
lanelet::LaneletSequence::size
size_t size() const noexcept
Returns number of lanelets.
Definition: LaneletSequence.h:126
lanelet::LaneletSequenceData::lanelets_
const ConstLanelets lanelets_
Definition: LaneletSequence.h:64
lanelet::LaneletSequenceData::LaneletSequenceData
LaneletSequenceData(ConstLanelets lanelets)
Constructs a new, valid LaneletData object.
Definition: LaneletSequence.cpp:5
lanelet::LaneletSequence::MutableType
void MutableType
Definition: LaneletSequence.h:92
lanelet::LaneletSequence::resetCache
void resetCache()
call this function if one of the contained Lanelets was modified to give this object the opportunity ...
Definition: LaneletSequence.h:238
lanelet::LaneletSequenceData::polygon_
std::shared_ptr< CompoundPolygon3d > polygon_
combined polygon
Definition: LaneletSequence.h:69
lanelet::LaneletSequence::leftBound2d
CompoundLineString2d leftBound2d() const
get the left bound in 2d. To be used over leftBound where geometric calculations are required.
Definition: LaneletSequence.h:139
lanelet::utils::has
bool has(const ConstArea &ll, Id id)
returns true if element of a regulatory element has a matching Id
Definition: primitives/Area.h:324
lanelet::LaneletSequence::data_
std::shared_ptr< const LaneletSequenceData > data_
internal data
Definition: LaneletSequence.h:241
lanelet::LaneletSequence::operator[]
const ConstLanelet & operator[](size_t idx) const
Access an individual lanelet.
Definition: LaneletSequence.h:215
lanelet::LaneletSequence::HybridType
void HybridType
Definition: LaneletSequence.h:90
lanelet::LaneletSequence::polygon3d
CompoundPolygon3d polygon3d() const
returns the surface covered by the lanelets as 3-dimensional polygon. The result of the computation i...
Definition: LaneletSequence.h:194
lanelet::LaneletSequences
std::vector< LaneletSequence > LaneletSequences
Definition: Forward.h:118
lanelet::CompoundLineString2d
A Compound linestring in 2d (returns Point2d)
Definition: CompoundLineString.h:263
lanelet::LaneletSequenceData::lanelets
const ConstLanelets & lanelets() const
Definition: LaneletSequence.h:39
lanelet::LaneletSequence::empty
bool empty() const noexcept
Returns wether this holds any lanelets.
Definition: LaneletSequence.h:123
lanelet::RegulatoryElementConstPtrs
std::vector< RegulatoryElementConstPtr > RegulatoryElementConstPtrs
Definition: Forward.h:195
Lanelet.h
lanelet::ConstLanelet
An immutable lanelet.
Definition: primitives/Lanelet.h:131
lanelet::LaneletSequenceData::rightBound
const CompoundLineString3d & rightBound() const
Definition: LaneletSequence.h:36
lanelet::LaneletSequenceData::begin
iterator begin(bool inverted) const noexcept
Definition: LaneletSequence.h:55
lanelet::LaneletSequence::inverted
bool inverted() const
returns out if this is an inverted lanelets.
Definition: LaneletSequence.h:120
lanelet::LaneletSequence::LaneletSequence
LaneletSequence(const LaneletSequences &ls)
Create a compound lanelet from other compound lanelets.
Definition: LaneletSequence.h:107
lanelet::LaneletSequenceData
Common data management class for LaneletSequences.
Definition: LaneletSequence.h:22
lanelet::utils::detail::concatenate
VectorT concatenate(ContainerT &&c)
Definition: Utilities.h:63
lanelet::LaneletSequence::centerline2d
CompoundLineString2d centerline2d() const
Definition: LaneletSequence.h:184
CompoundLineString.h
lanelet::LaneletSequenceData::leftBound3d
const CompoundLineString3d & leftBound3d() const
Definition: LaneletSequence.h:33
lanelet::LaneletSequence::ThreeDType
void ThreeDType
Definition: LaneletSequence.h:89
lanelet::internal::ReverseAndForwardIterator
Definition: ReverseAndForwardIterator.h:9
lanelet::ConstLanelets
std::vector< ConstLanelet > ConstLanelets
Definition: Forward.h:114


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52