LaneletPath.h
Go to the documentation of this file.
1 #pragma once
2 #include <lanelet2_core/primitives/Lanelet.h>
6 
8 
9 namespace lanelet {
10 namespace routing {
13 class LaneletPath {
14  public:
15  using iterator = ConstLanelets::iterator; // NOLINT
16  using const_iterator = ConstLanelets::const_iterator; // NOLINT
17 
18  explicit LaneletPath(ConstLanelets lanelets = {}) : lanelets_{std::move(lanelets)} {}
19 
20  iterator begin() { return lanelets_.begin(); }
21  const_iterator begin() const { return lanelets_.begin(); }
22  iterator end() { return lanelets_.end(); }
23  const_iterator end() const { return lanelets_.end(); }
24  size_t size() const { return lanelets_.size(); }
25  bool empty() const { return lanelets_.empty(); }
26  const ConstLanelet& front() const { return lanelets_.front(); }
27  const ConstLanelet& back() const { return lanelets_.back(); }
28  const ConstLanelet& operator[](size_t idx) const {
29  assert(idx < lanelets_.size());
30  return lanelets_[idx];
31  }
32 
33  bool operator!=(const LaneletPath& other) const { return !(*this == other); }
34 
35  bool operator==(const LaneletPath& other) const { return lanelets_ == other.lanelets_; }
36 
38  LaneletSequence getRemainingLane(const_iterator laneletPosition) const;
39 
41  return getRemainingLane(std::find(lanelets_.begin(), lanelets_.end(), llt));
42  }
43 
44  private:
46 };
47 
50  public:
51  using iterator = ConstLaneletOrAreas::iterator; // NOLINT
52  using const_iterator = ConstLaneletOrAreas::const_iterator; // NOLINT
53 
54  explicit LaneletOrAreaPath(ConstLaneletOrAreas lltsOrArea = {}) : laneletsOrAreas_{std::move(lltsOrArea)} {}
55 
56  iterator begin() { return laneletsOrAreas_.begin(); }
57  const_iterator begin() const { return laneletsOrAreas_.begin(); }
58  iterator end() { return laneletsOrAreas_.end(); }
59  const_iterator end() const { return laneletsOrAreas_.end(); }
60  size_t size() const { return laneletsOrAreas_.size(); }
61  bool empty() const { return laneletsOrAreas_.empty(); }
62  const ConstLaneletOrArea& front() const { return laneletsOrAreas_.front(); }
63  const ConstLaneletOrArea& back() const { return laneletsOrAreas_.back(); }
64  const ConstLaneletOrArea& operator[](size_t idx) const {
65  assert(idx < laneletsOrAreas_.size());
66  return laneletsOrAreas_[idx];
67  }
68 
69  bool operator!=(const LaneletOrAreaPath& other) const { return !(*this == other); }
70 
71  bool operator==(const LaneletOrAreaPath& other) const { return laneletsOrAreas_ == other.laneletsOrAreas_; }
72 
73  private:
75 };
76 
84 } // namespace routing
85 } // namespace lanelet
lanelet::routing::LaneletPath::begin
const_iterator begin() const
Definition: LaneletPath.h:21
lanelet::routing::LaneletPath::end
iterator end()
Definition: LaneletPath.h:22
lanelet::ConstLaneletOrAreas
std::vector< ConstLaneletOrArea > ConstLaneletOrAreas
lanelet::routing::LaneletOrAreaPath::empty
bool empty() const
Definition: LaneletPath.h:61
lanelet
lanelet::LaneletSequence
lanelet::ConstLaneletOrArea
lanelet::routing::LaneletPath::getRemainingLane
LaneletSequence getRemainingLane(const ConstLanelet &llt) const
Definition: LaneletPath.h:40
lanelet::routing::LaneletOrAreaPath::begin
iterator begin()
Definition: LaneletPath.h:56
lanelet::routing::LaneletOrAreaPath::operator!=
bool operator!=(const LaneletOrAreaPath &other) const
Definition: LaneletPath.h:69
lanelet::routing::LaneletOrAreaPath::operator==
bool operator==(const LaneletOrAreaPath &other) const
Definition: LaneletPath.h:71
lanelet::routing::LaneletPath::operator[]
const ConstLanelet & operator[](size_t idx) const
Definition: LaneletPath.h:28
lanelet::routing::LaneletOrAreaPath::size
size_t size() const
Definition: LaneletPath.h:60
lanelet::routing::LaneletPath::iterator
ConstLanelets::iterator iterator
Definition: LaneletPath.h:15
lanelet::routing::LaneletOrAreaPath::end
iterator end()
Definition: LaneletPath.h:58
lanelet::routing::LaneletOrAreaPath::begin
const_iterator begin() const
Definition: LaneletPath.h:57
lanelet::routing::LaneletPath::front
const ConstLanelet & front() const
Definition: LaneletPath.h:26
lanelet::routing::LaneletPath::end
const_iterator end() const
Definition: LaneletPath.h:23
lanelet::routing::LaneletOrAreaPath::iterator
ConstLaneletOrAreas::iterator iterator
Definition: LaneletPath.h:51
other
LaneletAdjacency other
Definition: LaneletPath.cpp:89
LaneletOrArea.h
lanelet::routing::LaneletPath::empty
bool empty() const
Definition: LaneletPath.h:25
lanelet::BasicPolygon3d
lanelet::routing::LaneletPath::lanelets_
ConstLanelets lanelets_
Definition: LaneletPath.h:45
lanelet::routing::LaneletPath::operator==
bool operator==(const LaneletPath &other) const
Definition: LaneletPath.h:35
lanelet::routing::LaneletOrAreaPath::LaneletOrAreaPath
LaneletOrAreaPath(ConstLaneletOrAreas lltsOrArea={})
Definition: LaneletPath.h:54
lanelet::routing::LaneletOrAreaPath::operator[]
const ConstLaneletOrArea & operator[](size_t idx) const
Definition: LaneletPath.h:64
lanelet::routing::LaneletPath::LaneletPath
LaneletPath(ConstLanelets lanelets={})
Definition: LaneletPath.h:18
lanelet::routing::LaneletOrAreaPath::laneletsOrAreas_
ConstLaneletOrAreas laneletsOrAreas_
Definition: LaneletPath.h:74
lanelet::routing::LaneletOrAreaPath::end
const_iterator end() const
Definition: LaneletPath.h:59
lanelet::routing::LaneletOrAreaPath
Similar to LaneletPath, but can also contain areas.
Definition: LaneletPath.h:49
LaneletSequence.h
other
lanelet::routing::LaneletOrAreaPath::front
const ConstLaneletOrArea & front() const
Definition: LaneletPath.h:62
lanelet::routing::LaneletPath::size
size_t size() const
Definition: LaneletPath.h:24
lanelet::routing::LaneletPath::operator!=
bool operator!=(const LaneletPath &other) const
Definition: LaneletPath.h:33
lanelet::routing::LaneletPath::getRemainingLane
LaneletSequence getRemainingLane(const_iterator laneletPosition) const
Returns all succeeding lanelets from the current position that can be reached without changing lanes.
Definition: LaneletPath.cpp:326
lanelet::routing::LaneletPath::begin
iterator begin()
Definition: LaneletPath.h:20
lanelet::routing::LaneletOrAreaPath::back
const ConstLaneletOrArea & back() const
Definition: LaneletPath.h:63
lanelet::routing::LaneletOrAreaPath::const_iterator
ConstLaneletOrAreas::const_iterator const_iterator
Definition: LaneletPath.h:52
lanelet::ConstLanelet
Forward.h
lanelet::ConstLanelets
std::vector< ConstLanelet > ConstLanelets
Optional.h
lanelet::routing::LaneletPath
A lanelet path represents a set of lanelets that can be reached in order by either driving straight o...
Definition: LaneletPath.h:13
lanelet::routing::getEnclosingPolygon3d
BasicPolygon3d getEnclosingPolygon3d(const LaneletOrAreaPath &path)
Definition: LaneletPath.cpp:338
lanelet::routing::LaneletPath::back
const ConstLanelet & back() const
Definition: LaneletPath.h:27
lanelet::routing::LaneletPath::const_iterator
ConstLanelets::const_iterator const_iterator
Definition: LaneletPath.h:16


lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Sun Oct 27 2024 02:27:49