Public Member Functions | Static Private Member Functions | Private Attributes | List of all members
lanelet::routing::RoutingCostDistance Class Reference

A basic distance-based routing cost module. Uses the 2D length and a fixed lane change cost to evaluate relations. More...

#include <RoutingCost.h>

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

Public Member Functions

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. More...
 
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. More...
 
 RoutingCostDistance (double laneChangeCost, double minLaneChangeLength=0.)
 
- Public Member Functions inherited from lanelet::routing::RoutingCost
virtual ~RoutingCost ()=default
 

Static Private Member Functions

static double length (const ConstArea &ar) noexcept
 
static double length (const ConstLanelet &ll) noexcept
 

Private Attributes

const double laneChangeCost_
 
const double minChangeLength_
 

Detailed Description

A basic distance-based routing cost module. Uses the 2D length and a fixed lane change cost to evaluate relations.

Definition at line 48 of file RoutingCost.h.

Constructor & Destructor Documentation

◆ RoutingCostDistance()

lanelet::routing::RoutingCostDistance::RoutingCostDistance ( double  laneChangeCost,
double  minLaneChangeLength = 0. 
)
inlineexplicit

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".

Definition at line 52 of file RoutingCost.h.

Member Function Documentation

◆ getCostLaneChange()

double lanelet::routing::RoutingCostDistance::getCostLaneChange ( const traffic_rules::TrafficRules trafficRules,
const ConstLanelets from,
const ConstLanelets to 
) const
inlineoverridevirtualnoexcept

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.

Implements lanelet::routing::RoutingCost.

Definition at line 63 of file RoutingCost.h.

◆ getCostSucceeding()

double lanelet::routing::RoutingCostDistance::getCostSucceeding ( const traffic_rules::TrafficRules trafficRules,
const ConstLaneletOrArea from,
const ConstLaneletOrArea to 
) const
inlineoverridevirtual

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.

Implements lanelet::routing::RoutingCost.

Definition at line 58 of file RoutingCost.h.

◆ length() [1/2]

double lanelet::routing::RoutingCostDistance::length ( const ConstArea ar)
staticprivatenoexcept

Definition at line 37 of file RoutingCost.cpp.

◆ length() [2/2]

double lanelet::routing::RoutingCostDistance::length ( const ConstLanelet ll)
staticprivatenoexcept

Definition at line 35 of file RoutingCost.cpp.

Member Data Documentation

◆ laneChangeCost_

const double lanelet::routing::RoutingCostDistance::laneChangeCost_
private

Definition at line 76 of file RoutingCost.h.

◆ minChangeLength_

const double lanelet::routing::RoutingCostDistance::minChangeLength_
private

Definition at line 76 of file RoutingCost.h.


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


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