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>
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 std::filesystem::path &,
const geographic_msgs::msg::GeoPoint &);
69 const lanelet::Id from,
const lanelet::Id to,
79 auto generateMarker()
const -> visualization_msgs::msg::MarkerArray;
81 auto getCenterPoints(
const lanelet::Ids &)
const -> std::vector<geometry_msgs::msg::Point>;
83 auto getCenterPoints(
const lanelet::Id)
const -> std::vector<geometry_msgs::msg::Point>;
86 -> std::shared_ptr<math::geometry::CatmullRomSpline>;
89 const lanelet::Id current_lanelet_id,
const lanelet::Ids &
route,
const double horizon = 100,
90 const bool include_current_lanelet_id =
true,
95 const lanelet::Id,
const double distance = 100,
const bool include_self =
true,
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>>;
109 -> std::optional<std::pair<math::geometry::HermiteCurve, double>>;
115 -> std::optional<lanelet::Id>;
121 -> std::optional<lanelet::Id>;
125 auto getLanelets(
const lanelet::Ids &)
const -> lanelet::Lanelets;
128 const lanelet::Id,
const double backward_horizon = 100,
133 const lanelet::Id from,
const lanelet::Id to,
143 -> std::optional<geometry_msgs::msg::Vector3>;
146 const lanelet::Id traffic_light_id,
const std::string &,
147 const bool allow_infer_position =
false)
const -> std::optional<geometry_msgs::msg::Point>;
160 -> std::vector<std::vector<geometry_msgs::msg::Point>>;
163 visualization_msgs::msg::MarkerArray &,
const visualization_msgs::msg::MarkerArray &)
const
166 auto isInRoute(
const lanelet::Id,
const lanelet::Ids &
route)
const -> bool;
175 constexpr
static double DEFAULT_MATCH_TO_LANE_REDUCTION_RATIO = 0.8;
185 lanelet::LaneletMapPtr lanelet_map_ptr_;
190 explicit RoutingGraphs(
const lanelet::LaneletMapPtr & lanelet_map);
194 lanelet::traffic_rules::TrafficRulesPtr
rules;
195 lanelet::routing::RoutingGraphPtr
graph;
199 [[nodiscard]] lanelet::routing::RoutingGraphPtr routing_graph(
202 [[nodiscard]] lanelet::traffic_rules::TrafficRulesPtr traffic_rule(
206 const lanelet::Id from_lanelet_id,
const lanelet::Id to_lanelet_id,
207 lanelet::LaneletMapPtr lanelet_map_ptr,
221 std::unique_ptr<RoutingGraphs> routing_graphs_;
223 template <
typename Lanelet>
224 auto getLaneletIds(
const std::vector<Lanelet> & lanelets)
const -> lanelet::Ids
228 lanelets.begin(), lanelets.end(), std::back_inserter(ids),
229 [](
const auto & lanelet) { return lanelet.id(); });
233 auto calculateAccumulatedLengths(
const lanelet::ConstLineString3d &)
const -> std::vector<double>;
235 auto calculateSegmentDistances(
const lanelet::ConstLineString3d &)
const -> std::vector<double>;
237 auto excludeSubtypeLanelets(
238 const std::vector<std::pair<double, lanelet::Lanelet>> &,
const char subtype[])
const
239 -> std::vector<std::pair<double, lanelet::Lanelet>>;
241 auto findNearestIndexPair(
242 const std::vector<double> & accumulated_lengths,
const double target_length)
const
243 -> std::pair<std::size_t, std::size_t>;
245 auto generateFineCenterline(
const lanelet::ConstLanelet &,
const double resolution)
const
246 -> lanelet::LineString3d;
251 const double tangent_vector_size = 100) const ->
math::geometry::HermiteCurve;
253 auto getTrafficLightRegulatoryElementsOnPath(const lanelet::Ids &) const
254 ->
std::vector<
std::shared_ptr<const lanelet::
autoware::AutowareTrafficLight>>;
256 auto getTrafficLights(const lanelet::Id traffic_light_id) const
257 ->
std::vector<lanelet::AutowareTrafficLightConstPtr>;
259 auto getTrafficSignRegulatoryElementsOnPath(const lanelet::Ids &) const
260 ->
std::vector<
std::shared_ptr<const lanelet::TrafficSign>>;
262 auto getTrafficSignRegulatoryElements() const
263 ->
std::vector<
std::shared_ptr<const lanelet::TrafficSign>>;
265 auto getVectorFromPose(const geometry_msgs::msg::
Pose &, const
double magnitude) const
266 -> geometry_msgs::msg::
Vector3;
268 auto resamplePoints(const lanelet::ConstLineString3d &, const
std::int32_t num_segments) const
269 -> lanelet::BasicPoints3d;
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: sim_model_delay_steer_acc_geared_wo_fall_guard.hpp:26
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
Definition: hdmap_utils.hpp:193
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