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 auto isInLanelet(const lanelet::Id lanelet_id, const double lanelet_pose_s) -> bool;
30 
31 auto isInLanelet(const lanelet::Id lanelet_id, const Point point) -> bool;
32 
33 auto laneletLength(const lanelet::Id lanelet_id) -> double;
34 
35 auto laneletAltitude(
36  const lanelet::Id & lanelet_id, const geometry_msgs::msg::Pose & pose,
37  const double matching_distance) -> std::optional<double>;
38 
39 template <typename Lanelet>
40 auto laneletIds(const std::vector<Lanelet> & lanelets) -> lanelet::Ids
41 {
42  lanelet::Ids ids;
43  std::transform(
44  lanelets.begin(), lanelets.end(), std::back_inserter(ids),
45  [](const auto & lanelet) { return lanelet.id(); });
46  return ids;
47 }
48 
49 auto laneletIds() -> lanelet::Ids;
50 
51 auto nearbyLaneletIds(
52  const Point & point, const double distance_threshold, const bool include_crosswalk,
53  const std::size_t search_count) -> lanelet::Ids;
54 
55 auto centerPoints(const lanelet::Ids & lanelet_ids) -> std::vector<Point>;
56 
57 auto centerPoints(const lanelet::Id lanelet_id) -> std::vector<Point>;
58 
59 auto centerPointsSpline(const lanelet::Id lanelet_id) -> std::shared_ptr<Spline>;
60 
61 auto nextLaneletIds(
62  const lanelet::Id lanelet_id,
63  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
64 
65 auto nextLaneletIds(
66  const lanelet::Ids & lanelet_ids,
67  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
68 
69 auto nextLaneletIds(
70  const lanelet::Id lanelet_id, std::string_view turn_direction,
71  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
72 
73 auto nextLaneletIds(
74  const lanelet::Ids & lanelet_ids, std::string_view turn_direction,
75  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
76 
78  const lanelet::Id lanelet_id,
79  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
80 
82  const lanelet::Ids & lanelet_ids,
83  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
84 
86  const lanelet::Id lanelet_id, std::string_view turn_direction,
87  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
88 
90  const lanelet::Ids & lanelet_ids, std::string_view turn_direction,
91  const RoutingGraphType type = RoutingConfiguration().routing_graph_type) -> lanelet::Ids;
92 
93 // Bounds
94 auto leftBound(const lanelet::Id lanelet_id) -> std::vector<Point>;
95 
96 auto rightBound(const lanelet::Id lanelet_id) -> std::vector<Point>;
97 
98 // Polygons
99 auto stopLinePolygon(const lanelet::Id lanelet_id) -> std::vector<Point>;
100 
101 auto toPolygon(const lanelet::ConstLineString3d & line_string) -> std::vector<Point>;
102 
103 // Objects on path
104 auto trafficSignsOnPath(const lanelet::Ids & lanelet_ids)
105  -> std::vector<std::shared_ptr<const lanelet::TrafficSign>>;
106 
107 auto trafficSigns() -> std::vector<std::shared_ptr<const lanelet::TrafficSign>>;
108 
109 auto stopLines() -> lanelet::ConstLineStrings3d;
110 
111 auto stopLinesOnPath(const lanelet::Ids & lanelet_ids) -> lanelet::ConstLineStrings3d;
112 
113 auto stopLineIds() -> lanelet::Ids;
114 
115 auto stopLineIdsOnPath(const lanelet::Ids & lanelet_ids) -> lanelet::Ids;
116 } // namespace lanelet_map
117 } // namespace lanelet_wrapper
118 } // namespace traffic_simulator
119 #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:191
auto stopLines() -> lanelet::ConstLineStrings3d
Definition: lanelet_map.cpp:295
auto laneletAltitude(const lanelet::Id &lanelet_id, const geometry_msgs::msg::Pose &pose, const double matching_distance) -> std::optional< double >
Definition: lanelet_map.cpp:47
auto stopLinesOnPath(const lanelet::Ids &lanelet_ids) -> lanelet::ConstLineStrings3d
Definition: lanelet_map.cpp:307
auto leftBound(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:240
auto stopLineIds() -> lanelet::Ids
Definition: lanelet_map.cpp:319
auto stopLinePolygon(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:251
auto rightBound(const lanelet::Id lanelet_id) -> std::vector< Point >
Definition: lanelet_map.cpp:245
auto nextLaneletIds(const lanelet::Id lanelet_id, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> lanelet::Ids
Definition: lanelet_map.cpp:144
auto centerPointsSpline(const lanelet::Id lanelet_id) -> std::shared_ptr< Spline >
Definition: lanelet_map.cpp:138
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:68
auto trafficSigns() -> std::vector< std::shared_ptr< const lanelet::TrafficSign >>
Definition: lanelet_map.cpp:282
auto laneletIds(const std::vector< Lanelet > &lanelets) -> lanelet::Ids
Definition: lanelet_map.hpp:40
auto stopLineIdsOnPath(const lanelet::Ids &lanelet_ids) -> lanelet::Ids
Definition: lanelet_map.cpp:330
auto isInLanelet(const lanelet::Id lanelet_id, const double lanelet_pose_s) -> bool
Definition: lanelet_map.cpp:31
auto toPolygon(const lanelet::ConstLineString3d &line_string) -> std::vector< Point >
Definition: lanelet_map.cpp:257
auto laneletLength(const lanelet::Id lanelet_id) -> double
Definition: lanelet_map.cpp:42
auto centerPoints(const lanelet::Ids &lanelet_ids) -> std::vector< Point >
Definition: lanelet_map.cpp:117
auto trafficSignsOnPath(const lanelet::Ids &lanelet_ids) -> std::vector< std::shared_ptr< const lanelet::TrafficSign >>
Definition: lanelet_map.cpp:268
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