Class RoutingCost

Inheritance Relationships

Derived Types

Class Documentation

class RoutingCost

Abstract class to define a framework for custom routing cost calculation modules. This interfaces can be implemented to allow routing cost calculation based on specific needs (e.g. road conditions). As of now, two modules are implemented which should satisfy basic needs:

  1. Distance-based calculation

  2. Travel time-based calculation Routing cost modules can be used to prohibit a certain relation by setting the cost to infinity. Still it is generally better to use regulatory elements and the TrafficRules module to achieve this. The cost can represent whatever you want it to be - seconds, meter, lane changes, … but it must not be negative!

Subclassed by lanelet::routing::RoutingCostDistance, lanelet::routing::RoutingCostTravelTime

Public Functions

virtual ~RoutingCost() = default
virtual double getCostSucceeding(const traffic_rules::TrafficRules &trafficRules, const ConstLaneletOrArea &from, const ConstLaneletOrArea &to) const = 0

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

virtual double getCostLaneChange(const traffic_rules::TrafficRules &trafficRules, const ConstLanelets &from, const ConstLanelets &to) const = 0

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