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_auto_mapping_msgs/msg/had_map_bin.hpp>
32 #include <autoware_lanelet2_extension/utility/message_conversion.hpp>
33 #include <autoware_lanelet2_extension/utility/query.hpp>
34 #include <autoware_lanelet2_extension/utility/utilities.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>
49 #include <traffic_simulator_msgs/msg/bounding_box.hpp>
50 #include <traffic_simulator_msgs/msg/entity_status.hpp>
52 #include <unordered_map>
55 #include <visualization_msgs/msg/marker_array.hpp>
64 explicit HdMapUtils(
const boost::filesystem::path &,
const geographic_msgs::msg::GeoPoint &);
66 auto canChangeLane(
const lanelet::Id from,
const lanelet::Id to)
const -> bool;
70 std::optional<traffic_simulator_msgs::msg::LaneletPose>, std::optional<lanelet::Id>>;
75 std::optional<traffic_simulator_msgs::msg::LaneletPose>, std::optional<lanelet::Id>>;
78 const lanelet::Id,
const double s,
const lanelet::Ids &,
79 const double forward_distance = 20)
const -> std::vector<geometry_msgs::msg::Point>;
84 -> std::optional<std::pair<int, int>>;
86 auto filterLaneletIds(
const lanelet::Ids &,
const char subtype[])
const -> lanelet::Ids;
88 auto generateMarker()
const -> visualization_msgs::msg::MarkerArray;
91 -> std::vector<traffic_simulator_msgs::msg::LaneletPose>;
97 auto getCenterPoints(
const lanelet::Ids &)
const -> std::vector<geometry_msgs::msg::Point>;
99 auto getCenterPoints(
const lanelet::Id)
const -> std::vector<geometry_msgs::msg::Point>;
102 -> std::shared_ptr<math::geometry::CatmullRomSpline>;
105 const geometry_msgs::msg::Pose &,
const double distance_thresh = 30.0,
106 const bool include_crosswalk =
false)
const -> std::optional<lanelet::Id>;
109 const lanelet::Id lanelet_id,
const lanelet::Id crossing_lanelet_id)
const
110 -> std::optional<double>;
117 const lanelet::Ids & route_lanelets,
121 const lanelet::Ids & route_lanelets,
122 const std::vector<geometry_msgs::msg::Point> & waypoints)
const -> std::optional<double>;
125 const lanelet::Ids & route_lanelets,
129 const lanelet::Ids & route_lanelets,
130 const std::vector<geometry_msgs::msg::Point> & waypoints)
const -> std::optional<double>;
134 const lanelet::Id traffic_light_id)
const -> std::optional<double>;
137 const std::vector<geometry_msgs::msg::Point> & waypoints,
138 const lanelet::Id traffic_light_id)
const -> std::optional<double>;
141 const lanelet::Id current_lanelet_id,
const lanelet::Ids & route,
const double horizon = 100,
142 const bool include_current_lanelet_id =
true)
const -> lanelet::Ids;
145 const lanelet::Id,
const double distance = 100,
const bool include_self =
true)
const
151 const geometry_msgs::msg::Pose & from,
153 const double maximum_curvature_threshold,
const double target_trajectory_length,
154 const double forward_distance_threshold)
const
155 -> std::optional<std::pair<math::geometry::HermiteCurve, double>>;
160 -> std::optional<std::pair<math::geometry::HermiteCurve, double>>;
164 -> std::optional<lanelet::Id>;
168 const std::uint8_t shift)
const -> std::optional<lanelet::Id>;
174 auto getLaneletPolygon(
const lanelet::Id)
const -> std::vector<geometry_msgs::msg::Point>;
176 auto getLanelets(
const lanelet::Ids &)
const -> lanelet::Lanelets;
181 -> std::optional<double>;
183 auto getLeftBound(
const lanelet::Id)
const -> std::vector<geometry_msgs::msg::Point>;
187 const bool include_opposite_direction =
true)
const -> lanelet::Ids;
192 const bool allow_lane_change =
false)
const -> std::optional<double>;
195 const geometry_msgs::msg::Point &,
const double distance_threshold,
196 const bool include_crosswalk,
const std::size_t search_count = 5)
const -> lanelet::Ids;
199 const geometry_msgs::msg::Point &,
const double distance_threshold,
200 const std::size_t search_count = 5)
const -> lanelet::Ids;
225 auto getRightBound(
const lanelet::Id)
const -> std::vector<geometry_msgs::msg::Point>;
229 bool include_opposite_direction =
true)
const -> lanelet::Ids;
232 -> std::unordered_map<lanelet::Id, lanelet::Ids>;
236 auto getRoute(
const lanelet::Id from,
const lanelet::Id to,
bool allow_lane_change =
false)
const
245 auto getStopLinePolygon(
const lanelet::Id)
const -> std::vector<geometry_msgs::msg::Point>;
248 -> std::optional<geometry_msgs::msg::Vector3>;
251 -> std::optional<geometry_msgs::msg::Point>;
264 -> std::vector<std::vector<geometry_msgs::msg::Point>>;
267 visualization_msgs::msg::MarkerArray &,
const visualization_msgs::msg::MarkerArray &)
const
270 auto isInLanelet(
const lanelet::Id,
const double s)
const -> bool;
272 auto isInRoute(
const lanelet::Id,
const lanelet::Ids & route)
const -> bool;
279 const geometry_msgs::msg::Pose &,
const traffic_simulator_msgs::msg::BoundingBox &,
280 const bool include_crosswalk,
const double matching_distance = 1.0,
281 const double reduction_ratio = 0.8)
const -> std::optional<lanelet::Id>;
284 const geometry_msgs::msg::Pose &,
const bool include_crosswalk,
285 const double matching_distance = 1.0)
const
286 -> std::optional<traffic_simulator_msgs::msg::LaneletPose>;
289 const geometry_msgs::msg::Pose &,
const lanelet::Ids &,
290 const double matching_distance = 1.0)
const
291 -> std::optional<traffic_simulator_msgs::msg::LaneletPose>;
294 const geometry_msgs::msg::Point &,
const traffic_simulator_msgs::msg::BoundingBox &,
295 const bool include_crosswalk,
const double matching_distance = 1.0)
const
296 -> std::optional<traffic_simulator_msgs::msg::LaneletPose>;
299 const geometry_msgs::msg::Pose &,
const traffic_simulator_msgs::msg::BoundingBox &,
300 const bool include_crosswalk,
const double matching_distance = 1.0)
const
301 -> std::optional<traffic_simulator_msgs::msg::LaneletPose>;
304 const geometry_msgs::msg::Pose &,
const lanelet::Id,
const double matching_distance = 1.0)
const
305 -> std::optional<traffic_simulator_msgs::msg::LaneletPose>;
308 const geometry_msgs::msg::Pose &,
const lanelet::Id,
const double matching_distance = 5.0,
309 const bool include_opposite_direction =
true)
const
310 -> std::vector<traffic_simulator_msgs::msg::LaneletPose>;
312 auto toMapBin()
const -> autoware_auto_mapping_msgs::msg::HADMapBin;
314 auto toMapPoints(
const lanelet::Id,
const std::vector<double> & s)
const
315 -> std::vector<geometry_msgs::msg::Point>;
318 const -> geometry_msgs::msg::PoseStamped;
330 lanelet::LaneletMapPtr lanelet_map_ptr_;
331 lanelet::routing::RoutingGraphConstPtr vehicle_routing_graph_ptr_;
332 lanelet::traffic_rules::TrafficRulesPtr traffic_rules_vehicle_ptr_;
333 lanelet::routing::RoutingGraphConstPtr pedestrian_routing_graph_ptr_;
334 lanelet::traffic_rules::TrafficRulesPtr traffic_rules_pedestrian_ptr_;
335 lanelet::ConstLanelets shoulder_lanelets_;
337 template <
typename Lanelet>
338 auto getLaneletIds(
const std::vector<Lanelet> & lanelets)
const -> lanelet::Ids
342 lanelets.begin(), lanelets.end(), std::back_inserter(ids),
343 [](
const auto & lanelet) { return lanelet.id(); });
348 const lanelet::BasicPolygon2d & relative_hull,
const lanelet::matching::Pose2d &)
const
349 -> lanelet::BasicPolygon2d;
352 const std::vector<double> & x,
const std::vector<double> & y,
353 const std::vector<double> & z)
const -> std::vector<double>;
355 auto calculateAccumulatedLengths(
const lanelet::ConstLineString3d &)
const -> std::vector<double>;
357 auto calculateSegmentDistances(
const lanelet::ConstLineString3d &)
const -> std::vector<double>;
359 auto excludeSubtypeLanelets(
360 const std::vector<std::pair<double, lanelet::Lanelet>> &,
const char subtype[])
const
361 -> std::vector<std::pair<double, lanelet::Lanelet>>;
363 auto filterLanelets(
const lanelet::Lanelets &,
const char subtype[])
const -> lanelet::Lanelets;
365 auto findNearestIndexPair(
366 const std::vector<double> & accumulated_lengths,
const double target_length)
const
367 -> std::pair<std::size_t, std::size_t>;
369 auto generateFineCenterline(
const lanelet::ConstLanelet &,
const double resolution)
const
370 -> lanelet::LineString3d;
377 auto getNextRoadShoulderLanelet(
const lanelet::Id)
const -> lanelet::Ids;
379 auto getPreviousRoadShoulderLanelet(
const lanelet::Id)
const -> lanelet::Ids;
381 auto getStopLines()
const -> lanelet::ConstLineStrings3d;
383 auto getStopLinesOnPath(
const lanelet::Ids &)
const -> lanelet::ConstLineStrings3d;
385 auto getTrafficLightRegulatoryElementsOnPath(
const lanelet::Ids &)
const
386 -> std::vector<std::shared_ptr<const lanelet::autoware::AutowareTrafficLight>>;
388 auto getTrafficLights(
const lanelet::Id traffic_light_id)
const
389 -> std::vector<lanelet::AutowareTrafficLightConstPtr>;
391 auto getTrafficSignRegulatoryElementsOnPath(
const lanelet::Ids &)
const
392 -> std::vector<std::shared_ptr<const lanelet::TrafficSign>>;
394 auto getTrafficSignRegulatoryElements()
const
395 -> std::vector<std::shared_ptr<const lanelet::TrafficSign>>;
397 auto getVectorFromPose(
const geometry_msgs::msg::Pose &,
const double magnitude)
const
398 -> geometry_msgs::msg::Vector3;
400 auto mapCallback(
const autoware_auto_mapping_msgs::msg::HADMapBin &)
const -> void;
402 auto overwriteLaneletsCenterline() -> void;
404 auto resamplePoints(
const lanelet::ConstLineString3d &,
const std::int32_t num_segments)
const
405 -> lanelet::BasicPoints3d;
407 auto toPoint2d(
const geometry_msgs::msg::Point &)
const -> lanelet::BasicPoint2d;
409 auto toPolygon(
const lanelet::ConstLineString3d &)
const
410 -> std::vector<geometry_msgs::msg::Point>;
Definition: hdmap_utils.hpp:62
auto getStopLineIds() const -> lanelet::Ids
Definition: hdmap_utils.cpp:1825
auto getTangentVector(const lanelet::Id, const double s) const -> std::optional< geometry_msgs::msg::Vector3 >
Definition: hdmap_utils.cpp:1482
auto toMapPoints(const lanelet::Id, const std::vector< double > &s) const -> std::vector< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:1439
auto getNextLaneletIds(const lanelet::Ids &) const -> lanelet::Ids
Definition: hdmap_utils.cpp:1081
auto getLateralDistance(const traffic_simulator_msgs::msg::LaneletPose &from, const traffic_simulator_msgs::msg::LaneletPose &to, bool allow_lane_change=false) const -> std::optional< double >
Definition: hdmap_utils.cpp:1496
HdMapUtils(const boost::filesystem::path &, const geographic_msgs::msg::GeoPoint &)
Definition: hdmap_utils.cpp:59
auto matchToLane(const geometry_msgs::msg::Pose &, const traffic_simulator_msgs::msg::BoundingBox &, const bool include_crosswalk, const double matching_distance=1.0, const double reduction_ratio=0.8) const -> std::optional< lanelet::Id >
Definition: hdmap_utils.cpp:533
auto getCenterPointsSpline(const lanelet::Id) const -> std::shared_ptr< math::geometry::CatmullRomSpline >
Definition: hdmap_utils.cpp:929
auto getLeftLaneletIds(const lanelet::Id, const traffic_simulator_msgs::msg::EntityType &, const bool include_opposite_direction=true) const -> lanelet::Ids
Definition: hdmap_utils.cpp:1218
auto getRoute(const lanelet::Id from, const lanelet::Id to, bool allow_lane_change=false) const -> lanelet::Ids
Definition: hdmap_utils.cpp:901
auto getDistanceToTrafficLightStopLine(const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: hdmap_utils.cpp:1950
auto getStopLineIdsOnPath(const lanelet::Ids &route_lanelets) const -> lanelet::Ids
Definition: hdmap_utils.cpp:1834
auto getTrafficLightStopLinesPoints(const lanelet::Id traffic_light_id) const -> std::vector< std::vector< geometry_msgs::msg::Point >>
Definition: hdmap_utils.cpp:1877
auto getCollisionPointInLaneCoordinate(const lanelet::Id lanelet_id, const lanelet::Id crossing_lanelet_id) const -> std::optional< double >
Definition: hdmap_utils.cpp:352
auto getDistanceToStopLine(const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
Definition: hdmap_utils.cpp:2039
auto getTrafficLightIds() const -> lanelet::Ids
Definition: hdmap_utils.cpp:1113
auto isInRoute(const lanelet::Id, const lanelet::Ids &route) const -> bool
Definition: hdmap_utils.cpp:816
auto toLaneletPose(const geometry_msgs::msg::Pose &, const bool include_crosswalk, const double matching_distance=1.0) const -> std::optional< traffic_simulator_msgs::msg::LaneletPose >
Definition: hdmap_utils.cpp:575
auto getRightOfWayLaneletIds(const lanelet::Ids &) const -> std::unordered_map< lanelet::Id, lanelet::Ids >
Definition: hdmap_utils.cpp:1731
auto filterLaneletIds(const lanelet::Ids &, const char subtype[]) const -> lanelet::Ids
Definition: hdmap_utils.cpp:273
auto getLaneChangeableLaneletId(const lanelet::Id, const traffic_simulator::lane_change::Direction) const -> std::optional< lanelet::Id >
Definition: hdmap_utils.cpp:769
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:1342
auto getStopLinePolygon(const lanelet::Id) const -> std::vector< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:1899
auto getHeight(const traffic_simulator_msgs::msg::LaneletPose &) const -> double
Definition: hdmap_utils.cpp:346
auto canonicalizeLaneletPose(const traffic_simulator_msgs::msg::LaneletPose &) const -> std::tuple< std::optional< traffic_simulator_msgs::msg::LaneletPose >, std::optional< lanelet::Id >>
Definition: hdmap_utils.cpp:159
auto getTrafficLightRegulatoryElement(const lanelet::Id) const -> lanelet::TrafficLight::Ptr
Definition: hdmap_utils.cpp:2203
auto canChangeLane(const lanelet::Id from, const lanelet::Id to) const -> bool
Definition: hdmap_utils.cpp:1488
auto getAlongLaneletPose(const traffic_simulator_msgs::msg::LaneletPose &from, const double along) const -> traffic_simulator_msgs::msg::LaneletPose
Definition: hdmap_utils.cpp:1168
auto isTrafficLightRegulatoryElement(const lanelet::Id) const -> bool
Definition: hdmap_utils.cpp:2196
auto getTrafficLightBulbPosition(const lanelet::Id traffic_light_id, const std::string &) const -> std::optional< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:1132
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:435
auto getSpeedLimit(const lanelet::Ids &) const -> double
Definition: hdmap_utils.cpp:731
auto toMapPose(const traffic_simulator_msgs::msg::LaneletPose &, const bool fill_pitch=true) const -> geometry_msgs::msg::PoseStamped
Definition: hdmap_utils.cpp:1450
auto getPreviousLaneletIds(const lanelet::Ids &) const -> lanelet::Ids
Definition: hdmap_utils.cpp:1024
auto getLeftBound(const lanelet::Id) const -> std::vector< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:1206
auto getTrafficLightRegulatoryElementIDsFromTrafficLight(const lanelet::Id) const -> lanelet::Ids
Definition: hdmap_utils.cpp:2211
auto getTrafficLightIdsOnPath(const lanelet::Ids &route_lanelets) const -> lanelet::Ids
Definition: hdmap_utils.cpp:1914
auto getLaneletLength(const lanelet::Id) const -> double
Definition: hdmap_utils.cpp:989
auto getRightBound(const lanelet::Id) const -> std::vector< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:1212
auto getPreviousLanelets(const lanelet::Id, const double backward_horizon=100) const -> lanelet::Ids
Definition: hdmap_utils.cpp:793
auto isTrafficLight(const lanelet::Id) const -> bool
Definition: hdmap_utils.cpp:2182
auto getLaneletIds() const -> lanelet::Ids
Definition: hdmap_utils.cpp:248
auto toLaneletPoses(const geometry_msgs::msg::Pose &, const lanelet::Id, const double matching_distance=5.0, const bool include_opposite_direction=true) const -> std::vector< traffic_simulator_msgs::msg::LaneletPose >
Definition: hdmap_utils.cpp:678
auto getConflictingLaneIds(const lanelet::Ids &) const -> lanelet::Ids
Definition: hdmap_utils.cpp:401
auto generateMarker() const -> visualization_msgs::msg::MarkerArray
Definition: hdmap_utils.cpp:1633
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:699
auto getTrafficLightStopLineIds(const lanelet::Id traffic_light_id) const -> lanelet::Ids
Definition: hdmap_utils.cpp:1865
auto getCenterPoints(const lanelet::Ids &) const -> std::vector< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:936
auto getLaneletPolygon(const lanelet::Id) const -> std::vector< geometry_msgs::msg::Point >
Definition: hdmap_utils.cpp:257
auto countLaneChanges(const traffic_simulator_msgs::msg::LaneletPose &from, const traffic_simulator_msgs::msg::LaneletPose &to, bool allow_lane_change) const -> std::optional< std::pair< int, int >>
Definition: hdmap_utils.cpp:217
auto getFollowingLanelets(const lanelet::Id current_lanelet_id, const lanelet::Ids &route, const double horizon=100, const bool include_current_lanelet_id=true) const -> lanelet::Ids
Definition: hdmap_utils.cpp:821
auto getAllCanonicalizedLaneletPoses(const traffic_simulator_msgs::msg::LaneletPose &) const -> std::vector< traffic_simulator_msgs::msg::LaneletPose >
Definition: hdmap_utils.cpp:93
auto getLongitudinalDistance(const traffic_simulator_msgs::msg::LaneletPose &from_pose, const traffic_simulator_msgs::msg::LaneletPose &to_pose, const bool allow_lane_change=false) const -> std::optional< double >
Definition: hdmap_utils.cpp:1541
auto getRightLaneletIds(lanelet::Id, traffic_simulator_msgs::msg::EntityType, bool include_opposite_direction=true) const -> lanelet::Ids
Definition: hdmap_utils.cpp:1253
auto toMapBin() const -> autoware_auto_mapping_msgs::msg::HADMapBin
Definition: hdmap_utils.cpp:1610
auto getLanelets(const lanelet::Ids &) const -> lanelet::Lanelets
Definition: hdmap_utils.cpp:2173
auto isInLanelet(const lanelet::Id, const double s) const -> bool
Definition: hdmap_utils.cpp:1434
auto getConflictingCrosswalkIds(const lanelet::Ids &) const -> lanelet::Ids
Definition: hdmap_utils.cpp:415
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:308
auto insertMarkerArray(visualization_msgs::msg::MarkerArray &, const visualization_msgs::msg::MarkerArray &) const -> void
Definition: hdmap_utils.cpp:1626
Definition: cache.hpp:127
Definition: catmull_rom_spline_interface.hpp:30
Definition: hermite_curve.hpp:32
LaneletType
Definition: hdmap_utils.hpp:59
auto distance(const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2)
Definition: detection_sensor.cpp:34
TrajectoryShape
Definition: lane_change.hpp:31
Direction
Definition: lane_change.hpp:29
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:22
std::string string
Definition: junit5.hpp:26
traffic_simulator_msgs::EntityType EntityType
Definition: helper_functions.hpp:31
parameters for behavior plugin
Definition: lane_change.hpp:75