Route.h
Go to the documentation of this file.
1 #pragma once
5 
6 #include <memory>
7 #include <string>
8 #include <vector>
9 
12 #include "lanelet2_routing/Types.h"
13 
14 namespace lanelet {
15 namespace routing {
16 
36 class Route {
37  public:
38  using Errors = std::vector<std::string>;
39  Route();
40  Route(const Route& other) = delete;
41  Route& operator=(const Route& other) = delete;
42  Route& operator=(Route&& other) noexcept;
43  Route(Route&& other) noexcept;
44  ~Route() noexcept;
45 
47  Route(LaneletPath shortestPath, std::unique_ptr<internal::RouteGraph> graph,
49 
51  inline const LaneletPath& shortestPath() const noexcept { return shortestPath_; }
52 
60 
68 
73 
75  double length2d() const;
76 
79  size_t numLanes() const;
80 
86  inline LaneletSubmapConstPtr laneletSubmap() const noexcept { return laneletSubmap_; }
87 
97  [[deprecated("Use laneletSubmap() to obtain a view on the elements within this route")]] inline LaneletMapConstPtr
98  laneletMap() const noexcept {
99  return laneletSubmap_->laneletMap();
100  }
101 
107 
111  size_t size() const;
112 
119 
122 
129 
132 
140 
148 
156 
164 
168  void forEachSuccessor(const ConstLanelet& lanelet, const LaneletVisitFunction& f) const;
169 
171  void forEachPredecessor(const ConstLanelet& lanelet, const LaneletVisitFunction& f) const;
172 
178 
186 
191 
193  bool contains(const ConstLanelet& lanelet) const;
194 
199  Errors checkValidity(bool throwOnError = false) const;
200 
201  private:
202  std::unique_ptr<internal::RouteGraph> graph_;
205 };
206 } // namespace routing
207 } // namespace lanelet
lanelet::routing::Route::following
ConstLanelets following(const ConstLanelet &lanelet) const
Similar to followingRelations but directly provides the following lanelets within the Route.
Definition: Route.cpp:235
lanelet::routing::Route::allConflictingInMap
ConstLaneletOrAreas allConflictingInMap() const
Provides all lanelets in the map that conflict with any lanelet in the route.
Definition: Route.cpp:344
lanelet::routing::Route::conflictingInRoute
ConstLanelets conflictingInRoute(const ConstLanelet &lanelet) const
Information about conflicting lanelets of a lanelet within the route.
Definition: Route.cpp:328
lanelet::ConstLaneletOrAreas
std::vector< ConstLaneletOrArea > ConstLaneletOrAreas
lanelet::routing::Route::forEachSuccessor
void forEachSuccessor(const ConstLanelet &lanelet, const LaneletVisitFunction &f) const
Definition: Route.cpp:301
lanelet::routing::Route::previous
ConstLanelets previous(const ConstLanelet &lanelet) const
Similar to followingRelations but directly provides the following lanelets within the Route.
Definition: Route.cpp:251
LaneletMap.h
lanelet::LaneletMapPtr
std::shared_ptr< LaneletMap > LaneletMapPtr
lanelet
lanelet::routing::Route::followingRelations
LaneletRelations followingRelations(const ConstLanelet &lanelet) const
Provides information of the following lanelets within the Route.
Definition: Route.cpp:227
Types.h
lanelet::routing::Route::leftRelations
LaneletRelations leftRelations(const ConstLanelet &lanelet) const
Provides information of the all lanelets left of a given lanelet within the Route.
Definition: Route.cpp:267
lanelet::LaneletSequence
lanelet::routing::Route::previousRelations
LaneletRelations previousRelations(const ConstLanelet &lanelet) const
Provides information of the previous lanelets within the Route.
Definition: Route.cpp:243
lanelet::routing::Route::laneletSubmap
LaneletSubmapConstPtr laneletSubmap() const noexcept
A LaneletSubmap with all lanelets that are part of the route.
Definition: Route.h:86
lanelet::routing::Route::conflictingInMap
ConstLaneletOrAreas conflictingInMap(const ConstLanelet &lanelet) const
Information about conflicting lanelets of a lanelet within all passable lanelets in the laneletMap.
Definition: Route.cpp:336
lanelet::routing::Route::numLanes
size_t numLanes() const
Returns the number of individual lanes.
Definition: Route.cpp:193
lanelet::routing::Route::remainingLane
LaneletSequence remainingLane(const ConstLanelet &ll) const
Returns that remaining lane a Lanelet belongs to.
Definition: Route.cpp:180
lanelet::LaneletMapConstPtr
std::shared_ptr< const LaneletMap > LaneletMapConstPtr
lanelet::routing::Route::forEachPredecessor
void forEachPredecessor(const ConstLanelet &lanelet, const LaneletVisitFunction &f) const
Similar to forEachSuccessor but goes backwards in the routing graph instead of forwards.
Definition: Route.cpp:314
lanelet::routing::Route::shortestPath
const LaneletPath & shortestPath() const noexcept
Returns the shortest path that was the base of this route.
Definition: Route.h:51
Forward.h
lanelet::Optional
boost::optional< T > Optional
lanelet::routing::Route::rightRelations
LaneletRelations rightRelations(const ConstLanelet &lanelet) const
Provides information of the all lanelets right of a given lanelet within the Route.
Definition: Route.cpp:288
lanelet::routing::Route::getDebugLaneletMap
LaneletMapPtr getDebugLaneletMap() const
Get a laneletMap that represents the Lanelets of the Route and their relationship.
Definition: Route.cpp:202
lanelet::routing::Route::size
size_t size() const
Number of Lanelets in the route.
Definition: Route.cpp:225
lanelet::routing::Route::rightRelation
Optional< LaneletRelation > rightRelation(const ConstLanelet &lanelet) const
Provides information of the lanelet right of a given lanelet within the Route.
Definition: Route.cpp:280
lanelet::routing::Route::shortestPath_
LaneletPath shortestPath_
The underlying shortest path used to create the route.
Definition: Route.h:203
lanelet::routing::Route::~Route
~Route() noexcept
LaneletPath.h
lanelet::routing::LaneletRelations
std::vector< LaneletRelation > LaneletRelations
Definition: Forward.h:34
lanelet::routing::Route::checkValidity
Errors checkValidity(bool throwOnError=false) const
Perform some sanity checks on the route.
Definition: Route.cpp:363
lanelet::routing::Route::contains
bool contains(const ConstLanelet &lanelet) const
Checks if a specific lanelet is part of the route.
Definition: Route.cpp:352
lanelet::routing::Route::Errors
std::vector< std::string > Errors
Definition: Route.h:38
lanelet::routing::Route::length2d
double length2d() const
Get the 2d length of the shortest path of this route.
Definition: Route.cpp:188
lanelet::routing::Route::operator=
Route & operator=(const Route &other)=delete
lanelet::routing::Route::graph_
std::unique_ptr< internal::RouteGraph > graph_
The internal graph.
Definition: Route.h:202
LaneletSequence.h
lanelet::routing::Route::laneletSubmap_
LaneletSubmapConstPtr laneletSubmap_
LaneletSubmap with all lanelets that are part of the route.
Definition: Route.h:204
other
lanelet::routing::Route::remainingShortestPath
LaneletPath remainingShortestPath(const ConstLanelet &ll) const
Obtains the remaining shortest path to the destination. If the route is circular, the result will alw...
Definition: Route.cpp:140
lanelet::routing::Route::fullLane
LaneletSequence fullLane(const ConstLanelet &ll) const
Returns the complete lane a Lanelet belongs to. Circular lanes will always have 'll' as the first ele...
Definition: Route.cpp:154
lanelet::routing::Route::Route
Route()
std
lanelet::routing::LaneletVisitFunction
std::function< bool(const LaneletVisitInformation &)> LaneletVisitFunction
Definition: Types.h:30
lanelet::routing::Route
The famous route object that marks a route from A to B.
Definition: Route.h:36
lanelet::routing::Route::leftRelation
Optional< LaneletRelation > leftRelation(const ConstLanelet &lanelet) const
Provides information of the lanelet left of a given lanelet within the Route.
Definition: Route.cpp:259
lanelet::LaneletSubmapConstPtr
std::shared_ptr< const LaneletSubmap > LaneletSubmapConstPtr
lanelet::routing::Route::laneletMap
LaneletMapConstPtr laneletMap() const noexcept
A LaneletMap with all lanelets that are part of the route and those referenced by regelems.
Definition: Route.h:98
lanelet::ConstLanelet
Forward.h
ll
LaneletAdjacency ll
Definition: LaneletPath.cpp:88
lanelet::ConstLanelets
std::vector< ConstLanelet > ConstLanelets
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


lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Thu Mar 6 2025 03:26:10