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. More...
#include <RoutingCost.h>
Public Member Functions | |
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. More... | |
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. More... | |
RoutingCostTravelTime ()=delete | |
RoutingCostTravelTime (double laneChangeCost, double minLaneChangeTime=0.) | |
Public Member Functions inherited from lanelet::routing::RoutingCost | |
virtual | ~RoutingCost ()=default |
Static Private Member Functions | |
static double | travelTime (const traffic_rules::TrafficRules &trafficRules, const ConstArea &ar) |
static double | travelTime (const traffic_rules::TrafficRules &trafficRules, const ConstLanelet &ll) |
Private Attributes | |
const double | laneChangeCost_ |
const Velocity | maxSpeed_ |
const double | minChangeTime_ |
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.
Definition at line 82 of file RoutingCost.h.
|
delete |
|
inlineexplicit |
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".
Definition at line 89 of file RoutingCost.h.
|
inlineoverridevirtualnoexcept |
Get the cost of the lane change between two adjacent lanelets.
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) |
Implements lanelet::routing::RoutingCost.
Definition at line 96 of file RoutingCost.h.
|
inlineoverridevirtual |
Get the cost of the transistion from one to another lanelet.
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) |
Implements lanelet::routing::RoutingCost.
Definition at line 106 of file RoutingCost.h.
|
staticprivate |
Definition at line 29 of file RoutingCost.cpp.
|
staticprivate |
Definition at line 24 of file RoutingCost.cpp.
|
private |
Definition at line 118 of file RoutingCost.h.
|
private |
Definition at line 117 of file RoutingCost.h.
|
private |
Definition at line 118 of file RoutingCost.h.