RoutingGraphBuilder.h
Go to the documentation of this file.
1 #pragma once
3 
6 
7 namespace lanelet {
8 class LaneletLayer;
9 
10 namespace routing {
11 namespace internal {
12 
13 class LaneChangeLaneletsCollector;
14 
16  public:
17  RoutingGraphBuilder(const traffic_rules::TrafficRules& trafficRules, const RoutingCostPtrs& routingCosts,
18  const RoutingGraph::Configuration& config);
19 
20  RoutingGraphUPtr build(const LaneletMapLayers& laneletMapLayers);
21 
22  private:
23  using PointsLaneletMap = std::multimap<IdPair, ConstLanelet>;
24  using PointsLaneletMapIt = PointsLaneletMap::iterator;
25  using PointsLaneletMapResult = std::pair<PointsLaneletMapIt, PointsLaneletMapIt>;
26 
27  static ConstLanelets getPassableLanelets(const LaneletLayer& lanelets,
28  const traffic_rules::TrafficRules& trafficRules);
29  static ConstAreas getPassableAreas(const AreaLayer& areas, const traffic_rules::TrafficRules& trafficRules);
32  void addAreasToGraph(ConstAreas& areas);
33  void addEdges(const ConstLanelets& lanelets, const LaneletLayer& passableLanelets);
34  void addEdges(const ConstAreas& areas, const LaneletLayer& passableLanelets, const AreaLayer& passableAreas);
35  void addFollowingEdges(const ConstLanelet& ll);
36  void addSidewayEdge(LaneChangeLaneletsCollector& laneChangeLanelets, const ConstLanelet& ll,
37  const ConstLineString3d& bound, const RelationType& relation);
38  void addConflictingEdge(const ConstLanelet& ll, const LaneletLayer& passableLanelets);
39  void addLaneChangeEdges(LaneChangeLaneletsCollector& laneChanges, const RelationType& relation);
40  void addAreaEdge(const ConstArea& area, const LaneletLayer& passableLanelets);
41  void addAreaEdge(const ConstArea& area, const AreaLayer& passableAreas);
42 
45 
48  bool hasEdge(const ConstLanelet& from, const ConstLanelet& to);
49  void assignLaneChangeCosts(ConstLanelets froms, ConstLanelets tos, const RelationType& relation);
50 
55  void assignCosts(const ConstLaneletOrArea& from, const ConstLaneletOrArea& to, const RelationType& relation);
56  std::unique_ptr<RoutingGraphGraph> graph_;
58  std::set<Id> bothWaysLaneletIds_;
62 };
63 } // namespace internal
64 } // namespace routing
65 } // namespace lanelet
lanelet::routing::internal::RoutingGraphBuilder::PointsLaneletMapIt
PointsLaneletMap::iterator PointsLaneletMapIt
Definition: RoutingGraphBuilder.h:24
lanelet::routing::internal::RoutingGraphBuilder::addPointsToSearchIndex
void addPointsToSearchIndex(const ConstLanelet &ll)
Adds the first and last points of a lanelet to the search index.
Definition: RoutingGraphBuilder.cpp:325
lanelet::routing::internal::RoutingGraphBuilder::assignLaneChangeCosts
void assignLaneChangeCosts(ConstLanelets froms, ConstLanelets tos, const RelationType &relation)
Definition: RoutingGraphBuilder.cpp:341
lanelet::routing::internal::RoutingGraphBuilder::participantHeight
Optional< double > participantHeight() const
Helper function to read the participant height from the configuration.
Definition: RoutingGraphBuilder.cpp:317
RoutingGraph.h
LaneletMap.h
lanelet
lanelet::routing::internal::RoutingGraphBuilder::RoutingGraphBuilder
RoutingGraphBuilder(const traffic_rules::TrafficRules &trafficRules, const RoutingCostPtrs &routingCosts, const RoutingGraph::Configuration &config)
Definition: RoutingGraphBuilder.cpp:87
lanelet::traffic_rules::TrafficRules
lanelet::routing::RoutingCostPtrs
std::vector< RoutingCostPtr > RoutingCostPtrs
Definition: Forward.h:43
lanelet::ConstArea
lanelet::routing::internal::RoutingGraphBuilder::addSidewayEdge
void addSidewayEdge(LaneChangeLaneletsCollector &laneChangeLanelets, const ConstLanelet &ll, const ConstLineString3d &bound, const RelationType &relation)
Definition: RoutingGraphBuilder.cpp:198
lanelet::routing::internal::RoutingGraphBuilder::addEdges
void addEdges(const ConstLanelets &lanelets, const LaneletLayer &passableLanelets)
Definition: RoutingGraphBuilder.cpp:148
lanelet::routing::internal::RoutingGraphBuilder::getPassableLanelets
static ConstLanelets getPassableLanelets(const LaneletLayer &lanelets, const traffic_rules::TrafficRules &trafficRules)
Definition: RoutingGraphBuilder.cpp:106
lanelet::routing::internal::RoutingGraphBuilder::addFollowingEdges
void addFollowingEdges(const ConstLanelet &ll)
Definition: RoutingGraphBuilder.cpp:172
lanelet::ConstLaneletOrArea
lanelet::routing::internal::RoutingGraphBuilder::pointsToLanelets_
PointsLaneletMap pointsToLanelets_
A map of tuples (first or last left and right boundary points) to lanelets.
Definition: RoutingGraphBuilder.h:57
lanelet::routing::internal::RoutingGraphBuilder::addConflictingEdge
void addConflictingEdge(const ConstLanelet &ll, const LaneletLayer &passableLanelets)
Definition: RoutingGraphBuilder.cpp:216
lanelet::routing::RelationType
RelationType
Definition: Forward.h:56
lanelet::routing::internal::RoutingGraphBuilder::hasEdge
bool hasEdge(const ConstLanelet &from, const ConstLanelet &to)
Definition: RoutingGraphBuilder.cpp:337
lanelet::routing::internal::RoutingGraphBuilder::getPassableAreas
static ConstAreas getPassableAreas(const AreaLayer &areas, const traffic_rules::TrafficRules &trafficRules)
Definition: RoutingGraphBuilder.cpp:115
lanelet::routing::internal::RoutingGraphBuilder::PointsLaneletMapResult
std::pair< PointsLaneletMapIt, PointsLaneletMapIt > PointsLaneletMapResult
Definition: RoutingGraphBuilder.h:25
lanelet::routing::internal::RoutingGraphBuilder::build
RoutingGraphUPtr build(const LaneletMapLayers &laneletMapLayers)
Definition: RoutingGraphBuilder.cpp:94
lanelet::routing::internal::RoutingGraphBuilder::addLaneChangeEdges
void addLaneChangeEdges(LaneChangeLaneletsCollector &laneChanges, const RelationType &relation)
Definition: RoutingGraphBuilder.cpp:243
lanelet::Optional
boost::optional< T > Optional
lanelet::routing::internal::RoutingGraphBuilder::addAreaEdge
void addAreaEdge(const ConstArea &area, const LaneletLayer &passableLanelets)
Definition: RoutingGraphBuilder.cpp:268
lanelet::routing::internal::LaneChangeLaneletsCollector
This class collects lane changable lanelets and combines them to a sequence of adjacent lanechangable...
Definition: RoutingGraphBuilder.cpp:21
lanelet::routing::internal::RoutingGraphBuilder::appendBidirectionalLanelets
void appendBidirectionalLanelets(ConstLanelets &llts)
Definition: RoutingGraphBuilder.cpp:124
lanelet::routing::internal::RoutingGraphBuilder::config_
const RoutingGraph::Configuration & config_
Definition: RoutingGraphBuilder.h:61
lanelet::routing::RoutingGraphUPtr
std::unique_ptr< RoutingGraph > RoutingGraphUPtr
Definition: Forward.h:26
lanelet::routing::internal::RoutingGraphBuilder::addLaneletsToGraph
void addLaneletsToGraph(ConstLanelets &llts)
Definition: RoutingGraphBuilder.cpp:135
lanelet::routing::internal::RoutingGraphBuilder::PointsLaneletMap
std::multimap< IdPair, ConstLanelet > PointsLaneletMap
Definition: RoutingGraphBuilder.h:23
lanelet::AreaLayer
lanelet::routing::internal::RoutingGraphBuilder::trafficRules_
const traffic_rules::TrafficRules & trafficRules_
Definition: RoutingGraphBuilder.h:59
lanelet::routing::internal::RoutingGraphBuilder::routingCosts_
const RoutingCostPtrs & routingCosts_
Definition: RoutingGraphBuilder.h:60
lanelet::LaneletMapLayers
lanelet::routing::internal::RoutingGraphBuilder::assignCosts
void assignCosts(const ConstLaneletOrArea &from, const ConstLaneletOrArea &to, const RelationType &relation)
Assigns routing costs of each routing cost module to a relation between two lanelets.
Definition: RoutingGraphBuilder.cpp:358
lanelet::routing::internal::RoutingGraphBuilder::graph_
std::unique_ptr< RoutingGraphGraph > graph_
Definition: RoutingGraphBuilder.h:56
lanelet::routing::internal::RoutingGraphBuilder::bothWaysLaneletIds_
std::set< Id > bothWaysLaneletIds_
Definition: RoutingGraphBuilder.h:58
Graph.h
lanelet::LaneletLayer
lanelet::routing::internal::RoutingGraphBuilder::addAreasToGraph
void addAreasToGraph(ConstAreas &areas)
Definition: RoutingGraphBuilder.cpp:142
lanelet::ConstLineString3d
lanelet::ConstLanelet
lanelet::routing::RoutingGraph::Configuration
std::map< std::string, Attribute > Configuration
Definition: RoutingGraph.h:72
lanelet::routing::internal::RoutingGraphBuilder
Definition: RoutingGraphBuilder.h:15
lanelet::ConstAreas
std::vector< ConstArea > ConstAreas
ll
LaneletAdjacency ll
Definition: LaneletPath.cpp:88
lanelet::ConstLanelets
std::vector< ConstLanelet > ConstLanelets


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