scenario_simulator_v2 C++ API
hdmap_utils.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__HDMAP_UTILS__HDMAP_UTILS_HPP_
16 #define TRAFFIC_SIMULATOR__HDMAP_UTILS__HDMAP_UTILS_HPP_
17 
18 #include <geometry_msgs/msg/vector3.h>
19 #include <lanelet2_core/LaneletMap.h>
20 #include <lanelet2_core/geometry/Lanelet.h>
21 #include <lanelet2_core/primitives/BasicRegulatoryElements.h>
22 #include <lanelet2_core/primitives/LaneletSequence.h>
23 #include <lanelet2_matching/LaneletMatching.h>
24 #include <lanelet2_routing/Route.h>
25 #include <lanelet2_routing/RoutingCost.h>
26 #include <lanelet2_routing/RoutingGraph.h>
27 #include <lanelet2_routing/RoutingGraphContainer.h>
28 #include <lanelet2_traffic_rules/TrafficRulesFactory.h>
29 #include <tf2/LinearMath/Matrix3x3.h>
30 
31 #include <autoware_lanelet2_extension/utility/message_conversion.hpp>
32 #include <autoware_lanelet2_extension/utility/query.hpp>
33 #include <autoware_lanelet2_extension/utility/utilities.hpp>
34 #include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
35 #include <filesystem>
36 #include <geographic_msgs/msg/geo_point.hpp>
40 #include <geometry_msgs/msg/pose_stamped.hpp>
41 #include <map>
42 #include <memory>
43 #include <optional>
44 #include <rclcpp/rclcpp.hpp>
45 #include <string>
46 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
51 #include <traffic_simulator_msgs/msg/bounding_box.hpp>
52 #include <traffic_simulator_msgs/msg/entity_status.hpp>
53 #include <tuple>
54 #include <unordered_map>
55 #include <utility>
56 #include <vector>
57 #include <visualization_msgs/msg/marker_array.hpp>
58 
59 namespace hdmap_utils
60 {
61 enum class LaneletType { LANE, CROSSWALK };
62 
64 {
65 public:
66  explicit HdMapUtils(const std::filesystem::path &, const geographic_msgs::msg::GeoPoint &);
67 
68  auto canChangeLane(
69  const lanelet::Id from, const lanelet::Id to,
71  traffic_simulator::RoutingConfiguration().routing_graph_type) const -> bool;
72 
73  auto countLaneChanges(
76  const traffic_simulator::RoutingConfiguration & routing_configuration =
77  traffic_simulator::RoutingConfiguration()) const -> std::optional<std::pair<int, int>>;
78 
79  auto generateMarker() const -> visualization_msgs::msg::MarkerArray;
80 
81  auto getCenterPoints(const lanelet::Ids &) const -> std::vector<geometry_msgs::msg::Point>;
82 
83  auto getCenterPoints(const lanelet::Id) const -> std::vector<geometry_msgs::msg::Point>;
84 
85  auto getCenterPointsSpline(const lanelet::Id) const
86  -> std::shared_ptr<math::geometry::CatmullRomSpline>;
87 
89  const lanelet::Id current_lanelet_id, const lanelet::Ids & route, const double horizon = 100,
90  const bool include_current_lanelet_id = true,
92  traffic_simulator::RoutingConfiguration().routing_graph_type) const -> lanelet::Ids;
93 
95  const lanelet::Id, const double distance = 100, const bool include_self = true,
97  traffic_simulator::RoutingConfiguration().routing_graph_type) const -> lanelet::Ids;
98 
100  const geometry_msgs::msg::Pose & from,
101  const traffic_simulator::lane_change::Parameter & lane_change_parameter,
102  const double maximum_curvature_threshold, const double target_trajectory_length,
103  const double forward_distance_threshold) const
104  -> std::optional<std::pair<math::geometry::HermiteCurve, double>>;
105 
108  const traffic_simulator::lane_change::Parameter & lane_change_parameter) const
109  -> std::optional<std::pair<math::geometry::HermiteCurve, double>>;
110 
112  const lanelet::Id, const traffic_simulator::lane_change::Direction,
114  traffic_simulator::RoutingConfiguration().routing_graph_type) const
115  -> std::optional<lanelet::Id>;
116 
118  const lanelet::Id, const traffic_simulator::lane_change::Direction, const std::uint8_t shift,
120  traffic_simulator::RoutingConfiguration().routing_graph_type) const
121  -> std::optional<lanelet::Id>;
122 
123  auto getLaneletIds() const -> lanelet::Ids;
124 
125  auto getLanelets(const lanelet::Ids &) const -> lanelet::Lanelets;
126 
127  auto getPreviousLanelets(
128  const lanelet::Id, const double backward_horizon = 100,
130  traffic_simulator::RoutingConfiguration().routing_graph_type) const -> lanelet::Ids;
131 
132  auto getRoute(
133  const lanelet::Id from, const lanelet::Id to,
134  const traffic_simulator::RoutingConfiguration & routing_configuration =
135  traffic_simulator::RoutingConfiguration()) const -> lanelet::Ids;
136 
137  auto getSpeedLimit(
138  const lanelet::Ids &, const traffic_simulator::RoutingGraphType type =
139  traffic_simulator::RoutingConfiguration().routing_graph_type) const
140  -> double;
141 
142  auto getTangentVector(const lanelet::Id, const double s) const
143  -> std::optional<geometry_msgs::msg::Vector3>;
144 
146  const lanelet::Id traffic_light_id, const std::string &,
147  const bool allow_infer_position = false) const -> std::optional<geometry_msgs::msg::Point>;
148 
149  auto getTrafficLightIds() const -> lanelet::Ids;
150 
151  auto getTrafficLightIdsOnPath(const lanelet::Ids & route_lanelets) const -> lanelet::Ids;
152 
153  auto getTrafficLightRegulatoryElement(const lanelet::Id) const -> lanelet::TrafficLight::Ptr;
154 
155  auto getTrafficLightRegulatoryElementIDsFromTrafficLight(const lanelet::Id) const -> lanelet::Ids;
156 
157  auto getTrafficLightStopLineIds(const lanelet::Id traffic_light_id) const -> lanelet::Ids;
158 
159  auto getTrafficLightStopLinesPoints(const lanelet::Id traffic_light_id) const
160  -> std::vector<std::vector<geometry_msgs::msg::Point>>;
161 
162  auto insertMarkerArray(
163  visualization_msgs::msg::MarkerArray &, const visualization_msgs::msg::MarkerArray &) const
164  -> void;
165 
166  auto isInRoute(const lanelet::Id, const lanelet::Ids & route) const -> bool;
167 
168  auto isTrafficLight(const lanelet::Id) const -> bool;
169 
170  auto isTrafficLightRegulatoryElement(const lanelet::Id) const -> bool;
171 
172 private:
175  constexpr static double DEFAULT_MATCH_TO_LANE_REDUCTION_RATIO = 0.8;
176 
180  // @{
181  mutable CenterPointsCache center_points_cache_;
182  mutable LaneletLengthCache lanelet_length_cache_;
183  // @}
184 
185  lanelet::LaneletMapPtr lanelet_map_ptr_;
186 
187  class RoutingGraphs
188  {
189  public:
190  explicit RoutingGraphs(const lanelet::LaneletMapPtr & lanelet_map);
191 
193  {
194  lanelet::traffic_rules::TrafficRulesPtr rules;
195  lanelet::routing::RoutingGraphPtr graph;
197  };
198 
199  [[nodiscard]] lanelet::routing::RoutingGraphPtr routing_graph(
200  const traffic_simulator::RoutingGraphType type) const;
201 
202  [[nodiscard]] lanelet::traffic_rules::TrafficRulesPtr traffic_rule(
203  const traffic_simulator::RoutingGraphType type) const;
204 
205  [[nodiscard]] auto getRoute(
206  const lanelet::Id from_lanelet_id, const lanelet::Id to_lanelet_id,
207  lanelet::LaneletMapPtr lanelet_map_ptr,
208  const traffic_simulator::RoutingConfiguration & routing_configuration =
209  traffic_simulator::RoutingConfiguration()) -> lanelet::Ids;
210 
211  private:
212  [[nodiscard]] RouteCache & route_cache(const traffic_simulator::RoutingGraphType type);
213 
214  RuleWithGraph vehicle;
215 
216  RuleWithGraph vehicle_with_road_shoulder;
217 
218  RuleWithGraph pedestrian;
219  };
220 
221  std::unique_ptr<RoutingGraphs> routing_graphs_;
222 
223  template <typename Lanelet>
224  auto getLaneletIds(const std::vector<Lanelet> & lanelets) const -> lanelet::Ids
225  {
226  lanelet::Ids ids;
227  std::transform(
228  lanelets.begin(), lanelets.end(), std::back_inserter(ids),
229  [](const auto & lanelet) { return lanelet.id(); });
230  return ids;
231  }
232 
233  auto calculateAccumulatedLengths(const lanelet::ConstLineString3d &) const -> std::vector<double>;
234 
235  auto calculateSegmentDistances(const lanelet::ConstLineString3d &) const -> std::vector<double>;
236 
237  auto excludeSubtypeLanelets(
238  const std::vector<std::pair<double, lanelet::Lanelet>> &, const char subtype[]) const
239  -> std::vector<std::pair<double, lanelet::Lanelet>>;
240 
241  auto findNearestIndexPair(
242  const std::vector<double> & accumulated_lengths, const double target_length) const
243  -> std::pair<std::size_t, std::size_t>;
244 
245  auto generateFineCenterline(const lanelet::ConstLanelet &, const double resolution) const
246  -> lanelet::LineString3d;
247 
251  const double tangent_vector_size = 100) const -> math::geometry::HermiteCurve;
252 
253  auto getTrafficLightRegulatoryElementsOnPath(const lanelet::Ids &) const
254  -> std::vector<std::shared_ptr<const lanelet::autoware::AutowareTrafficLight>>;
255 
256  auto getTrafficLights(const lanelet::Id traffic_light_id) const
257  -> std::vector<lanelet::AutowareTrafficLightConstPtr>;
258 
259  auto getTrafficSignRegulatoryElementsOnPath(const lanelet::Ids &) const
260  -> std::vector<std::shared_ptr<const lanelet::TrafficSign>>;
261 
262  auto getTrafficSignRegulatoryElements() const
263  -> std::vector<std::shared_ptr<const lanelet::TrafficSign>>;
264 
265  auto getVectorFromPose(const geometry_msgs::msg::Pose &, const double magnitude) const
266  -> geometry_msgs::msg::Vector3;
267 
268  auto resamplePoints(const lanelet::ConstLineString3d &, const std::int32_t num_segments) const
269  -> lanelet::BasicPoints3d;
270 };
271 } // namespace hdmap_utils
272 
273 #endif // TRAFFIC_SIMULATOR__HDMAP_UTILS__HDMAP_UTILS_HPP_
Definition: cache.hpp:67
Definition: hdmap_utils.hpp:64
auto getTangentVector(const lanelet::Id, const double s) const -> std::optional< geometry_msgs::msg::Vector3 >
Definition: hdmap_utils.cpp:610
auto getRoute(const lanelet::Id from, const lanelet::Id to, const traffic_simulator::RoutingConfiguration &routing_configuration=traffic_simulator::RoutingConfiguration()) const -> lanelet::Ids
Definition: hdmap_utils.cpp:308
auto getCenterPointsSpline(const lanelet::Id) const -> std::shared_ptr< math::geometry::CatmullRomSpline >
Definition: hdmap_utils.cpp:316
auto getTrafficLightStopLinesPoints(const lanelet::Id traffic_light_id) const -> std::vector< std::vector< geometry_msgs::msg::Point >>
Definition: hdmap_utils.cpp:797
auto getTrafficLightIds() const -> lanelet::Ids
Definition: hdmap_utils.cpp:376
auto getSpeedLimit(const lanelet::Ids &, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) const -> double
Definition: hdmap_utils.cpp:131
auto isInRoute(const lanelet::Id, const lanelet::Ids &route) const -> bool
Definition: hdmap_utils.cpp:221
auto canChangeLane(const lanelet::Id from, const lanelet::Id to, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) const -> bool
Definition: hdmap_utils.cpp:616
auto getLaneChangeTrajectory(const geometry_msgs::msg::Pose &from, const traffic_simulator::lane_change::Parameter &lane_change_parameter, const double maximum_curvature_threshold, const double target_trajectory_length, const double forward_distance_threshold) const -> std::optional< std::pair< math::geometry::HermiteCurve, double >>
Definition: hdmap_utils.cpp:518
auto getTrafficLightRegulatoryElement(const lanelet::Id) const -> lanelet::TrafficLight::Ptr
Definition: hdmap_utils.cpp:953
auto isTrafficLightRegulatoryElement(const lanelet::Id) const -> bool
Definition: hdmap_utils.cpp:946
auto getTrafficLightBulbPosition(const lanelet::Id traffic_light_id, const std::string &, const bool allow_infer_position=false) const -> std::optional< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:395
HdMapUtils(const std::filesystem::path &, const geographic_msgs::msg::GeoPoint &)
Definition: hdmap_utils.cpp:65
auto getTrafficLightRegulatoryElementIDsFromTrafficLight(const lanelet::Id) const -> lanelet::Ids
Definition: hdmap_utils.cpp:961
auto getTrafficLightIdsOnPath(const lanelet::Ids &route_lanelets) const -> lanelet::Ids
Definition: hdmap_utils.cpp:819
auto isTrafficLight(const lanelet::Id) const -> bool
Definition: hdmap_utils.cpp:932
auto getLaneletIds() const -> lanelet::Ids
Definition: hdmap_utils.cpp:106
auto getFollowingLanelets(const lanelet::Id current_lanelet_id, const lanelet::Ids &route, const double horizon=100, const bool include_current_lanelet_id=true, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) const -> lanelet::Ids
Definition: hdmap_utils.cpp:226
auto generateMarker() const -> visualization_msgs::msg::MarkerArray
Definition: hdmap_utils.cpp:632
auto getTrafficLightStopLineIds(const lanelet::Id traffic_light_id) const -> lanelet::Ids
Definition: hdmap_utils.cpp:785
auto getCenterPoints(const lanelet::Ids &) const -> std::vector< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:323
auto getLaneChangeableLaneletId(const lanelet::Id, const traffic_simulator::lane_change::Direction, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) const -> std::optional< lanelet::Id >
Definition: hdmap_utils.cpp:171
auto getPreviousLanelets(const lanelet::Id, const double backward_horizon=100, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) const -> lanelet::Ids
Definition: hdmap_utils.cpp:195
auto getLanelets(const lanelet::Ids &) const -> lanelet::Lanelets
Definition: hdmap_utils.cpp:923
auto insertMarkerArray(visualization_msgs::msg::MarkerArray &, const visualization_msgs::msg::MarkerArray &) const -> void
Definition: hdmap_utils.cpp:625
auto countLaneChanges(const traffic_simulator_msgs::msg::LaneletPose &from, const traffic_simulator_msgs::msg::LaneletPose &to, const traffic_simulator::RoutingConfiguration &routing_configuration=traffic_simulator::RoutingConfiguration()) const -> std::optional< std::pair< int, int >>
Definition: hdmap_utils.cpp:72
Definition: cache.hpp:109
Definition: cache.hpp:30
Definition: sim_model_delay_steer_acc_geared_wo_fall_guard.hpp:26
Definition: cache.hpp:28
LaneletType
Definition: hdmap_utils.hpp:61
Definition: bounding_box.hpp:32
auto distance(const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2)
Definition: detection_sensor.cpp:45
Definition: lanelet_wrapper.hpp:43
TrajectoryShape
Definition: lane_change.hpp:31
Direction
Definition: lane_change.hpp:29
auto route(const lanelet::Id from_lanelet_id, const lanelet::Id to_lanelet_id, const RoutingConfiguration &routing_configuration=RoutingConfiguration()) -> lanelet::Ids
Definition: route.cpp:28
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:69
geometry_msgs::msg::Vector3 Vector3
Definition: lanelet_wrapper.hpp:73
RoutingGraphType
Definition: routing_graph_type.hpp:24
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:30
std::string string
Definition: junit5.hpp:26
lanelet::traffic_rules::TrafficRulesPtr rules
Definition: hdmap_utils.hpp:194
RouteCache route_cache
Definition: hdmap_utils.hpp:196
lanelet::routing::RoutingGraphPtr graph
Definition: hdmap_utils.hpp:195
Definition: routing_configuration.hpp:24
parameters for behavior plugin
Definition: lane_change.hpp:75