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 466ecf6b8f..89eb19594f 100644 --- a/planning/autoware_path_generator/include/autoware/path_generator/utils.hpp +++ b/planning/autoware_path_generator/include/autoware/path_generator/utils.hpp @@ -101,6 +101,30 @@ std::vector>> get_wa const lanelet::LaneletSequence & lanelet_sequence, const lanelet::LaneletMap & lanelet_map, const double group_separation_threshold, const double interval_margin_ratio); +/** + * @brief get position of first self-intersection (point where return + * path intersects outward path) of lanelet sequence in arc length + * @param lanelet_sequence target lanelet sequence (both left and right bound are + * considered) + * @param s_start longitudinal distance of point to start searching for self-intersections + * @param s_end longitudinal distance of point to end search + * @return longitudinal distance of self-intersecting point (std::nullopt if no + * self-intersection) + */ +std::optional get_first_self_intersection_arc_length( + const lanelet::LaneletSequence & lanelet_sequence, const double s_start, const double s_end); + +/** + * @brief get position of first self-intersection of line string in arc length + * @param line_string target line string + * @param s_start longitudinal distance of point to start searching for self-intersections + * @param s_end longitudinal distance of point to end search + * @return longitudinal distance of self-intersecting point (std::nullopt if no + * self-intersection) + */ +std::optional get_first_self_intersection_arc_length( + const lanelet::BasicLineString2d & line_string, const double s_start, const double s_end); + /** * @brief get bound of path cropped within specified range * @param lanelet_bound original bound of lanelet diff --git a/planning/autoware_path_generator/src/node.cpp b/planning/autoware_path_generator/src/node.cpp index b869491aad..ada61f4f97 100644 --- a/planning/autoware_path_generator/src/node.cpp +++ b/planning/autoware_path_generator/src/node.cpp @@ -245,6 +245,12 @@ std::optional PathGenerator::generate_path( s_end = std::min(s_end, goal_arc_coordinates.length); } + if ( + const auto s_intersection = + utils::get_first_self_intersection_arc_length(lanelet_sequence, s_start, s_end)) { + s_end = std::clamp(s_end, 0.0, *s_intersection - vehicle_info_.max_longitudinal_offset_m); + } + return s_end; }(); diff --git a/planning/autoware_path_generator/src/utils.cpp b/planning/autoware_path_generator/src/utils.cpp index de993907ac..0c8c636913 100644 --- a/planning/autoware_path_generator/src/utils.cpp +++ b/planning/autoware_path_generator/src/utils.cpp @@ -166,6 +166,50 @@ std::optional get_next_lanelet_within_route( return *next_lanelet_itr; } +std::optional get_first_self_intersection_arc_length( + const lanelet::LaneletSequence & lanelet_sequence, const double s_start, const double s_end) +{ + const auto s_left = get_first_self_intersection_arc_length( + lanelet_sequence.leftBound2d().basicLineString(), s_start, s_end); + const auto s_right = get_first_self_intersection_arc_length( + lanelet_sequence.rightBound2d().basicLineString(), s_start, s_end); + + if (s_left && s_right) { + return std::min(*s_left, *s_right); + } + return s_left ? s_left : s_right; +} + +std::optional get_first_self_intersection_arc_length( + const lanelet::BasicLineString2d & line_string, const double s_start, const double s_end) +{ + const auto tree = lanelet::geometry::internal::makeIndexedSegmenTree(line_string); + std::optional> last_intersection = std::nullopt; + auto s = 0.; + + for (size_t i = 1; i < line_string.size() - 1; ++i) { + if (last_intersection && i == last_intersection->first) { + return s + last_intersection->second; + } + s += lanelet::geometry::distance2d(line_string.at(i - 1), line_string.at(i)); + if (s < s_start) { + continue; + } + if (s > s_end) { + break; + } + const auto self_intersections = lanelet::geometry::internal::getSelfIntersectionsAt( + tree, 0, lanelet::BasicSegment2d{line_string.at(i - 1), line_string.at(i)}); + if (self_intersections.empty()) { + continue; + } + last_intersection = { + self_intersections.front().lastSegment.idx, self_intersections.front().lastSegment.s}; + } + + return std::nullopt; +} + std::vector>> get_waypoint_groups( const lanelet::LaneletSequence & lanelet_sequence, const lanelet::LaneletMap & lanelet_map, const double group_separation_threshold, const double interval_margin_ratio)