From 76bc7fa1233f408c9e01ae64f356fc1ad4742158 Mon Sep 17 00:00:00 2001 From: mitukou1109 Date: Fri, 28 Mar 2025 14:58:15 +0900 Subject: [PATCH 1/2] avoid using fixed-size array Signed-off-by: mitukou1109 --- .../include/autoware/path_generator/utils.hpp | 16 +++++---- .../autoware_path_generator/src/utils.cpp | 33 +++++++++---------- 2 files changed, 24 insertions(+), 25 deletions(-) diff --git a/planning/autoware_path_generator/include/autoware/path_generator/utils.hpp b/planning/autoware_path_generator/include/autoware/path_generator/utils.hpp index 5d6666f51..180d3a1a6 100644 --- a/planning/autoware_path_generator/include/autoware/path_generator/utils.hpp +++ b/planning/autoware_path_generator/include/autoware/path_generator/utils.hpp @@ -34,10 +34,12 @@ using autoware_internal_planning_msgs::msg::PathPointWithLaneId; using autoware_internal_planning_msgs::msg::PathWithLaneId; using autoware_vehicle_msgs::msg::TurnIndicatorsCommand; -const std::unordered_map turn_signal_command_map = { - {"left", TurnIndicatorsCommand::ENABLE_LEFT}, - {"right", TurnIndicatorsCommand::ENABLE_RIGHT}, - {"straight", TurnIndicatorsCommand::DISABLE}}; +template +struct PathRange +{ + T left; + T right; +}; namespace utils { @@ -142,7 +144,7 @@ std::optional get_first_self_intersection_arc_length( * @param s_end longitudinal distance of end of bound on centerline * @return cropped bounds (left / right) */ -std::array, 2> get_path_bounds( +PathRange> get_path_bounds( const lanelet::LaneletSequence & lanelet_sequence, const double s_start, const double s_end); /** @@ -162,7 +164,7 @@ std::vector crop_line_string( * @param s_centerline longitudinal distance of point on centerline * @return longitudinal distance of projected point (left / right) */ -std::array get_arc_length_on_bounds( +PathRange get_arc_length_on_bounds( const lanelet::LaneletSequence & lanelet_sequence, const double s_centerline); /** @@ -172,7 +174,7 @@ std::array get_arc_length_on_bounds( * @param s_right_bound longitudinal distance of point on left bound * @return longitudinal distance of projected point (left / right) */ -std::array, 2> get_arc_length_on_centerline( +PathRange> get_arc_length_on_centerline( const lanelet::LaneletSequence & lanelet_sequence, const std::optional & s_left_bound, const std::optional & s_right_bound); diff --git a/planning/autoware_path_generator/src/utils.cpp b/planning/autoware_path_generator/src/utils.cpp index 9bfa33dae..0947b55bc 100644 --- a/planning/autoware_path_generator/src/utils.cpp +++ b/planning/autoware_path_generator/src/utils.cpp @@ -40,6 +40,11 @@ namespace utils { namespace { +const std::unordered_map turn_signal_command_map = { + {"left", TurnIndicatorsCommand::ENABLE_LEFT}, + {"right", TurnIndicatorsCommand::ENABLE_RIGHT}, + {"straight", TurnIndicatorsCommand::DISABLE}}; + template bool exists(const std::vector & vec, const T & item) { @@ -244,13 +249,11 @@ std::optional get_first_intersection_arc_length( { std::optional s_intersection{std::nullopt}; - const auto s_start_bounds = get_arc_length_on_bounds(lanelet_sequence, s_start); - const double s_start_left_bound = s_start_bounds.at(0); - const double s_start_right_bound = s_start_bounds.at(1); + const auto [s_start_left_bound, s_start_right_bound] = + get_arc_length_on_bounds(lanelet_sequence, s_start); - const auto s_end_bound = get_arc_length_on_bounds(lanelet_sequence, s_end); - const double s_end_left_bound = s_end_bound.at(0); - const double s_end_right_bound = s_end_bound.at(1); + const auto [s_end_left_bound, s_end_right_bound] = + get_arc_length_on_bounds(lanelet_sequence, s_end); const auto cropped_centerline = lanelet::utils::to2D(to_lanelet_points(crop_line_string( to_geometry_msgs_points( @@ -285,10 +288,8 @@ std::optional get_first_intersection_arc_length( return s; }(); - const auto s_bounds_on_centerline = + const auto [s_left, s_right] = get_arc_length_on_centerline(lanelet_sequence, s_left_bound, s_right_bound); - const auto s_left = s_bounds_on_centerline.at(0); - const auto s_right = s_bounds_on_centerline.at(1); if (s_left && s_right) { s_intersection = std::min(s_left, s_right); @@ -302,14 +303,12 @@ std::optional get_first_intersection_arc_length( lanelet::BasicPoints2d intersections; boost::geometry::intersection(cropped_left_bound, cropped_right_bound, intersections); for (const auto & intersection : intersections) { - const auto s_bounds_on_centerline = get_arc_length_on_centerline( + const auto [s_left, s_right] = get_arc_length_on_centerline( lanelet_sequence, s_start_left_bound + lanelet::geometry::toArcCoordinates(cropped_left_bound, intersection).length, s_start_right_bound + lanelet::geometry::toArcCoordinates(cropped_right_bound, intersection).length); - const auto s_left = s_bounds_on_centerline.at(0); - const auto s_right = s_bounds_on_centerline.at(1); const auto s_mutual = [&]() { if (s_left && s_right) { return std::max(s_left, s_right); @@ -358,10 +357,8 @@ std::optional get_first_intersection_arc_length( return s; }(); - const auto s_bounds_on_centerline = + const auto [s_left, s_right] = get_arc_length_on_centerline(lanelet_sequence, s_left_bound, s_right_bound); - const auto s_left = s_bounds_on_centerline.at(0); - const auto s_right = s_bounds_on_centerline.at(1); const auto s_start_edge = [&]() { if (s_left && s_right) { @@ -427,7 +424,7 @@ std::optional get_first_self_intersection_arc_length( return std::nullopt; } -std::array, 2> get_path_bounds( +PathRange> get_path_bounds( const lanelet::LaneletSequence & lanelet_sequence, const double s_start, const double s_end) { const auto [s_left_start, s_right_start] = get_arc_length_on_bounds(lanelet_sequence, s_start); @@ -455,7 +452,7 @@ std::vector crop_line_string( return trajectory->restore(); } -std::array get_arc_length_on_bounds( +PathRange get_arc_length_on_bounds( const lanelet::LaneletSequence & lanelet_sequence, const double s_centerline) { auto s = 0.; @@ -487,7 +484,7 @@ std::array get_arc_length_on_bounds( return {s_centerline, s_centerline}; } -std::array, 2> get_arc_length_on_centerline( +PathRange> get_arc_length_on_centerline( const lanelet::LaneletSequence & lanelet_sequence, const std::optional & s_left_bound, const std::optional & s_right_bound) { From bb3edc758b58a1679319abae6d0e1c9a6fc659f1 Mon Sep 17 00:00:00 2001 From: mitukou1109 Date: Thu, 3 Apr 2025 15:16:48 +0900 Subject: [PATCH 2/2] include necessary headers Signed-off-by: mitukou1109 --- .../include/autoware/path_generator/utils.hpp | 2 -- planning/autoware_path_generator/src/utils.cpp | 2 ++ 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/autoware_path_generator/include/autoware/path_generator/utils.hpp b/planning/autoware_path_generator/include/autoware/path_generator/utils.hpp index 180d3a1a6..83c932a9a 100644 --- a/planning/autoware_path_generator/include/autoware/path_generator/utils.hpp +++ b/planning/autoware_path_generator/include/autoware/path_generator/utils.hpp @@ -23,8 +23,6 @@ #include #include #include -#include -#include #include #include diff --git a/planning/autoware_path_generator/src/utils.cpp b/planning/autoware_path_generator/src/utils.cpp index 0947b55bc..5c6d6fffd 100644 --- a/planning/autoware_path_generator/src/utils.cpp +++ b/planning/autoware_path_generator/src/utils.cpp @@ -31,6 +31,8 @@ #include #include #include +#include +#include #include #include