Class RoutingCostDistance
Defined in File RoutingCost.h
Inheritance Relationships
Base Type
public lanelet::routing::RoutingCost
(Class RoutingCost)
Class Documentation
-
class RoutingCostDistance : public lanelet::routing::RoutingCost
A basic distance-based routing cost module. Uses the 2D length and a fixed lane change cost to evaluate relations.
Public Functions
-
inline explicit RoutingCostDistance(double laneChangeCost, double minLaneChangeLength = 0.)
Distance cost of a lane change [m]. If a lane change requires less than minLaneChangeLength, no lane change will be possible here. Instead, relation between the involved lanelets will be “adjacent”.
-
inline virtual double getCostSucceeding(const traffic_rules::TrafficRules&, const ConstLaneletOrArea &from, const ConstLaneletOrArea &to) const override
Get the cost of the transistion from one to another lanelet.
Note
The calculated cost will be assigned to the edge in the graph between ‘from’ and ‘to’. So typically this should represent the cost of passing the ‘from’-lanelet with regards of going into the ‘to’-lanelet.
- Parameters:
trafficRules – TrafficRules module to apply
from – The lanelet or area the traffic participant is on (assumed to be in the middle)
to – The lanelet or area the traffic participant is reaching for (reference is the middle again)
- Returns:
Routing cost for passing this lanelet
-
inline virtual double getCostLaneChange(const traffic_rules::TrafficRules&, const ConstLanelets &from, const ConstLanelets&) const noexcept override
Get the cost of the lane change between two adjacent lanelets.
Note
The calculated cost will be assigned to the edge in the graph between ‘from’ and ‘to’. So typically this should represent some artificial cost for a lane change.
- Parameters:
trafficRules – TrafficRules module to apply
from – The lanelet or area the traffic participant is on (assumed to be in the middle)
to – The lanelet or area the traffic participant is reaching for (reference is the middle again)
- Returns:
Routing cost of the lane change
-
inline explicit RoutingCostDistance(double laneChangeCost, double minLaneChangeLength = 0.)