Class Route
Defined in File Route.h
Class Documentation
-
class Route
The famous route object that marks a route from A to B.
A Route includes all Lanelets that are adjacent to the Lanelets that represent the shortest path and lead towards the goal. Any Lanelet that is close, but not directly attached, e.g. the other way around a channeling island is not included. Any adjacent Lanelet which does not lead to the goal is also not included.
A Route does not have any relations to Lanelets that are not part of the Route (the only exception are conflicting Lanelets)
A Route is usually obtained from a RoutingGraph via “RoutingGraph::getRoute”.
A Route is self-sustained in terms of that there is no relation to the RoutingGraph anymore
RelationTypes within a Route refer to relations of the Elements that are part of the Route. A lanelet can have fewer successors than in the routing graph if some are not part of the route
The route is divided into lanes with individual Ids. The exact value of the id for a lane is random. Ids are not continuous.
A new lane begins at every lanelet that has not exactly one predecessor or that is part of a diverging situation. Simple routes often just have one lane leading across multiple intersections.
It is recommended to check a couple of basic things with the “checkValidity” function once the Route is created
Routes can also be circular (e.g. if start and end lanelet are the same). The “last” lanelet of the route will then have the first lanelet of the route as successor.
Public Types
-
using Errors = std::vector<std::string>
Public Functions
-
Route()
-
~Route() noexcept
-
Route(LaneletPath shortestPath, std::unique_ptr<internal::RouteGraph> graph, LaneletSubmapConstPtr laneletSubmap) noexcept
Constructs a route. Not supposed to be called directly. Use RoutingGraph to obtain routes.
-
inline const LaneletPath &shortestPath() const noexcept
Returns the shortest path that was the base of this route.
-
LaneletPath remainingShortestPath(const ConstLanelet &ll) const
Obtains the remaining shortest path to the destination. If the route is circular, the result will always have the same length and end before the lanelet passed as input argument.
- Parameters:
ll – a lanelet on the shortest path
- Returns:
shortest path where lanelet is the first element. Nothing if the lanelet is not on the shortest path.
-
LaneletSequence fullLane(const ConstLanelet &ll) const
Returns the complete lane a Lanelet belongs to. Circular lanes will always have ‘ll’ as the first element.
If
-
LaneletSequence remainingLane(const ConstLanelet &ll) const
Returns that remaining lane a Lanelet belongs to.
-
double length2d() const
Get the 2d length of the shortest path of this route.
-
size_t numLanes() const
Returns the number of individual lanes.
- Returns:
Number of lanes
-
inline LaneletSubmapConstPtr laneletSubmap() const noexcept
A LaneletSubmap with all lanelets that are part of the route.
Can be used to do spatial lookups like ‘which Lanelets of the route are close to my position’. It does not contain anything beyond that, no points, linestrings, etc.
-
inline LaneletMapConstPtr laneletMap() const noexcept
A LaneletMap with all lanelets that are part of the route and those referenced by regelems.
Due to this behaviour that the map can contain lanelets that are not on the route, this function is deprecated. laneletSubmap() only returns lanelets on the map. To get the old behaviour use laneletSubmap()->laneletMap().
- Returns:
A laneletMap with all lanelets of the route, excluding regulatory elements. Can be used to do spatial lookups like ‘which Lanelets of the route are close to my position’. Note that not all lanelets in the map automatically belong to the route. They can also belong to one of the regulatory elements of the lanelet. Use Route::contains for that.
-
LaneletMapPtr getDebugLaneletMap() const
Get a laneletMap that represents the Lanelets of the Route and their relationship.
- Returns:
The laneletMap Note that this laneletMap won’t contain any Lanelets but rather just points and line string that represent the lanelets and their relationship.
-
size_t size() const
Number of Lanelets in the route.
- Returns:
Number of lanelets.
-
LaneletRelations followingRelations(const ConstLanelet &lanelet) const
Provides information of the following lanelets within the Route.
- Parameters:
lanelet – Lanelet to get information about.
- Returns:
Relations to following lanelets in the route. Nothing if ‘lanelet’ is not part of the route. The relation will always be “succesor”
-
ConstLanelets following(const ConstLanelet &lanelet) const
Similar to followingRelations but directly provides the following lanelets within the Route.
-
LaneletRelations previousRelations(const ConstLanelet &lanelet) const
Provides information of the previous lanelets within the Route.
- Parameters:
lanelet – Lanelet to get information about.
- Returns:
Relations to previous lanelets in the route. Nothing if ‘lanelet’ is not part of the route. The type will always be “successor”.
-
ConstLanelets previous(const ConstLanelet &lanelet) const
Similar to followingRelations but directly provides the following lanelets within the Route.
-
Optional<LaneletRelation> leftRelation(const ConstLanelet &lanelet) const
Provides information of the lanelet left of a given lanelet within the Route.
Note
The returned lanelet can include a lanelet that can be switched or not-switched to. The relation will be “left” and “adjacent_left” accordingly.
- Parameters:
lanelet – Lanelet to get information about.
- Returns:
Relation to lanelet left of the input lanelet in the route. Nothing if ‘lanelet’ is not part of the route.
-
LaneletRelations leftRelations(const ConstLanelet &lanelet) const
Provides information of the all lanelets left of a given lanelet within the Route.
Note
The returned lanelets include lanelets that can be switched or not-switched to. The relations will be “left” and “adjacent_left” accordingly.
- Parameters:
lanelet – Lanelet to get information about.
- Returns:
Relations to lanelets left of the input lanelet in the route. Nothing if ‘lanelet’ is not part of the route.
-
Optional<LaneletRelation> rightRelation(const ConstLanelet &lanelet) const
Provides information of the lanelet right of a given lanelet within the Route.
Note
The returned lanelet can include a lanelet that can be switched or not-switched to. The relation will be “right” and “adjacent_right” accordingly.
- Parameters:
lanelet – Lanelet to get information about.
- Returns:
Relation to lanelet right of the input lanelet in the route. Nothing if ‘lanelet’ is not part of the route.
-
LaneletRelations rightRelations(const ConstLanelet &lanelet) const
Provides information of the all lanelets right of a given lanelet within the Route.
Note
The returned lanelets include lanelets that can be switched or not-switched to. The relations will be “right” and “adjacent_right” accordingly.
- Parameters:
lanelet – Lanelet to get information about.
- Returns:
Relations to lanelets right of the input lanelet in the route. Nothing if ‘lanelet’ is not part of the route.
-
void forEachSuccessor(const ConstLanelet &lanelet, const LaneletVisitFunction &f) const
Can be used to search the route object with a custom function that is called for the successors of lanelet. This function works similar to RoutingGraph::forEachSuccessor. Which costs and whether lane changes are used to determine the shortest path depends on the cost id that was used to create this route object.
-
void forEachPredecessor(const ConstLanelet &lanelet, const LaneletVisitFunction &f) const
Similar to forEachSuccessor but goes backwards in the routing graph instead of forwards.
-
ConstLanelets conflictingInRoute(const ConstLanelet &lanelet) const
Information about conflicting lanelets of a lanelet within the route.
See also
- Parameters:
lanelet – Lanelet to find conflicting lanelets to
- Returns:
Vector of conflicting lanelets. Empty vector if input lanelet is not part of the route.
-
ConstLaneletOrAreas conflictingInMap(const ConstLanelet &lanelet) const
Information about conflicting lanelets of a lanelet within all passable lanelets in the laneletMap.
See also
- Parameters:
lanelet – Lanelet to find conflicting lanelets to
- Returns:
Vector of conflicting lanelets. Empty vector if input lanelet is not part of the route. Lanelets that are also conflicting in route are returned as well.
-
ConstLaneletOrAreas allConflictingInMap() const
Provides all lanelets in the map that conflict with any lanelet in the route.
-
bool contains(const ConstLanelet &lanelet) const
Checks if a specific lanelet is part of the route.
-
Errors checkValidity(bool throwOnError = false) const
Perform some sanity checks on the route.
- Parameters:
throwOnError – Throw or not-throw an exception if errors are found
- Throws:
Throws – if errors are encountered and throwOnError is true
- Returns:
Vector of errors if no-throw is chosen and errors are found