File tree 1 file changed +11
-1
lines changed
planning/behavior_path_planner/src/utils/drivable_area_expansion
1 file changed +11
-1
lines changed Original file line number Diff line number Diff line change @@ -51,7 +51,17 @@ void reuse_previous_poses(
51
51
prev_poses, 0 , ego_point) < 0.0 ;
52
52
const auto ego_is_far = !prev_poses.empty () &&
53
53
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) {
55
65
const auto first_idx =
56
66
motion_utils::findNearestSegmentIndex (prev_poses, path.points .front ().point .pose );
57
67
const auto deviation =
You can’t perform that action at this time.
0 commit comments