RoutingGraph.h
Go to the documentation of this file.
1 #pragma once
4 #include <lanelet2_core/primitives/Lanelet.h>
7 
8 #include <map>
9 
13 #include "lanelet2_routing/Types.h"
14 
15 namespace lanelet {
16 namespace routing {
17 
54  bool includeLaneChanges{false};
55  bool includeShorterPaths{false};
56 };
57 
69 class RoutingGraph {
70  public:
71  using Errors = std::vector<std::string>;
72  using Configuration = std::map<std::string, Attribute>;
73  static constexpr const char ParticipantHeight[] = "participant_height";
75 
81  static RoutingGraphUPtr build(const LaneletMap& laneletMap, const traffic_rules::TrafficRules& trafficRules,
82  const RoutingCostPtrs& routingCosts = defaultRoutingCosts(),
83  const Configuration& config = Configuration());
84 
86  static RoutingGraphUPtr build(const LaneletSubmap& laneletSubmap, const traffic_rules::TrafficRules& trafficRules,
87  const RoutingCostPtrs& routingCosts = defaultRoutingCosts(),
88  const Configuration& config = Configuration());
89 
91  RoutingGraph() = delete;
92  RoutingGraph(const RoutingGraph&) = delete;
93  RoutingGraph& operator=(const RoutingGraph&) = delete;
94  RoutingGraph(RoutingGraph&& /*other*/) noexcept;
95  RoutingGraph& operator=(RoutingGraph&& /*other*/) noexcept;
96  ~RoutingGraph();
97 
106  Optional<Route> getRoute(const ConstLanelet& from, const ConstLanelet& to, RoutingCostId routingCostId = {},
107  bool withLaneChanges = true) const;
108 
121  Optional<Route> getRouteVia(const ConstLanelet& from, const ConstLanelets& via, const ConstLanelet& to,
122  RoutingCostId routingCostId = {}, bool withLaneChanges = true) const;
123 
133  Optional<LaneletPath> shortestPath(const ConstLanelet& from, const ConstLanelet& to, RoutingCostId routingCostId = {},
134  bool withLaneChanges = true) const;
135 
145  Optional<LaneletOrAreaPath> shortestPathIncludingAreas(const ConstLaneletOrArea& from, const ConstLaneletOrArea& to,
146  RoutingCostId routingCostId = {},
147  bool withLaneChanges = true) const;
148 
159  Optional<LaneletPath> shortestPathVia(const ConstLanelet& start, const ConstLanelets& via, const ConstLanelet& end,
160  RoutingCostId routingCostId = {}, bool withLaneChanges = true) const;
161 
172  Optional<LaneletOrAreaPath> shortestPathIncludingAreasVia(const ConstLaneletOrArea& start,
173  const ConstLaneletOrAreas& via,
174  const ConstLaneletOrArea& end,
175  RoutingCostId routingCostId = {},
176  bool withLaneChanges = true) const;
177 
184  Optional<RelationType> routingRelation(const ConstLanelet& from, const ConstLanelet& to,
185  bool includeConflicting = false) const;
186 
192  ConstLanelets following(const ConstLanelet& lanelet, bool withLaneChanges = false) const;
193 
199  LaneletRelations followingRelations(const ConstLanelet& lanelet, bool withLaneChanges = false) const;
200 
206  ConstLanelets previous(const ConstLanelet& lanelet, bool withLaneChanges = false) const;
207 
213  LaneletRelations previousRelations(const ConstLanelet& lanelet, bool withLaneChanges = false) const;
214 
220  ConstLanelets besides(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
221 
228  Optional<ConstLanelet> left(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
229 
236  Optional<ConstLanelet> adjacentLeft(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
237 
244  Optional<ConstLanelet> right(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
245 
252  Optional<ConstLanelet> adjacentRight(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
253 
260  ConstLanelets lefts(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
261 
268  ConstLanelets adjacentLefts(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
269 
276  LaneletRelations leftRelations(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
277 
284  ConstLanelets rights(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
285 
292  ConstLanelets adjacentRights(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
293 
300  LaneletRelations rightRelations(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
301 
308  ConstLaneletOrAreas conflicting(const ConstLaneletOrArea& laneletOrArea) const;
309 
318  ConstLanelets reachableSet(const ConstLanelet& lanelet, double maxRoutingCost, RoutingCostId routingCostId = {},
319  bool allowLaneChanges = true) const;
320 
322  ConstLaneletOrAreas reachableSetIncludingAreas(const ConstLaneletOrArea& llOrAr, double maxRoutingCost,
323  RoutingCostId routingCostId = {}) const;
324 
333  ConstLanelets reachableSetTowards(const ConstLanelet& lanelet, double maxRoutingCost,
334  RoutingCostId routingCostId = {}, bool allowLaneChanges = true) const;
335 
345  LaneletPaths possiblePaths(const ConstLanelet& startPoint, const PossiblePathsParams& params) const;
346 
352  LaneletPaths possiblePaths(const ConstLanelet& startPoint, double minRoutingCost, RoutingCostId routingCostId = {},
353  bool allowLaneChanges = false) const;
354 
360  LaneletPaths possiblePaths(const ConstLanelet& startPoint, uint32_t minLanelets, bool allowLaneChanges = false,
361  RoutingCostId routingCostId = {}) const;
362 
370  LaneletPaths possiblePathsTowards(const ConstLanelet& targetLanelet, const PossiblePathsParams& params) const;
371 
376  LaneletPaths possiblePathsTowards(const ConstLanelet& targetLanelet, double minRoutingCost,
377  RoutingCostId routingCostId = {}, bool allowLaneChanges = false) const;
378 
383  LaneletPaths possiblePathsTowards(const ConstLanelet& targetLanelet, uint32_t minLanelets,
384  bool allowLaneChanges = false, RoutingCostId routingCostId = {}) const;
385 
387  LaneletOrAreaPaths possiblePathsIncludingAreas(const ConstLaneletOrArea& startPoint,
388  const PossiblePathsParams& params) const;
389 
391  LaneletOrAreaPaths possiblePathsIncludingAreas(const ConstLaneletOrArea& startPoint, double minRoutingCost,
392  RoutingCostId routingCostId = {}, bool allowLaneChanges = false) const;
393 
395  LaneletOrAreaPaths possiblePathsIncludingAreas(const ConstLaneletOrArea& startPoint, uint32_t minElements,
396  bool allowLaneChanges = false, RoutingCostId routingCostId = {}) const;
397 
415  void forEachSuccessor(const ConstLanelet& lanelet, const LaneletVisitFunction& f, bool allowLaneChanges = true,
416  RoutingCostId routingCostId = {}) const;
417 
419  void forEachSuccessorIncludingAreas(const ConstLaneletOrArea& lanelet, const LaneletOrAreaVisitFunction& f,
420  bool allowLaneChanges = true, RoutingCostId routingCostId = {}) const;
421 
424  void forEachPredecessor(const ConstLanelet& lanelet, const LaneletVisitFunction& f, bool allowLaneChanges = true,
425  RoutingCostId routingCostId = {}) const;
426 
428  void forEachPredecessorIncludingAreas(const ConstLaneletOrArea& lanelet, const LaneletOrAreaVisitFunction& f,
429  bool allowLaneChanges = true, RoutingCostId routingCostId = {}) const;
430 
436  void exportGraphML(const std::string& filename, const RelationType& edgeTypesToExclude = RelationType::None,
437  RoutingCostId routingCostId = {}) const;
438 
444  void exportGraphViz(const std::string& filename, const RelationType& edgeTypesToExclude = RelationType::None,
445  RoutingCostId routingCostId = {}) const;
446 
455  LaneletMapPtr getDebugLaneletMap(RoutingCostId routingCostId = {}, bool includeAdjacent = false,
456  bool includeConflicting = false) const;
457 
463  inline LaneletSubmapConstPtr passableSubmap() const noexcept { return passableLaneletSubmap_; }
464 
474  [[deprecated(
475  "Use passableSubmap to obtain the lanelets and areas within the routing graph!")]] inline LaneletMapConstPtr
476  passableMap() const noexcept {
477  return passableSubmap()->laneletMap();
478  }
479 
486  Errors checkValidity(bool throwOnError = true) const;
487 
491  RoutingGraph(std::unique_ptr<internal::RoutingGraphGraph>&& graph, lanelet::LaneletSubmapConstPtr&& passableMap);
492 
493  private:
495  std::unique_ptr<internal::RoutingGraphGraph> graph_;
497 };
498 
499 } // namespace routing
500 } // namespace lanelet
lanelet::routing::RoutingGraph::shortestPathIncludingAreas
Optional< LaneletOrAreaPath > shortestPathIncludingAreas(const ConstLaneletOrArea &from, const ConstLaneletOrArea &to, RoutingCostId routingCostId={}, bool withLaneChanges=true) const
Retrieve a shortest path between 'start' and 'end' that may contain Areas.
Definition: RoutingGraph.cpp:409
lanelet::routing::RoutingGraph::previousRelations
LaneletRelations previousRelations(const ConstLanelet &lanelet, bool withLaneChanges=false) const
Returns the possible previous lanelets of this lanelet and the relation.
Definition: RoutingGraph.cpp:465
lanelet::routing::RoutingGraph::rightRelations
LaneletRelations rightRelations(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Retrieve all lanelets and relations right of a given lanelet.
Definition: RoutingGraph.cpp:550
ConstLaneletOrAreas
std::vector< ConstLaneletOrArea > ConstLaneletOrAreas
lanelet::routing::RoutingGraph::routingRelation
Optional< RelationType > routingRelation(const ConstLanelet &from, const ConstLanelet &to, bool includeConflicting=false) const
Determines the relation between two lanelets.
Definition: RoutingGraph.cpp:436
LaneletMap.h
LaneletMapPtr
std::shared_ptr< LaneletMap > LaneletMapPtr
lanelet
lanelet::routing::RoutingGraph::checkValidity
Errors checkValidity(bool throwOnError=true) const
Performs some basic sanity checks. It is recommended to call this function after the routing graph ha...
Definition: RoutingGraph.cpp:855
lanelet::routing::RoutingGraph::graph_
std::unique_ptr< internal::RoutingGraphGraph > graph_
Documentation to be found in the cpp file.
Definition: RoutingGraph.h:495
lanelet::routing::RoutingGraph::rights
ConstLanelets rights(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get all right (routable) lanelets of a given lanelet if they exist.
Definition: RoutingGraph.cpp:542
Types.h
lanelet::routing::RoutingGraph::ParticipantHeight
static constexpr const char ParticipantHeight[]
Defined configuration attributes.
Definition: RoutingGraph.h:74
lanelet::traffic_rules::TrafficRules
lanelet::routing::RoutingCostPtrs
std::vector< RoutingCostPtr > RoutingCostPtrs
Definition: Forward.h:43
lanelet::routing::RoutingGraph::build
static RoutingGraphUPtr build(const LaneletMap &laneletMap, const traffic_rules::TrafficRules &trafficRules, const RoutingCostPtrs &routingCosts=defaultRoutingCosts(), const Configuration &config=Configuration())
Main constructor with optional configuration.
Definition: RoutingGraph.cpp:375
lanelet::routing::RoutingGraph::forEachSuccessor
void forEachSuccessor(const ConstLanelet &lanelet, const LaneletVisitFunction &f, bool allowLaneChanges=true, RoutingCostId routingCostId={}) const
Calls a function on every successor of lanelet, optionally including lane changes.
Definition: RoutingGraph.cpp:671
lanelet::routing::RoutingGraph::besides
ConstLanelets besides(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Retrieve all reachable left and right lanelets.
Definition: RoutingGraph.cpp:480
lanelet::routing::RoutingGraph::exportGraphML
void exportGraphML(const std::string &filename, const RelationType &edgeTypesToExclude=RelationType::None, RoutingCostId routingCostId={}) const
Export the internal graph to graphML (xml-based) file format.
Definition: RoutingGraph.cpp:736
lanelet::routing::RoutingGraph::adjacentRight
Optional< ConstLanelet > adjacentRight(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get adjacent right (non-routable) lanelet of a given lanelet if it exists.
Definition: RoutingGraph.cpp:508
lanelet::routing::RelationType
RelationType
Definition: Forward.h:56
lanelet::routing::RoutingGraph::forEachPredecessorIncludingAreas
void forEachPredecessorIncludingAreas(const ConstLaneletOrArea &lanelet, const LaneletOrAreaVisitFunction &f, bool allowLaneChanges=true, RoutingCostId routingCostId={}) const
Similar to RoutingGraph::forEachPredecessor but also includes areas into the search.
Definition: RoutingGraph.cpp:718
lanelet::LaneletMapConstPtr
std::shared_ptr< const LaneletMap > LaneletMapConstPtr
lanelet::routing::RoutingGraph::getRoute
Optional< Route > getRoute(const ConstLanelet &from, const ConstLanelet &to, RoutingCostId routingCostId={}, bool withLaneChanges=true) const
Get a driving route from 'start' to 'end' lanelet.
Definition: RoutingGraph.cpp:386
lanelet::routing::PossiblePathsParams::includeLaneChanges
bool includeLaneChanges
if true, returned paths will include lane changes
Definition: RoutingGraph.h:54
lanelet::routing::LaneletOrAreaVisitFunction
std::function< bool(const LaneletOrAreaVisitInformation &)> LaneletOrAreaVisitFunction
Definition: Types.h:31
lanelet::routing::RoutingGraph::RoutingGraph
RoutingGraph()=delete
The graph can not be copied, only moved.
Forward.h
lanelet::routing::RoutingGraph::following
ConstLanelets following(const ConstLanelet &lanelet, bool withLaneChanges=false) const
Returns the lanelets that can be reached from this lanelet.
Definition: RoutingGraph.cpp:446
lanelet::routing::RoutingGraph::followingRelations
LaneletRelations followingRelations(const ConstLanelet &lanelet, bool withLaneChanges=false) const
Returns the lanelets that can be reached from this lanelet and the relation.
Definition: RoutingGraph.cpp:451
lanelet::routing::RoutingGraph::possiblePaths
LaneletPaths possiblePaths(const ConstLanelet &startPoint, const PossiblePathsParams &params) const
Determines possible routes from a given start lanelet that satisfy the configuration in PossiblePaths...
Definition: RoutingGraph.cpp:604
lanelet::routing::RoutingGraph::shortestPath
Optional< LaneletPath > shortestPath(const ConstLanelet &from, const ConstLanelet &to, RoutingCostId routingCostId={}, bool withLaneChanges=true) const
Retrieve a shortest path between 'start' and 'end'.
Definition: RoutingGraph.cpp:404
lanelet::routing::RoutingGraph::getDebugLaneletMap
LaneletMapPtr getDebugLaneletMap(RoutingCostId routingCostId={}, bool includeAdjacent=false, bool includeConflicting=false) const
An abstract lanelet map holding the information of the routing graph. A good way to view the routing ...
Definition: RoutingGraph.cpp:844
lanelet::routing::LaneletPaths
std::vector< LaneletPath > LaneletPaths
Definition: Forward.h:47
lanelet::routing::RoutingGraph::shortestPathIncludingAreasVia
Optional< LaneletOrAreaPath > shortestPathIncludingAreasVia(const ConstLaneletOrArea &start, const ConstLaneletOrAreas &via, const ConstLaneletOrArea &end, RoutingCostId routingCostId={}, bool withLaneChanges=true) const
Retrieve a shortest path between 'start' and 'end' using intermediate points. Will find a shortest pa...
Definition: RoutingGraph.cpp:425
lanelet::LaneletMap
lanelet::routing::RoutingGraph::getRouteVia
Optional< Route > getRouteVia(const ConstLanelet &from, const ConstLanelets &via, const ConstLanelet &to, RoutingCostId routingCostId={}, bool withLaneChanges=true) const
Get a driving route from 'start' to 'end' lanelets while going via other lanelets.
Definition: RoutingGraph.cpp:395
lanelet::Optional
boost::optional< T > Optional
lanelet::routing::defaultRoutingCosts
RoutingCostPtrs defaultRoutingCosts()
Returns routing cost objects for initialization of routing graph with reasonable default values (for ...
Definition: RoutingCost.h:122
lanelet::routing::PossiblePathsParams
Controls the behaviour of the different possible path algorithms in RoutingGraph.
Definition: RoutingGraph.h:50
LaneletOrArea.h
lanelet::routing::RoutingGraph::adjacentLefts
ConstLanelets adjacentLefts(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get all adjacent left (non-routable) lanelets of a given lanelet if they exist.
Definition: RoutingGraph.cpp:518
lanelet::routing::RoutingGraph::forEachSuccessorIncludingAreas
void forEachSuccessorIncludingAreas(const ConstLaneletOrArea &lanelet, const LaneletOrAreaVisitFunction &f, bool allowLaneChanges=true, RoutingCostId routingCostId={}) const
Similar to RoutingGraph::forEachSuccessor but also includes areas into the search.
Definition: RoutingGraph.cpp:685
lanelet::routing::RoutingGraph::possiblePathsTowards
LaneletPaths possiblePathsTowards(const ConstLanelet &targetLanelet, const PossiblePathsParams &params) const
Determines possible routes to reach the given lanelet which satisfy the configuration in PossiblePath...
Definition: RoutingGraph.cpp:624
lanelet::routing::RoutingGraph::adjacentRights
ConstLanelets adjacentRights(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get all adjacent right (non-routable) lanelets of a given lanelet if they exist.
Definition: RoutingGraph.cpp:546
lanelet::routing::RoutingGraph::Errors
std::vector< std::string > Errors
For the checkValidity function.
Definition: RoutingGraph.h:71
lanelet::routing::PossiblePathsParams::includeShorterPaths
bool includeShorterPaths
also return paths that do not reach the limits
Definition: RoutingGraph.h:55
lanelet::routing::RoutingGraphUPtr
std::unique_ptr< RoutingGraph > RoutingGraphUPtr
Definition: Forward.h:26
LaneletPath.h
lanelet::routing::LaneletRelations
std::vector< LaneletRelation > LaneletRelations
Definition: Forward.h:34
lanelet::routing::RoutingGraph::reachableSet
ConstLanelets reachableSet(const ConstLanelet &lanelet, double maxRoutingCost, RoutingCostId routingCostId={}, bool allowLaneChanges=true) const
Retrieve a set of lanelets that can be reached from a given lanelet.
Definition: RoutingGraph.cpp:574
lanelet::routing::PossiblePathsParams::elementLimit
Optional< uint32_t > elementLimit
element limit for every path. Effect depends on includeShorterPaths
Definition: RoutingGraph.h:52
lanelet::routing::RoutingCostId
uint16_t RoutingCostId
Definition: Forward.h:44
lanelet::routing::LaneletOrAreaPaths
std::vector< LaneletOrAreaPath > LaneletOrAreaPaths
Definition: Forward.h:49
lanelet::routing::RoutingGraph::left
Optional< ConstLanelet > left(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get left (routable) lanelet of a given lanelet if it exists.
Definition: RoutingGraph.cpp:492
lanelet::routing::RoutingGraph::passableSubmap
LaneletSubmapConstPtr passableSubmap() const noexcept
Returns a submap that contains all lanelets and areas within this routing graph, and nothing else....
Definition: RoutingGraph.h:463
lanelet::routing::RoutingGraph::previous
ConstLanelets previous(const ConstLanelet &lanelet, bool withLaneChanges=false) const
Returns the possible previous lanelets of this lanelet.
Definition: RoutingGraph.cpp:460
lanelet::routing::RoutingGraph::passableMap
LaneletMapConstPtr passableMap() const noexcept
LaneletSubmap that includes all passable lanelets and areas. This map contains all passable lanelets ...
Definition: RoutingGraph.h:476
lanelet::routing::RelationType::None
@ None
No relation.
lanelet::routing::RoutingGraph::possiblePathsIncludingAreas
LaneletOrAreaPaths possiblePathsIncludingAreas(const ConstLaneletOrArea &startPoint, const PossiblePathsParams &params) const
Similar to RoutingGraph::possiblePaths, but also considers areas.
Definition: RoutingGraph.cpp:647
lanelet::routing::RoutingGraph::right
Optional< ConstLanelet > right(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get right (routable) lanelet of a given lanelet if it exists.
Definition: RoutingGraph.cpp:503
lanelet::routing::RoutingGraph::adjacentLeft
Optional< ConstLanelet > adjacentLeft(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get adjacent left (non-routable) lanelet of a given lanelet if it exists.
Definition: RoutingGraph.cpp:497
lanelet::routing::RoutingGraph::exportGraphViz
void exportGraphViz(const std::string &filename, const RelationType &edgeTypesToExclude=RelationType::None, RoutingCostId routingCostId={}) const
Export the internal graph to graphViz (DOT) file format. This format includes coloring of the edges i...
Definition: RoutingGraph.cpp:748
lanelet::routing::RoutingGraph::leftRelations
LaneletRelations leftRelations(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Retrieve all lanelets and relations left of a given lanelet.
Definition: RoutingGraph.cpp:522
lanelet::routing::LaneletVisitFunction
std::function< bool(const LaneletVisitInformation &)> LaneletVisitFunction
Definition: Types.h:30
lanelet::LaneletSubmap
lanelet::routing::RoutingGraph
Main class of the routing module that holds routing information and can be queried....
Definition: RoutingGraph.h:69
lanelet::routing::RoutingGraph::conflicting
ConstLaneletOrAreas conflicting(const ConstLaneletOrArea &laneletOrArea) const
Retrieve all lanelets that are conflicting with the given lanelet.
Definition: RoutingGraph.cpp:570
lanelet::routing::Route
The famous route object that marks a route from A to B.
Definition: Route.h:36
lanelet::routing::RoutingGraph::reachableSetTowards
ConstLanelets reachableSetTowards(const ConstLanelet &lanelet, double maxRoutingCost, RoutingCostId routingCostId={}, bool allowLaneChanges=true) const
Retrieve a set of lanelets that can reach a given lanelet.
Definition: RoutingGraph.cpp:594
lanelet::routing::PossiblePathsParams::routingCostLimit
Optional< double > routingCostLimit
cost limit for every path. Either that or maxElements must be valid.
Definition: RoutingGraph.h:51
lanelet::LaneletSubmapConstPtr
std::shared_ptr< const LaneletSubmap > LaneletSubmapConstPtr
lanelet::ConstLanelet
lanelet::routing::RoutingGraph::lefts
ConstLanelets lefts(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get all left (routable) lanelets of a given lanelet if they exist.
Definition: RoutingGraph.cpp:514
RoutingCost.h
lanelet::routing::RoutingGraph::Configuration
std::map< std::string, Attribute > Configuration
Definition: RoutingGraph.h:72
Forward.h
lanelet::routing::RoutingGraph::operator=
RoutingGraph & operator=(const RoutingGraph &)=delete
lanelet::routing::RoutingGraph::reachableSetIncludingAreas
ConstLaneletOrAreas reachableSetIncludingAreas(const ConstLaneletOrArea &llOrAr, double maxRoutingCost, RoutingCostId routingCostId={}) const
Retrieve set of lanelet or areas that are reachable without exceeding routing cost.
Definition: RoutingGraph.cpp:584
lanelet::ConstLanelets
std::vector< ConstLanelet > ConstLanelets
lanelet::routing::RoutingGraph::passableLaneletSubmap_
LaneletSubmapConstPtr passableLaneletSubmap_
Lanelet map of all passable lanelets.
Definition: RoutingGraph.h:496
lanelet::routing::RoutingGraph::forEachPredecessor
void forEachPredecessor(const ConstLanelet &lanelet, const LaneletVisitFunction &f, bool allowLaneChanges=true, RoutingCostId routingCostId={}) const
Definition: RoutingGraph.cpp:702
lanelet::routing::PossiblePathsParams::routingCostId
RoutingCostId routingCostId
the routing cost module to be used for the costs
Definition: RoutingGraph.h:53
Optional.h
lanelet::routing::RoutingGraph::shortestPathVia
Optional< LaneletPath > shortestPathVia(const ConstLanelet &start, const ConstLanelets &via, const ConstLanelet &end, RoutingCostId routingCostId={}, bool withLaneChanges=true) const
Retrieve a shortest path between 'start' and 'end' using intermediate points. Will find a shortest pa...
Definition: RoutingGraph.cpp:417


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