RoutingCost.h
Go to the documentation of this file.
1 #pragma once
2 
7 
9 
10 namespace lanelet {
11 namespace routing {
12 
21 class RoutingCost { // NOLINT
22  public:
23  virtual ~RoutingCost() = default;
24 
32  virtual double getCostSucceeding(const traffic_rules::TrafficRules& trafficRules, const ConstLaneletOrArea& from,
33  const ConstLaneletOrArea& to) const = 0;
34 
42  virtual double getCostLaneChange(const traffic_rules::TrafficRules& trafficRules, const ConstLanelets& from,
43  const ConstLanelets& to) const = 0;
44 };
45 
49  public:
52  explicit RoutingCostDistance(double laneChangeCost, double minLaneChangeLength = 0.)
53  : laneChangeCost_{laneChangeCost}, minChangeLength_{minLaneChangeLength} {
54  if (laneChangeCost_ < 0.0) {
55  throw InvalidInputError("Lane change cost must be positive, but it is " + std::to_string(laneChangeCost_));
56  }
57  }
58  inline double getCostSucceeding(const traffic_rules::TrafficRules& /*trafficRules*/, const ConstLaneletOrArea& from,
59  const ConstLaneletOrArea& to) const override {
60  auto getLength = [this](auto& lltOrArea) -> double { return this->length(lltOrArea); };
61  return (from.applyVisitor(getLength) + to.applyVisitor(getLength)) / 2;
62  }
63  inline double getCostLaneChange(const traffic_rules::TrafficRules& /*trafficRules*/, const ConstLanelets& from,
64  const ConstLanelets& /*to*/) const noexcept override {
65  if (minChangeLength_ <= 0.) {
66  return laneChangeCost_;
67  }
68  auto totalLength = std::accumulate(from.begin(), from.end(), 0.,
69  [this](double acc, auto& llt) { return acc + this->length(llt); });
70  return totalLength >= minChangeLength_ ? laneChangeCost_ : std::numeric_limits<double>::infinity();
71  }
72 
73  private:
74  static double length(const ConstLanelet& ll) noexcept;
75  static double length(const ConstArea& ar) noexcept;
76  const double laneChangeCost_, minChangeLength_; // NOLINT
77 };
78 
83  public:
84  RoutingCostTravelTime() = delete;
85 
89  explicit RoutingCostTravelTime(double laneChangeCost, double minLaneChangeTime = 0.)
90  : laneChangeCost_{laneChangeCost}, minChangeTime_{minLaneChangeTime} {
91  if (laneChangeCost_ < 0.0) {
92  throw InvalidInputError("Lane change cost must be positive, but it is " + std::to_string(laneChangeCost_));
93  }
94  }
95 
96  inline double getCostLaneChange(const traffic_rules::TrafficRules& trafficRules, const ConstLanelets& from,
97  const ConstLanelets& /*to*/) const noexcept override {
98  if (minChangeTime_ <= 0.) {
99  return laneChangeCost_;
100  }
101  auto changeTime = std::accumulate(from.begin(), from.end(), 0., [this, &trafficRules](double acc, auto& llt) {
102  return acc + this->travelTime(trafficRules, llt);
103  });
104  return changeTime >= minChangeTime_ ? laneChangeCost_ : std::numeric_limits<double>::infinity();
105  }
106  inline double getCostSucceeding(const traffic_rules::TrafficRules& trafficRules, const ConstLaneletOrArea& from,
107  const ConstLaneletOrArea& to) const override {
108  auto getTravelTime = [&trafficRules, this](auto& lltOrArea) -> double {
109  return this->travelTime(trafficRules, lltOrArea);
110  };
111  return (from.applyVisitor(getTravelTime) + to.applyVisitor(getTravelTime)) / 2;
112  }
113 
114  private:
115  static double travelTime(const traffic_rules::TrafficRules& trafficRules, const ConstLanelet& ll);
116  static double travelTime(const traffic_rules::TrafficRules& trafficRules, const ConstArea& ar);
117  const Velocity maxSpeed_; // NOLINT
118  const double laneChangeCost_, minChangeTime_; // NOLINT
119 };
120 
123  return RoutingCostPtrs{std::make_shared<RoutingCostDistance>(10.), std::make_shared<RoutingCostTravelTime>(5.)};
124 }
125 } // namespace routing
126 } // namespace lanelet
lanelet::Velocity
units::MPSQuantity Velocity
Exceptions.h
lanelet::ConstLaneletOrArea::applyVisitor
decltype(auto) applyVisitor(VisitorT visitor) const
lanelet
lanelet::routing::RoutingCostDistance::getCostLaneChange
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.
Definition: RoutingCost.h:63
lanelet::routing::RoutingCostTravelTime::getCostLaneChange
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.
Definition: RoutingCost.h:96
lanelet::traffic_rules::TrafficRules
lanelet::routing::RoutingCostPtrs
std::vector< RoutingCostPtr > RoutingCostPtrs
Definition: Forward.h:43
lanelet::ConstArea
lanelet::routing::RoutingCost
Abstract class to define a framework for custom routing cost calculation modules. This interfaces can...
Definition: RoutingCost.h:21
lanelet::routing::RoutingCostDistance::minChangeLength_
const double minChangeLength_
Definition: RoutingCost.h:76
lanelet::routing::RoutingCost::getCostLaneChange
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.
lanelet::ConstLaneletOrArea
Forward.h
lanelet::routing::RoutingCostTravelTime
A basic travel time-based routing cost module. Uses maximum allowed speed or the maximum speed of the...
Definition: RoutingCost.h:82
lanelet::routing::RoutingCostTravelTime::minChangeTime_
const double minChangeTime_
Definition: RoutingCost.h:118
lanelet::routing::RoutingCost::getCostSucceeding
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.
lanelet::routing::defaultRoutingCosts
RoutingCostPtrs defaultRoutingCosts()
Returns routing cost objects for initialization of routing graph with reasonable default values (for ...
Definition: RoutingCost.h:122
LaneletOrArea.h
lanelet::routing::RoutingCostTravelTime::laneChangeCost_
const double laneChangeCost_
Definition: RoutingCost.h:118
lanelet::routing::RoutingCostDistance::length
static double length(const ConstLanelet &ll) noexcept
Definition: RoutingCost.cpp:35
lanelet::routing::RoutingCostDistance::laneChangeCost_
const double laneChangeCost_
Definition: RoutingCost.h:76
lanelet::routing::RoutingCostTravelTime::RoutingCostTravelTime
RoutingCostTravelTime()=delete
lanelet::routing::RoutingCostTravelTime::travelTime
static double travelTime(const traffic_rules::TrafficRules &trafficRules, const ConstLanelet &ll)
Definition: RoutingCost.cpp:24
lanelet::routing::RoutingCostDistance::getCostSucceeding
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.
Definition: RoutingCost.h:58
lanelet::routing::RoutingCostTravelTime::maxSpeed_
const Velocity maxSpeed_
Definition: RoutingCost.h:117
TrafficRules.h
lanelet::routing::RoutingCostDistance
A basic distance-based routing cost module. Uses the 2D length and a fixed lane change cost to evalua...
Definition: RoutingCost.h:48
lanelet::routing::RoutingCostDistance::RoutingCostDistance
RoutingCostDistance(double laneChangeCost, double minLaneChangeLength=0.)
Definition: RoutingCost.h:52
lanelet::ConstLanelet
lanelet::routing::RoutingCost::~RoutingCost
virtual ~RoutingCost()=default
Forward.h
lanelet::routing::RoutingCostTravelTime::getCostSucceeding
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.
Definition: RoutingCost.h:106
lanelet::routing::RoutingCostTravelTime::RoutingCostTravelTime
RoutingCostTravelTime(double laneChangeCost, double minLaneChangeTime=0.)
Definition: RoutingCost.h:89
ll
LaneletAdjacency ll
Definition: LaneletPath.cpp:88
lanelet::ConstLanelets
std::vector< ConstLanelet > ConstLanelets
lanelet::InvalidInputError


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