scenario_simulator_v2 C++ API
lanelet_map.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef TRAFFIC_SIMULATOR__LANELET_WRAPPER_LANELET_MAP_HPP_
16 #define TRAFFIC_SIMULATOR__LANELET_WRAPPER_LANELET_MAP_HPP_
17 
18 #include <lanelet2_core/geometry/Lanelet.h>
19 #include <lanelet2_core/primitives/LaneletSequence.h>
20 
22 
23 namespace traffic_simulator
24 {
25 namespace lanelet_wrapper
26 {
27 namespace lanelet_map
28 {
29 // Basics
30 auto isInLanelet(const lanelet::Id lanelet_id, const double lanelet_pose_s) -> bool;
31 
32 auto isInLanelet(const lanelet::Id lanelet_id, const Point point) -> bool;
33 
34 auto laneletLength(const lanelet::Id lanelet_id) -> double;
35 
36 auto laneletAltitude(
37  const lanelet::Id & lanelet_id, const geometry_msgs::msg::Pose & pose,
38  const double matching_distance) -> std::optional<double>;
39 
40 template <typename Lanelet>
41 auto laneletIds(const std::vector<Lanelet> & lanelets) -> lanelet::Ids
42 {
43  lanelet::Ids ids;
44  std::transform(
45  lanelets.begin(), lanelets.end(), std::back_inserter(ids),
46  [](const auto & lanelet) { return lanelet.id(); });
47  return ids;
48 }
49 
50 auto laneletIds() -> lanelet::Ids;
51 
52 auto nearbyLaneletIds(
53  const Point & point, const double distance_threshold, const bool include_crosswalk,
54  const std::size_t search_count) -> lanelet::Ids;
55 
56 // Center points
57 auto centerPoints(const lanelet::Ids & lanelet_ids) -> std::vector<Point>;
58 
59 auto centerPoints(const lanelet::Id lanelet_id) -> std::vector<Point>;
60 
61 auto centerPointsSpline(const lanelet::Id lanelet_id) -> std::shared_ptr<Spline>;
62 
63 // Next lanelet
64 auto nextLaneletIds(
65  const lanelet::Id lanelet_id,
66  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
67 
68 auto nextLaneletIds(
69  const lanelet::Ids & lanelet_ids,
70  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
71 
72 auto nextLaneletIds(
73  const lanelet::Id lanelet_id, std::string_view turn_direction,
74  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
75 
76 auto nextLaneletIds(
77  const lanelet::Ids & lanelet_ids, std::string_view turn_direction,
78  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
79 
80 // Previous lanelet
82  const lanelet::Id lanelet_id,
83  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
84 
86  const lanelet::Ids & lanelet_ids,
87  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
88 
90  const lanelet::Id lanelet_id, std::string_view turn_direction,
91  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
92 
94  const lanelet::Ids & lanelet_ids, std::string_view turn_direction,
95  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
96 
97 // Bounds
98 auto leftBound(const lanelet::Id lanelet_id) -> std::vector<Point>;
99 
100 auto rightBound(const lanelet::Id lanelet_id) -> std::vector<Point>;
101 
102 // Polygons
103 auto laneletPolygon(const lanelet::Id lanelet_id) -> std::vector<Point>;
104 
105 auto stopLinePolygon(const lanelet::Id lanelet_id) -> std::vector<Point>;
106 
107 auto toPolygon(const lanelet::ConstLineString3d & line_string) -> std::vector<Point>;
108 
109 // Relations
110 auto rightOfWayLaneletIds(const lanelet::Ids & lanelet_ids)
111  -> std::unordered_map<lanelet::Id, lanelet::Ids>;
112 
113 auto rightOfWayLaneletIds(const lanelet::Id lanelet_id) -> lanelet::Ids;
114 
115 auto conflictingCrosswalkIds(const lanelet::Ids & lanelet_ids) -> lanelet::Ids;
116 
117 auto conflictingLaneIds(
118  const lanelet::Ids & lanelet_ids,
119  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
120 
121 // Objects on path
122 auto trafficSignsOnPath(const lanelet::Ids & lanelet_ids)
123  -> std::vector<std::shared_ptr<const lanelet::TrafficSign>>;
124 
125 auto trafficSigns() -> std::vector<std::shared_ptr<const lanelet::TrafficSign>>;
126 
127 auto stopLines() -> lanelet::ConstLineStrings3d;
128 
129 auto stopLinesOnPath(const lanelet::Ids & lanelet_ids) -> lanelet::ConstLineStrings3d;
130 
131 auto stopLineIds() -> lanelet::Ids;
132 
133 auto stopLineIdsOnPath(const lanelet::Ids & lanelet_ids) -> lanelet::Ids;
134 } // namespace lanelet_map
135 } // namespace lanelet_wrapper
136 } // namespace traffic_simulator
137 #endif // TRAFFIC_SIMULATOR__LANELET_WRAPPER_LANELET_MAP_HPP_
geometry_msgs::msg::Pose Pose
Definition: lanelet_map.hpp:30
auto previousLaneletIds(const lanelet::Id lanelet_id, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> lanelet::Ids
Definition: lanelet_map.cpp:200
auto laneletPolygon(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:262
auto stopLines() -> lanelet::ConstLineStrings3d
Definition: lanelet_map.cpp:376
auto laneletAltitude(const lanelet::Id &lanelet_id, const geometry_msgs::msg::Pose &pose, const double matching_distance) -> std::optional< double >
Definition: lanelet_map.cpp:48
auto stopLinesOnPath(const lanelet::Ids &lanelet_ids) -> lanelet::ConstLineStrings3d
Definition: lanelet_map.cpp:388
auto leftBound(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:251
auto conflictingLaneIds(const lanelet::Ids &lanelet_ids, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> lanelet::Ids
Definition: lanelet_map.cpp:334
auto stopLineIds() -> lanelet::Ids
Definition: lanelet_map.cpp:400
auto stopLinePolygon(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:273
auto rightBound(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:256
auto nextLaneletIds(const lanelet::Id lanelet_id, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> lanelet::Ids
Definition: lanelet_map.cpp:150
auto centerPointsSpline(const lanelet::Id lanelet_id) -> std::shared_ptr< Spline >
Definition: lanelet_map.cpp:143
auto nearbyLaneletIds(const Point &point, const double distance_threshold, const bool include_crosswalk, const std::size_t search_count) -> lanelet::Ids
Definition: lanelet_map.cpp:71
auto trafficSigns() -> std::vector< std::shared_ptr< const lanelet::TrafficSign >>
Definition: lanelet_map.cpp:363
auto rightOfWayLaneletIds(const lanelet::Ids &lanelet_ids) -> std::unordered_map< lanelet::Id, lanelet::Ids >
Definition: lanelet_map.cpp:305
auto laneletIds(const std::vector< Lanelet > &lanelets) -> lanelet::Ids
Definition: lanelet_map.hpp:41
auto stopLineIdsOnPath(const lanelet::Ids &lanelet_ids) -> lanelet::Ids
Definition: lanelet_map.cpp:411
auto isInLanelet(const lanelet::Id lanelet_id, const double lanelet_pose_s) -> bool
Definition: lanelet_map.cpp:32
auto conflictingCrosswalkIds(const lanelet::Ids &lanelet_ids) -> lanelet::Ids
Definition: lanelet_map.cpp:315
auto toPolygon(const lanelet::ConstLineString3d &line_string) -> std::vector< Point >
Definition: lanelet_map.cpp:279
auto laneletLength(const lanelet::Id lanelet_id) -> double
Definition: lanelet_map.cpp:43
auto centerPoints(const lanelet::Ids &lanelet_ids) -> std::vector< Point >
Definition: lanelet_map.cpp:121
auto trafficSignsOnPath(const lanelet::Ids &lanelet_ids) -> std::vector< std::shared_ptr< const lanelet::TrafficSign >>
Definition: lanelet_map.cpp:349
geometry_msgs::msg::Point Point
Definition: lanelet_wrapper.hpp:65
RoutingGraphType
Definition: routing_graph_type.hpp:24
Definition: api.hpp:32
Definition: routing_configuration.hpp:24