Go to the documentation of this file.
4 #include <lanelet2_core/primitives/Lanelet.h>
71 using Errors = std::vector<std::string>;
107 bool withLaneChanges =
true)
const;
122 RoutingCostId routingCostId = {},
bool withLaneChanges =
true)
const;
134 bool withLaneChanges =
true)
const;
147 bool withLaneChanges =
true)
const;
160 RoutingCostId routingCostId = {},
bool withLaneChanges =
true)
const;
174 const ConstLaneletOrArea& end,
176 bool withLaneChanges =
true)
const;
185 bool includeConflicting =
false)
const;
319 bool allowLaneChanges =
true)
const;
334 RoutingCostId routingCostId = {},
bool allowLaneChanges =
true)
const;
353 bool allowLaneChanges =
false)
const;
377 RoutingCostId routingCostId = {},
bool allowLaneChanges =
false)
const;
384 bool allowLaneChanges =
false,
RoutingCostId routingCostId = {})
const;
388 const PossiblePathsParams& params)
const;
392 RoutingCostId routingCostId = {},
bool allowLaneChanges =
false)
const;
396 bool allowLaneChanges =
false,
RoutingCostId routingCostId = {})
const;
420 bool allowLaneChanges =
true,
RoutingCostId routingCostId = {})
const;
429 bool allowLaneChanges =
true,
RoutingCostId routingCostId = {})
const;
456 bool includeConflicting =
false)
const;
475 "Use passableSubmap to obtain the lanelets and areas within the routing graph!")]]
inline LaneletMapConstPtr
495 std::unique_ptr<internal::RoutingGraphGraph>
graph_;
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.
LaneletRelations previousRelations(const ConstLanelet &lanelet, bool withLaneChanges=false) const
Returns the possible previous lanelets of this lanelet and the relation.
LaneletRelations rightRelations(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Retrieve all lanelets and relations right of a given lanelet.
std::vector< ConstLaneletOrArea > ConstLaneletOrAreas
Optional< RelationType > routingRelation(const ConstLanelet &from, const ConstLanelet &to, bool includeConflicting=false) const
Determines the relation between two lanelets.
std::shared_ptr< LaneletMap > LaneletMapPtr
Errors checkValidity(bool throwOnError=true) const
Performs some basic sanity checks. It is recommended to call this function after the routing graph ha...
std::unique_ptr< internal::RoutingGraphGraph > graph_
Documentation to be found in the cpp file.
ConstLanelets rights(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get all right (routable) lanelets of a given lanelet if they exist.
static constexpr const char ParticipantHeight[]
Defined configuration attributes.
std::vector< RoutingCostPtr > RoutingCostPtrs
static RoutingGraphUPtr build(const LaneletMap &laneletMap, const traffic_rules::TrafficRules &trafficRules, const RoutingCostPtrs &routingCosts=defaultRoutingCosts(), const Configuration &config=Configuration())
Main constructor with optional configuration.
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.
ConstLanelets besides(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Retrieve all reachable left and right lanelets.
void exportGraphML(const std::string &filename, const RelationType &edgeTypesToExclude=RelationType::None, RoutingCostId routingCostId={}) const
Export the internal graph to graphML (xml-based) file format.
Optional< ConstLanelet > adjacentRight(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get adjacent right (non-routable) lanelet of a given lanelet if it exists.
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.
std::shared_ptr< const LaneletMap > LaneletMapConstPtr
Optional< Route > getRoute(const ConstLanelet &from, const ConstLanelet &to, RoutingCostId routingCostId={}, bool withLaneChanges=true) const
Get a driving route from 'start' to 'end' lanelet.
bool includeLaneChanges
if true, returned paths will include lane changes
std::function< bool(const LaneletOrAreaVisitInformation &)> LaneletOrAreaVisitFunction
RoutingGraph()=delete
The graph can not be copied, only moved.
ConstLanelets following(const ConstLanelet &lanelet, bool withLaneChanges=false) const
Returns the lanelets that can be reached from this lanelet.
LaneletRelations followingRelations(const ConstLanelet &lanelet, bool withLaneChanges=false) const
Returns the lanelets that can be reached from this lanelet and the relation.
LaneletPaths possiblePaths(const ConstLanelet &startPoint, const PossiblePathsParams ¶ms) const
Determines possible routes from a given start lanelet that satisfy the configuration in PossiblePaths...
Optional< LaneletPath > shortestPath(const ConstLanelet &from, const ConstLanelet &to, RoutingCostId routingCostId={}, bool withLaneChanges=true) const
Retrieve a shortest path between 'start' and 'end'.
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 ...
std::vector< LaneletPath > LaneletPaths
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...
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.
boost::optional< T > Optional
RoutingCostPtrs defaultRoutingCosts()
Returns routing cost objects for initialization of routing graph with reasonable default values (for ...
Controls the behaviour of the different possible path algorithms in RoutingGraph.
ConstLanelets adjacentLefts(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get all adjacent left (non-routable) lanelets of a given lanelet if they exist.
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.
LaneletPaths possiblePathsTowards(const ConstLanelet &targetLanelet, const PossiblePathsParams ¶ms) const
Determines possible routes to reach the given lanelet which satisfy the configuration in PossiblePath...
ConstLanelets adjacentRights(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get all adjacent right (non-routable) lanelets of a given lanelet if they exist.
std::vector< std::string > Errors
For the checkValidity function.
bool includeShorterPaths
also return paths that do not reach the limits
std::unique_ptr< RoutingGraph > RoutingGraphUPtr
std::vector< LaneletRelation > LaneletRelations
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.
Optional< uint32_t > elementLimit
element limit for every path. Effect depends on includeShorterPaths
std::vector< LaneletOrAreaPath > LaneletOrAreaPaths
Optional< ConstLanelet > left(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get left (routable) lanelet of a given lanelet if it exists.
LaneletSubmapConstPtr passableSubmap() const noexcept
Returns a submap that contains all lanelets and areas within this routing graph, and nothing else....
ConstLanelets previous(const ConstLanelet &lanelet, bool withLaneChanges=false) const
Returns the possible previous lanelets of this lanelet.
LaneletMapConstPtr passableMap() const noexcept
LaneletSubmap that includes all passable lanelets and areas. This map contains all passable lanelets ...
LaneletOrAreaPaths possiblePathsIncludingAreas(const ConstLaneletOrArea &startPoint, const PossiblePathsParams ¶ms) const
Similar to RoutingGraph::possiblePaths, but also considers areas.
Optional< ConstLanelet > right(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get right (routable) lanelet of a given lanelet if it exists.
Optional< ConstLanelet > adjacentLeft(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get adjacent left (non-routable) lanelet of a given lanelet if it exists.
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...
LaneletRelations leftRelations(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Retrieve all lanelets and relations left of a given lanelet.
std::function< bool(const LaneletVisitInformation &)> LaneletVisitFunction
Main class of the routing module that holds routing information and can be queried....
ConstLaneletOrAreas conflicting(const ConstLaneletOrArea &laneletOrArea) const
Retrieve all lanelets that are conflicting with the given lanelet.
The famous route object that marks a route from A to B.
ConstLanelets reachableSetTowards(const ConstLanelet &lanelet, double maxRoutingCost, RoutingCostId routingCostId={}, bool allowLaneChanges=true) const
Retrieve a set of lanelets that can reach a given lanelet.
Optional< double > routingCostLimit
cost limit for every path. Either that or maxElements must be valid.
std::shared_ptr< const LaneletSubmap > LaneletSubmapConstPtr
ConstLanelets lefts(const ConstLanelet &lanelet, RoutingCostId routingCostId={}) const
Get all left (routable) lanelets of a given lanelet if they exist.
std::map< std::string, Attribute > Configuration
RoutingGraph & operator=(const RoutingGraph &)=delete
ConstLaneletOrAreas reachableSetIncludingAreas(const ConstLaneletOrArea &llOrAr, double maxRoutingCost, RoutingCostId routingCostId={}) const
Retrieve set of lanelet or areas that are reachable without exceeding routing cost.
std::vector< ConstLanelet > ConstLanelets
LaneletSubmapConstPtr passableLaneletSubmap_
Lanelet map of all passable lanelets.
void forEachPredecessor(const ConstLanelet &lanelet, const LaneletVisitFunction &f, bool allowLaneChanges=true, RoutingCostId routingCostId={}) const
RoutingCostId routingCostId
the routing cost module to be used for the costs
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...
lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Sun Oct 27 2024 02:27:49