Public Member Functions | List of all members
lanelet::routing::RoutingCost Class Referenceabstract

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: More...

#include <RoutingCost.h>

Inheritance diagram for lanelet::routing::RoutingCost:
Inheritance graph
[legend]

Public Member Functions

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. More...
 
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. More...
 
virtual ~RoutingCost ()=default
 

Detailed Description

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!

Definition at line 21 of file RoutingCost.h.

Constructor & Destructor Documentation

◆ ~RoutingCost()

virtual lanelet::routing::RoutingCost::~RoutingCost ( )
virtualdefault

Member Function Documentation

◆ getCostLaneChange()

virtual double lanelet::routing::RoutingCost::getCostLaneChange ( const traffic_rules::TrafficRules trafficRules,
const ConstLanelets from,
const ConstLanelets to 
) const
pure virtual

Get the cost of the lane change between two adjacent lanelets.

Parameters
trafficRulesTrafficRules module to apply
fromThe lanelet or area the traffic participant is on (assumed to be in the middle)
toThe lanelet or area the traffic participant is reaching for (reference is the middle again)
Returns
Routing cost of the lane change
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.

Implemented in lanelet::routing::RoutingCostTravelTime, and lanelet::routing::RoutingCostDistance.

◆ getCostSucceeding()

virtual double lanelet::routing::RoutingCost::getCostSucceeding ( const traffic_rules::TrafficRules trafficRules,
const ConstLaneletOrArea from,
const ConstLaneletOrArea to 
) const
pure virtual

Get the cost of the transistion from one to another lanelet.

Parameters
trafficRulesTrafficRules module to apply
fromThe lanelet or area the traffic participant is on (assumed to be in the middle)
toThe lanelet or area the traffic participant is reaching for (reference is the middle again)
Returns
Routing cost for passing this 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.

Implemented in lanelet::routing::RoutingCostTravelTime, and lanelet::routing::RoutingCostDistance.


The documentation for this class was generated from the following file:


lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Sun Oct 27 2024 02:27:49