15 #ifndef TRAFFIC_SIMULATOR__HDMAP_UTILS__HDMAP_UTILS_HPP_
16 #define TRAFFIC_SIMULATOR__HDMAP_UTILS__HDMAP_UTILS_HPP_
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>
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 <boost/filesystem.hpp>
36 #include <geographic_msgs/msg/geo_point.hpp>
40 #include <geometry_msgs/msg/pose_stamped.hpp>
44 #include <rclcpp/rclcpp.hpp>
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>
54 #include <unordered_map>
57 #include <visualization_msgs/msg/marker_array.hpp>
66 explicit HdMapUtils(
const boost::filesystem::path &,
const geographic_msgs::msg::GeoPoint &);
69 const lanelet::Id from,
const lanelet::Id to,
74 const lanelet::Id,
const double s,
const lanelet::Ids &,
75 const double forward_distance = 20)
const -> std::vector<geometry_msgs::msg::Point>;
83 auto filterLaneletIds(
const lanelet::Ids &,
const char subtype[])
const -> lanelet::Ids;
85 auto generateMarker()
const -> visualization_msgs::msg::MarkerArray;
87 auto getCenterPoints(
const lanelet::Ids &)
const -> std::vector<geometry_msgs::msg::Point>;
89 auto getCenterPoints(
const lanelet::Id)
const -> std::vector<geometry_msgs::msg::Point>;
92 -> std::shared_ptr<math::geometry::CatmullRomSpline>;
96 const bool include_crosswalk =
false)
const -> std::optional<lanelet::Id>;
99 const lanelet::Id lanelet_id,
const lanelet::Id crossing_lanelet_id)
const
100 -> std::optional<double>;
110 const lanelet::Ids & route_lanelets,
114 const lanelet::Ids & route_lanelets,
115 const std::vector<geometry_msgs::msg::Point> & waypoints)
const -> std::optional<double>;
118 const lanelet::Ids & route_lanelets,
122 const lanelet::Ids & route_lanelets,
123 const std::vector<geometry_msgs::msg::Point> & waypoints)
const -> std::optional<double>;
127 const lanelet::Id traffic_light_id)
const -> std::optional<double>;
130 const std::vector<geometry_msgs::msg::Point> & waypoints,
131 const lanelet::Id traffic_light_id)
const -> std::optional<double>;
134 const lanelet::Id current_lanelet_id,
const lanelet::Ids &
route,
const double horizon = 100,
135 const bool include_current_lanelet_id =
true,
140 const lanelet::Id,
const double distance = 100,
const bool include_self =
true,
149 const double maximum_curvature_threshold,
const double target_trajectory_length,
150 const double forward_distance_threshold)
const
151 -> std::optional<std::pair<math::geometry::HermiteCurve, double>>;
156 -> std::optional<std::pair<math::geometry::HermiteCurve, double>>;
162 -> std::optional<lanelet::Id>;
168 -> std::optional<lanelet::Id>;
172 auto getLaneletPolygon(
const lanelet::Id)
const -> std::vector<geometry_msgs::msg::Point>;
174 auto getLanelets(
const lanelet::Ids &)
const -> lanelet::Lanelets;
182 auto getLeftBound(
const lanelet::Id)
const -> std::vector<geometry_msgs::msg::Point>;
192 const bool include_crosswalk,
const std::size_t search_count = 5)
const -> lanelet::Ids;
196 const std::size_t search_count = 5)
const -> lanelet::Ids;
199 const lanelet::Id,
const double backward_horizon = 100,
203 auto getRightBound(
const lanelet::Id)
const -> std::vector<geometry_msgs::msg::Point>;
206 -> std::unordered_map<lanelet::Id, lanelet::Ids>;
211 const lanelet::Id from,
const lanelet::Id to,
224 auto getStopLinePolygon(
const lanelet::Id)
const -> std::vector<geometry_msgs::msg::Point>;
227 -> std::optional<geometry_msgs::msg::Vector3>;
230 -> std::optional<geometry_msgs::msg::Point>;
243 -> std::vector<std::vector<geometry_msgs::msg::Point>>;
246 visualization_msgs::msg::MarkerArray &,
const visualization_msgs::msg::MarkerArray &)
const
251 auto isInLanelet(
const lanelet::Id,
const double s)
const -> bool;
253 auto isInRoute(
const lanelet::Id,
const lanelet::Ids &
route)
const -> bool;
262 constexpr
static double DEFAULT_MATCH_TO_LANE_REDUCTION_RATIO = 0.8;
265 auto toMapBin()
const -> autoware_map_msgs::msg::LaneletMapBin;
267 auto toMapPoints(
const lanelet::Id,
const std::vector<double> & s)
const
268 -> std::vector<geometry_msgs::msg::Point>;
279 lanelet::LaneletMapPtr lanelet_map_ptr_;
284 explicit RoutingGraphs(
const lanelet::LaneletMapPtr & lanelet_map);
288 lanelet::traffic_rules::TrafficRulesPtr
rules;
289 lanelet::routing::RoutingGraphPtr
graph;
293 [[nodiscard]] lanelet::routing::RoutingGraphPtr routing_graph(
296 [[nodiscard]] lanelet::traffic_rules::TrafficRulesPtr traffic_rule(
300 const lanelet::Id from_lanelet_id,
const lanelet::Id to_lanelet_id,
301 lanelet::LaneletMapPtr lanelet_map_ptr,
315 std::unique_ptr<RoutingGraphs> routing_graphs_;
317 template <
typename Lanelet>
318 auto getLaneletIds(
const std::vector<Lanelet> & lanelets)
const -> lanelet::Ids
322 lanelets.begin(), lanelets.end(), std::back_inserter(ids),
323 [](
const auto & lanelet) { return lanelet.id(); });
328 const lanelet::BasicPolygon2d & relative_hull,
const lanelet::matching::Pose2d &)
const
329 -> lanelet::BasicPolygon2d;
332 const std::vector<double> & x,
const std::vector<double> & y,
333 const std::vector<double> & z)
const -> std::vector<double>;
335 auto calculateAccumulatedLengths(
const lanelet::ConstLineString3d &)
const -> std::vector<double>;
337 auto calculateSegmentDistances(
const lanelet::ConstLineString3d &)
const -> std::vector<double>;
339 auto excludeSubtypeLanelets(
340 const std::vector<std::pair<double, lanelet::Lanelet>> &,
const char subtype[])
const
341 -> std::vector<std::pair<double, lanelet::Lanelet>>;
343 auto filterLanelets(
const lanelet::Lanelets &,
const char subtype[])
const -> lanelet::Lanelets;
345 auto findNearestIndexPair(
346 const std::vector<double> & accumulated_lengths,
const double target_length)
const
347 -> std::pair<std::size_t, std::size_t>;
349 auto generateFineCenterline(
const lanelet::ConstLanelet &,
const double resolution)
const
350 -> lanelet::LineString3d;
355 const double tangent_vector_size = 100) const ->
math::geometry::HermiteCurve;
357 auto getStopLines() const -> lanelet::ConstLineStrings3d;
359 auto getStopLinesOnPath(const lanelet::Ids &) const -> lanelet::ConstLineStrings3d;
361 auto getTrafficLightRegulatoryElementsOnPath(const lanelet::Ids &) const
362 ->
std::vector<
std::shared_ptr<const lanelet::autoware::AutowareTrafficLight>>;
364 auto getTrafficLights(const lanelet::Id traffic_light_id) const
365 ->
std::vector<lanelet::AutowareTrafficLightConstPtr>;
367 auto getTrafficSignRegulatoryElementsOnPath(const lanelet::Ids &) const
368 ->
std::vector<
std::shared_ptr<const lanelet::TrafficSign>>;
370 auto getTrafficSignRegulatoryElements() const
371 ->
std::vector<
std::shared_ptr<const lanelet::TrafficSign>>;
373 auto getVectorFromPose(const geometry_msgs::msg::
Pose &, const
double magnitude) const
374 -> geometry_msgs::msg::
Vector3;
376 auto mapCallback(const autoware_map_msgs::msg::LaneletMapBin &) const ->
void;
378 auto overwriteLaneletsCenterline() ->
void;
380 auto resamplePoints(const lanelet::ConstLineString3d &, const
std::int32_t num_segments) const
381 -> lanelet::BasicPoints3d;
383 auto toPoint2d(const geometry_msgs::msg::
Point &) const -> lanelet::BasicPoint2d;
385 auto toPolygon(const lanelet::ConstLineString3d &) const
386 ->
std::vector<geometry_msgs::msg::
Point>;
Definition: hdmap_utils.hpp:64
auto getStopLineIds() const -> lanelet::Ids
Definition: hdmap_utils.cpp:1271
auto getTangentVector(const lanelet::Id, const double s) const -> std::optional< geometry_msgs::msg::Vector3 >
Definition: hdmap_utils.cpp:922
auto getLongitudinalDistance(const traffic_simulator_msgs::msg::LaneletPose &from_pose, const traffic_simulator_msgs::msg::LaneletPose &to_pose, const traffic_simulator::RoutingConfiguration &routing_configuration=traffic_simulator::RoutingConfiguration()) const -> std::optional< double >
Definition: hdmap_utils.cpp:984
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:620
auto toMapPoints(const lanelet::Id, const std::vector< double > &s) const -> std::vector< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:911
HdMapUtils(const boost::filesystem::path &, const geographic_msgs::msg::GeoPoint &)
Definition: hdmap_utils.cpp:65
auto isInIntersection(const lanelet::Id) const -> bool
Definition: hdmap_utils.cpp:901
auto getCenterPointsSpline(const lanelet::Id) const -> std::shared_ptr< math::geometry::CatmullRomSpline >
Definition: hdmap_utils.cpp:628
auto getDistanceToTrafficLightStopLine(const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: hdmap_utils.cpp:1396
auto getStopLineIdsOnPath(const lanelet::Ids &route_lanelets) const -> lanelet::Ids
Definition: hdmap_utils.cpp:1280
auto getTrafficLightStopLinesPoints(const lanelet::Id traffic_light_id) const -> std::vector< std::vector< geometry_msgs::msg::Point >>
Definition: hdmap_utils.cpp:1323
auto getCollisionPointInLaneCoordinate(const lanelet::Id lanelet_id, const lanelet::Id crossing_lanelet_id) const -> std::optional< double >
Definition: hdmap_utils.cpp:226
auto getDistanceToStopLine(const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: hdmap_utils.cpp:1485
auto getTrafficLightIds() const -> lanelet::Ids
Definition: hdmap_utils.cpp:688
auto getSpeedLimit(const lanelet::Ids &, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) const -> double
Definition: hdmap_utils.cpp:443
auto getConflictingLaneIds(const lanelet::Ids &, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) const -> lanelet::Ids
Definition: hdmap_utils.cpp:275
auto isInRoute(const lanelet::Id, const lanelet::Ids &route) const -> bool
Definition: hdmap_utils.cpp:533
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:928
auto getRightOfWayLaneletIds(const lanelet::Ids &) const -> std::unordered_map< lanelet::Id, lanelet::Ids >
Definition: hdmap_utils.cpp:1177
auto filterLaneletIds(const lanelet::Ids &, const char subtype[]) const -> lanelet::Ids
Definition: hdmap_utils.cpp:147
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:809
auto getStopLinePolygon(const lanelet::Id) const -> std::vector< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:1345
auto getTrafficLightRegulatoryElement(const lanelet::Id) const -> lanelet::TrafficLight::Ptr
Definition: hdmap_utils.cpp:1649
auto getAltitude(const traffic_simulator_msgs::msg::LaneletPose &) const -> double
Definition: hdmap_utils.cpp:220
auto isTrafficLightRegulatoryElement(const lanelet::Id) const -> bool
Definition: hdmap_utils.cpp:1642
auto getTrafficLightBulbPosition(const lanelet::Id traffic_light_id, const std::string &) const -> std::optional< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:707
auto clipTrajectoryFromLaneletIds(const lanelet::Id, const double s, const lanelet::Ids &, const double forward_distance=20) const -> std::vector< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:313
auto getLeftBound(const lanelet::Id) const -> std::vector< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:743
auto getTrafficLightRegulatoryElementIDsFromTrafficLight(const lanelet::Id) const -> lanelet::Ids
Definition: hdmap_utils.cpp:1657
auto getTrafficLightIdsOnPath(const lanelet::Ids &route_lanelets) const -> lanelet::Ids
Definition: hdmap_utils.cpp:1360
auto getRightBound(const lanelet::Id) const -> std::vector< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:749
auto isTrafficLight(const lanelet::Id) const -> bool
Definition: hdmap_utils.cpp:1628
auto getLaneletIds() const -> lanelet::Ids
Definition: hdmap_utils.cpp:122
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:538
auto generateMarker() const -> visualization_msgs::msg::MarkerArray
Definition: hdmap_utils.cpp:1079
auto getClosestLaneletId(const geometry_msgs::msg::Pose &, const double distance_thresh=30.0, const bool include_crosswalk=false) const -> std::optional< lanelet::Id >
Definition: hdmap_utils.cpp:411
auto getTrafficLightStopLineIds(const lanelet::Id traffic_light_id) const -> lanelet::Ids
Definition: hdmap_utils.cpp:1311
auto getCenterPoints(const lanelet::Ids &) const -> std::vector< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:635
auto getLaneletPolygon(const lanelet::Id) const -> std::vector< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:131
auto toMapBin() const -> autoware_map_msgs::msg::LaneletMapBin
Definition: hdmap_utils.cpp:1056
auto getLateralDistance(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< double >
Definition: hdmap_utils.cpp:937
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:483
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:507
auto getLanelets(const lanelet::Ids &) const -> lanelet::Lanelets
Definition: hdmap_utils.cpp:1619
auto isInLanelet(const lanelet::Id, const double s) const -> bool
Definition: hdmap_utils.cpp:906
auto getConflictingCrosswalkIds(const lanelet::Ids &) const -> lanelet::Ids
Definition: hdmap_utils.cpp:291
auto getNearbyLaneletIds(const geometry_msgs::msg::Point &, const double distance_threshold, const bool include_crosswalk, const std::size_t search_count=5) const -> lanelet::Ids
Definition: hdmap_utils.cpp:182
auto insertMarkerArray(visualization_msgs::msg::MarkerArray &, const visualization_msgs::msg::MarkerArray &) const -> void
Definition: hdmap_utils.cpp:1072
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:88
Definition: cache.hpp:109
Definition: catmull_rom_spline_interface.hpp:30
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:36
Definition: lanelet_wrapper.hpp:39
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:33
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:65
geometry_msgs::msg::Point Point
Definition: lanelet_wrapper.hpp:64
geometry_msgs::msg::Vector3 Vector3
Definition: lanelet_wrapper.hpp:68
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
Definition: hdmap_utils.hpp:287
lanelet::traffic_rules::TrafficRulesPtr rules
Definition: hdmap_utils.hpp:288
RouteCache route_cache
Definition: hdmap_utils.hpp:290
lanelet::routing::RoutingGraphPtr graph
Definition: hdmap_utils.hpp:289
Definition: routing_configuration.hpp:24
parameters for behavior plugin
Definition: lane_change.hpp:75