Class RoutingCostTravelTime
Defined in File RoutingCost.h
Inheritance Relationships
Base Type
public lanelet::routing::RoutingCost
(Class RoutingCost)
Class Documentation
-
class RoutingCostTravelTime : public lanelet::routing::RoutingCost
A basic travel time-based routing cost module. Uses maximum allowed speed or the maximum speed of the participant (what every is lower) and a fixed lane chance cost.
Public Functions
-
RoutingCostTravelTime() = delete
-
inline explicit RoutingCostTravelTime(double laneChangeCost, double minLaneChangeTime = 0.)
Time cost of a lane change [s]. If the time is not sufficient for the lane change (i.e. minLaneChangeTime is not reached), no lane change will possible at this position. Instead the relation between the involved lanelets is “adjacent”.
-
inline virtual double getCostLaneChange(const traffic_rules::TrafficRules &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 virtual double getCostSucceeding(const traffic_rules::TrafficRules &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
-
RoutingCostTravelTime() = delete