Skip to content
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.

Commit 789831b

Browse files
committedMar 8, 2024
fix(static_drivable_area_expansion): fix drivable bound edge process (autowarefoundation#6014)
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent e83a825 commit 789831b

File tree

1 file changed

+41
-4
lines changed

1 file changed

+41
-4
lines changed
 

‎planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp

+41-4
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,42 @@
3131

3232
namespace
3333
{
34+
template <class T>
35+
size_t findNearestSegmentIndexFromLateralDistance(
36+
const std::vector<T> & points, const geometry_msgs::msg::Point & target_point)
37+
{
38+
using tier4_autoware_utils::calcAzimuthAngle;
39+
using tier4_autoware_utils::calcDistance2d;
40+
using tier4_autoware_utils::normalizeRadian;
41+
42+
std::optional<size_t> closest_idx{std::nullopt};
43+
double min_lateral_dist = std::numeric_limits<double>::max();
44+
for (size_t seg_idx = 0; seg_idx < points.size() - 1; ++seg_idx) {
45+
const double lon_dist =
46+
motion_utils::calcLongitudinalOffsetToSegment(points, seg_idx, target_point);
47+
const double segment_length = calcDistance2d(points.at(seg_idx), points.at(seg_idx + 1));
48+
const double lat_dist = [&]() {
49+
if (lon_dist < 0.0) {
50+
return calcDistance2d(points.at(seg_idx), target_point);
51+
}
52+
if (segment_length < lon_dist) {
53+
return calcDistance2d(points.at(seg_idx + 1), target_point);
54+
}
55+
return std::abs(motion_utils::calcLateralOffset(points, target_point, seg_idx));
56+
}();
57+
if (lat_dist < min_lateral_dist) {
58+
closest_idx = seg_idx;
59+
min_lateral_dist = lat_dist;
60+
}
61+
}
62+
63+
if (closest_idx) {
64+
return *closest_idx;
65+
}
66+
67+
return motion_utils::findNearestSegmentIndex(points, target_point);
68+
}
69+
3470
template <class T>
3571
size_t findNearestSegmentIndexFromLateralDistance(
3672
const std::vector<T> & points, const geometry_msgs::msg::Pose & target_point,
@@ -850,9 +886,9 @@ void generateDrivableArea(
850886
const auto right_start_point = calcLongitudinalOffsetStartPoint(
851887
right_bound, front_pose, front_right_start_idx, -front_length);
852888
const size_t left_start_idx =
853-
motion_utils::findNearestSegmentIndex(left_bound, left_start_point);
889+
findNearestSegmentIndexFromLateralDistance(left_bound, left_start_point);
854890
const size_t right_start_idx =
855-
motion_utils::findNearestSegmentIndex(right_bound, right_start_point);
891+
findNearestSegmentIndexFromLateralDistance(right_bound, right_start_point);
856892

857893
// Insert a start point
858894
path.left_bound.push_back(left_start_point);
@@ -872,9 +908,10 @@ void generateDrivableArea(
872908
const auto right_goal_point =
873909
calcLongitudinalOffsetGoalPoint(right_bound, goal_pose, goal_right_start_idx, vehicle_length);
874910
const size_t left_goal_idx = std::max(
875-
goal_left_start_idx, motion_utils::findNearestSegmentIndex(left_bound, left_goal_point));
911+
goal_left_start_idx, findNearestSegmentIndexFromLateralDistance(left_bound, left_goal_point));
876912
const size_t right_goal_idx = std::max(
877-
goal_right_start_idx, motion_utils::findNearestSegmentIndex(right_bound, right_goal_point));
913+
goal_right_start_idx,
914+
findNearestSegmentIndexFromLateralDistance(right_bound, right_goal_point));
878915

879916
// Insert middle points
880917
for (size_t i = left_start_idx + 1; i <= left_goal_idx; ++i) {

0 commit comments

Comments
 (0)
Please sign in to comment.