Skip to content

Commit f9429d0

Browse files
authored
Merge branch 'beta/v0.11.2' into cherry-pick-planning-validator
2 parents cd51962 + 110b9ce commit f9429d0

File tree

1 file changed

+11
-1
lines changed

1 file changed

+11
-1
lines changed

planning/behavior_path_planner/src/utils/drivable_area_expansion/drivable_area_expansion.cpp

+11-1
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,17 @@ void reuse_previous_poses(
5151
prev_poses, 0, ego_point) < 0.0;
5252
const auto ego_is_far = !prev_poses.empty() &&
5353
tier4_autoware_utils::calcDistance2d(ego_point, prev_poses.front()) < 0.0;
54-
if (!ego_is_behind && !ego_is_far && prev_poses.size() > 1) {
54+
// make sure the reused points are not behind the current original drivable area
55+
LineString2d left_bound;
56+
LineString2d right_bound;
57+
for (const auto & p : path.left_bound) left_bound.push_back(convert_point(p));
58+
for (const auto & p : path.right_bound) right_bound.push_back(convert_point(p));
59+
LineString2d prev_poses_ls;
60+
for (const auto & p : prev_poses) prev_poses_ls.push_back(convert_point(p.position));
61+
auto prev_poses_across_bounds = boost::geometry::intersects(left_bound, prev_poses_ls) ||
62+
boost::geometry::intersects(right_bound, prev_poses_ls);
63+
64+
if (!ego_is_behind && !ego_is_far && prev_poses.size() > 1 && !prev_poses_across_bounds) {
5565
const auto first_idx =
5666
motion_utils::findNearestSegmentIndex(prev_poses, path.points.front().point.pose);
5767
const auto deviation =

0 commit comments

Comments
 (0)