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 
19 
20 namespace traffic_simulator
21 {
22 namespace lanelet_wrapper
23 {
24 namespace lanelet_map
25 {
26 // Basics
27 auto isInLanelet(const lanelet::Id lanelet_id, const double lanelet_pose_s) -> bool;
28 
29 auto isInLanelet(const lanelet::Id lanelet_id, const Point point) -> bool;
30 
31 auto isInIntersection(const lanelet::Id) -> bool;
32 
33 auto laneletLength(const lanelet::Id lanelet_id) -> double;
34 
35 auto laneletYaw(const lanelet::Id lanelet_id, const Point & point)
36  -> std::tuple<double, Point, Point>;
37 
38 auto laneletAltitude(
39  const lanelet::Id & lanelet_id, const geometry_msgs::msg::Pose & pose,
40  const double matching_distance) -> std::optional<double>;
41 
42 template <typename Lanelet>
43 auto laneletIds(const std::vector<Lanelet> & lanelets) -> lanelet::Ids
44 {
45  lanelet::Ids ids;
46  std::transform(
47  lanelets.begin(), lanelets.end(), std::back_inserter(ids),
48  [](const auto & lanelet) { return lanelet.id(); });
49  return ids;
50 }
51 
52 auto laneletIds() -> lanelet::Ids;
53 
54 auto filterLaneletIds(const lanelet::Ids & lanelet_ids, const char subtype[]) -> lanelet::Ids;
55 
56 auto nearbyLaneletIds(
57  const Point & point, const double distance_threshold, const bool include_crosswalk,
58  const std::size_t search_count) -> lanelet::Ids;
59 
60 // Center points
61 auto centerPoints(const lanelet::Ids & lanelet_ids) -> std::vector<Point>;
62 
63 auto centerPoints(const lanelet::Id lanelet_id) -> std::vector<Point>;
64 
65 auto centerPointsSpline(const lanelet::Id lanelet_id) -> std::shared_ptr<Spline>;
66 
67 // Next lanelet
68 auto nextLaneletIds(
69  const lanelet::Id lanelet_id,
70  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
71 
72 auto nextLaneletIds(
73  const lanelet::Ids & lanelet_ids,
74  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
75 
76 auto nextLaneletIds(
77  const lanelet::Id lanelet_id, std::string_view turn_direction,
78  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
79 
80 auto nextLaneletIds(
81  const lanelet::Ids & lanelet_ids, std::string_view turn_direction,
82  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
83 
84 // Previous lanelet
86  const lanelet::Id lanelet_id,
87  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
88 
90  const lanelet::Ids & lanelet_ids,
91  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
92 
94  const lanelet::Id lanelet_id, std::string_view turn_direction,
95  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
96 
98  const lanelet::Ids & lanelet_ids, std::string_view turn_direction,
99  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
100 
101 // Bounds
102 auto leftBound(const lanelet::Id lanelet_id) -> std::vector<Point>;
103 
104 auto rightBound(const lanelet::Id lanelet_id) -> std::vector<Point>;
105 
106 // Polygons
107 auto laneletPolygon(const lanelet::Id lanelet_id) -> std::vector<Point>;
108 
109 auto stopLinePolygon(const lanelet::Id lanelet_id) -> std::vector<Point>;
110 
111 auto toPolygon(const lanelet::ConstLineString3d & line_string) -> std::vector<Point>;
112 
113 // Relations
114 auto rightOfWayLaneletIds(const lanelet::Ids & lanelet_ids)
115  -> std::unordered_map<lanelet::Id, lanelet::Ids>;
116 
117 auto rightOfWayLaneletIds(const lanelet::Id lanelet_id) -> lanelet::Ids;
118 
119 auto conflictingCrosswalkIds(const lanelet::Ids & lanelet_ids) -> lanelet::Ids;
120 
121 auto conflictingLaneIds(
122  const lanelet::Ids & lanelet_ids,
123  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
124 
125 // Objects on path
126 auto trafficSignsOnPath(const lanelet::Ids & lanelet_ids)
127  -> std::vector<std::shared_ptr<const lanelet::TrafficSign>>;
128 
129 auto trafficSigns() -> std::vector<std::shared_ptr<const lanelet::TrafficSign>>;
130 
131 auto stopLines() -> lanelet::ConstLineStrings3d;
132 
133 auto stopLinesOnPath(const lanelet::Ids & lanelet_ids) -> lanelet::ConstLineStrings3d;
134 
135 auto stopLineIds() -> lanelet::Ids;
136 
137 auto stopLineIdsOnPath(const lanelet::Ids & lanelet_ids) -> lanelet::Ids;
138 } // namespace lanelet_map
139 } // namespace lanelet_wrapper
140 } // namespace traffic_simulator
141 #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:249
auto laneletPolygon(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:311
auto stopLines() -> lanelet::ConstLineStrings3d
Definition: lanelet_map.cpp:425
auto laneletAltitude(const lanelet::Id &lanelet_id, const geometry_msgs::msg::Pose &pose, const double matching_distance) -> std::optional< double >
Definition: lanelet_map.cpp:73
auto isInIntersection(const lanelet::Id) -> bool
Definition: lanelet_map.cpp:40
auto stopLinesOnPath(const lanelet::Ids &lanelet_ids) -> lanelet::ConstLineStrings3d
Definition: lanelet_map.cpp:437
auto leftBound(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:300
auto conflictingLaneIds(const lanelet::Ids &lanelet_ids, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> lanelet::Ids
Definition: lanelet_map.cpp:383
auto stopLineIds() -> lanelet::Ids
Definition: lanelet_map.cpp:449
auto stopLinePolygon(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:322
auto rightBound(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:305
auto nextLaneletIds(const lanelet::Id lanelet_id, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> lanelet::Ids
Definition: lanelet_map.cpp:199
auto centerPointsSpline(const lanelet::Id lanelet_id) -> std::shared_ptr< Spline >
Definition: lanelet_map.cpp:192
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:120
auto trafficSigns() -> std::vector< std::shared_ptr< const lanelet::TrafficSign >>
Definition: lanelet_map.cpp:412
auto rightOfWayLaneletIds(const lanelet::Ids &lanelet_ids) -> std::unordered_map< lanelet::Id, lanelet::Ids >
Definition: lanelet_map.cpp:354
auto laneletYaw(const lanelet::Id lanelet_id, const Point &point) -> std::tuple< double, Point, Point >
Definition: lanelet_map.cpp:50
auto filterLaneletIds(const lanelet::Ids &lanelet_ids, const char subtype[]) -> lanelet::Ids
Definition: lanelet_map.cpp:96
auto laneletIds(const std::vector< Lanelet > &lanelets) -> lanelet::Ids
Definition: lanelet_map.hpp:43
auto stopLineIdsOnPath(const lanelet::Ids &lanelet_ids) -> lanelet::Ids
Definition: lanelet_map.cpp:460
auto isInLanelet(const lanelet::Id lanelet_id, const double lanelet_pose_s) -> bool
Definition: lanelet_map.cpp:29
auto conflictingCrosswalkIds(const lanelet::Ids &lanelet_ids) -> lanelet::Ids
Definition: lanelet_map.cpp:364
auto toPolygon(const lanelet::ConstLineString3d &line_string) -> std::vector< Point >
Definition: lanelet_map.cpp:328
auto laneletLength(const lanelet::Id lanelet_id) -> double
Definition: lanelet_map.cpp:45
auto centerPoints(const lanelet::Ids &lanelet_ids) -> std::vector< Point >
Definition: lanelet_map.cpp:170
auto trafficSignsOnPath(const lanelet::Ids &lanelet_ids) -> std::vector< std::shared_ptr< const lanelet::TrafficSign >>
Definition: lanelet_map.cpp:398
geometry_msgs::msg::Point Point
Definition: lanelet_wrapper.hpp:69
RoutingGraphType
Definition: routing_graph_type.hpp:24
Definition: api.hpp:33
Definition: routing_configuration.hpp:24