Go to the documentation of this file.
60 auto getLength = [
this](
auto& lltOrArea) ->
double {
return this->
length(lltOrArea); };
68 auto totalLength = std::accumulate(from.begin(), from.end(), 0.,
69 [
this](
double acc,
auto& llt) { return acc + this->length(llt); });
101 auto changeTime = std::accumulate(from.begin(), from.end(), 0., [
this, &trafficRules](
double acc,
auto& llt) {
102 return acc + this->travelTime(trafficRules, llt);
108 auto getTravelTime = [&trafficRules,
this](
auto& lltOrArea) ->
double {
109 return this->
travelTime(trafficRules, lltOrArea);
123 return RoutingCostPtrs{std::make_shared<RoutingCostDistance>(10.), std::make_shared<RoutingCostTravelTime>(5.)};
units::MPSQuantity Velocity
decltype(auto) applyVisitor(VisitorT visitor) const
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.
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.
std::vector< RoutingCostPtr > RoutingCostPtrs
Abstract class to define a framework for custom routing cost calculation modules. This interfaces can...
const double minChangeLength_
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.
A basic travel time-based routing cost module. Uses maximum allowed speed or the maximum speed of the...
const double minChangeTime_
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.
RoutingCostPtrs defaultRoutingCosts()
Returns routing cost objects for initialization of routing graph with reasonable default values (for ...
const double laneChangeCost_
static double length(const ConstLanelet &ll) noexcept
const double laneChangeCost_
RoutingCostTravelTime()=delete
static double travelTime(const traffic_rules::TrafficRules &trafficRules, const ConstLanelet &ll)
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.
A basic distance-based routing cost module. Uses the 2D length and a fixed lane change cost to evalua...
RoutingCostDistance(double laneChangeCost, double minLaneChangeLength=0.)
virtual ~RoutingCost()=default
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.
RoutingCostTravelTime(double laneChangeCost, double minLaneChangeTime=0.)
std::vector< ConstLanelet > ConstLanelets
lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Sun Oct 27 2024 02:27:49