File tree 1 file changed +13
-0
lines changed
planning/behavior_path_planner/src/utils
1 file changed +13
-0
lines changed Original file line number Diff line number Diff line change @@ -1586,6 +1586,8 @@ std::vector<lanelet::ConstPoint3d> getBoundWithHatchedRoadMarkings(
1586
1586
} else {
1587
1587
if (!polygon) {
1588
1588
will_close_polygon = true ;
1589
+ } else if (polygon.value ().id () != current_polygon.value ().id ()) {
1590
+ will_close_polygon = true ;
1589
1591
} else {
1590
1592
current_polygon_border_indices.push_back (
1591
1593
get_corresponding_polygon_index (*current_polygon, bound_point.id ()));
@@ -1620,6 +1622,17 @@ std::vector<lanelet::ConstPoint3d> getBoundWithHatchedRoadMarkings(
1620
1622
(*current_polygon)[mod (target_poly_idx, current_polygon_points_num)]);
1621
1623
}
1622
1624
}
1625
+
1626
+ if (polygon.has_value () && current_polygon.has_value ()) {
1627
+ if (polygon.value ().id () != current_polygon.value ().id ()) {
1628
+ current_polygon = polygon;
1629
+ current_polygon_border_indices.clear ();
1630
+ current_polygon_border_indices.push_back (
1631
+ get_corresponding_polygon_index (current_polygon.value (), bound_point.id ()));
1632
+ continue ;
1633
+ }
1634
+ }
1635
+
1623
1636
current_polygon = std::nullopt;
1624
1637
current_polygon_border_indices.clear ();
1625
1638
}
You can’t perform that action at this time.
0 commit comments