31
31
32
32
namespace
33
33
{
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
+
34
70
template <class T >
35
71
size_t findNearestSegmentIndexFromLateralDistance (
36
72
const std::vector<T> & points, const geometry_msgs::msg::Pose & target_point,
@@ -850,9 +886,9 @@ void generateDrivableArea(
850
886
const auto right_start_point = calcLongitudinalOffsetStartPoint (
851
887
right_bound, front_pose, front_right_start_idx, -front_length);
852
888
const size_t left_start_idx =
853
- motion_utils::findNearestSegmentIndex (left_bound, left_start_point);
889
+ findNearestSegmentIndexFromLateralDistance (left_bound, left_start_point);
854
890
const size_t right_start_idx =
855
- motion_utils::findNearestSegmentIndex (right_bound, right_start_point);
891
+ findNearestSegmentIndexFromLateralDistance (right_bound, right_start_point);
856
892
857
893
// Insert a start point
858
894
path.left_bound .push_back (left_start_point);
@@ -872,9 +908,10 @@ void generateDrivableArea(
872
908
const auto right_goal_point =
873
909
calcLongitudinalOffsetGoalPoint (right_bound, goal_pose, goal_right_start_idx, vehicle_length);
874
910
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));
876
912
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));
878
915
879
916
// Insert middle points
880
917
for (size_t i = left_start_idx + 1 ; i <= left_goal_idx; ++i) {
0 commit comments