@@ -33,23 +33,33 @@ namespace
33
33
{
34
34
template <class T >
35
35
size_t findNearestSegmentIndexFromLateralDistance (
36
- const std::vector<T> & points, const geometry_msgs::msg::Point & target_point)
36
+ const std::vector<T> & points, const geometry_msgs::msg::Pose & target_point,
37
+ const double yaw_threshold)
37
38
{
39
+ using tier4_autoware_utils::calcAzimuthAngle;
40
+ using tier4_autoware_utils::calcDistance2d;
41
+ using tier4_autoware_utils::normalizeRadian;
42
+
38
43
std::optional<size_t > closest_idx{std::nullopt};
39
44
double min_lateral_dist = std::numeric_limits<double >::max ();
40
45
for (size_t seg_idx = 0 ; seg_idx < points.size () - 1 ; ++seg_idx) {
46
+ const auto base_yaw = tf2::getYaw (target_point.orientation );
47
+ const auto yaw =
48
+ normalizeRadian (calcAzimuthAngle (points.at (seg_idx), points.at (seg_idx + 1 )) - base_yaw);
49
+ if (yaw_threshold < std::abs (yaw)) {
50
+ continue ;
51
+ }
41
52
const double lon_dist =
42
- motion_utils::calcLongitudinalOffsetToSegment (points, seg_idx, target_point);
43
- const double segment_length =
44
- tier4_autoware_utils::calcDistance2d (points.at (seg_idx), points.at (seg_idx + 1 ));
53
+ motion_utils::calcLongitudinalOffsetToSegment (points, seg_idx, target_point.position );
54
+ const double segment_length = calcDistance2d (points.at (seg_idx), points.at (seg_idx + 1 ));
45
55
const double lat_dist = [&]() {
46
56
if (lon_dist < 0.0 ) {
47
- return tier4_autoware_utils:: calcDistance2d (points.at (seg_idx), target_point);
57
+ return calcDistance2d (points.at (seg_idx), target_point. position );
48
58
}
49
59
if (segment_length < lon_dist) {
50
- return tier4_autoware_utils:: calcDistance2d (points.at (seg_idx + 1 ), target_point);
60
+ return calcDistance2d (points.at (seg_idx + 1 ), target_point. position );
51
61
}
52
- return std::abs (motion_utils::calcLateralOffset (points, target_point, seg_idx));
62
+ return std::abs (motion_utils::calcLateralOffset (points, target_point. position , seg_idx));
53
63
}();
54
64
if (lat_dist < min_lateral_dist) {
55
65
closest_idx = seg_idx;
@@ -61,7 +71,7 @@ size_t findNearestSegmentIndexFromLateralDistance(
61
71
return *closest_idx;
62
72
}
63
73
64
- return motion_utils::findNearestSegmentIndex (points, target_point);
74
+ return motion_utils::findNearestSegmentIndex (points, target_point. position );
65
75
}
66
76
67
77
bool checkHasSameLane (
@@ -832,17 +842,17 @@ void generateDrivableArea(
832
842
const auto front_pose =
833
843
cropped_path_points.empty () ? current_pose : cropped_path_points.front ().point .pose ;
834
844
const size_t front_left_start_idx =
835
- findNearestSegmentIndexFromLateralDistance (left_bound, front_pose. position );
845
+ findNearestSegmentIndexFromLateralDistance (left_bound, front_pose, M_PI_2 );
836
846
const size_t front_right_start_idx =
837
- findNearestSegmentIndexFromLateralDistance (right_bound, front_pose. position );
847
+ findNearestSegmentIndexFromLateralDistance (right_bound, front_pose, M_PI_2 );
838
848
const auto left_start_point =
839
849
calcLongitudinalOffsetStartPoint (left_bound, front_pose, front_left_start_idx, -front_length);
840
850
const auto right_start_point = calcLongitudinalOffsetStartPoint (
841
851
right_bound, front_pose, front_right_start_idx, -front_length);
842
852
const size_t left_start_idx =
843
- findNearestSegmentIndexFromLateralDistance (left_bound, left_start_point);
853
+ motion_utils::findNearestSegmentIndex (left_bound, left_start_point);
844
854
const size_t right_start_idx =
845
- findNearestSegmentIndexFromLateralDistance (right_bound, right_start_point);
855
+ motion_utils::findNearestSegmentIndex (right_bound, right_start_point);
846
856
847
857
// Insert a start point
848
858
path.left_bound .push_back (left_start_point);
@@ -854,18 +864,17 @@ void generateDrivableArea(
854
864
// Get Closest segment for the goal point
855
865
const auto goal_pose = path.points .empty () ? current_pose : path.points .back ().point .pose ;
856
866
const size_t goal_left_start_idx =
857
- findNearestSegmentIndexFromLateralDistance (left_bound, goal_pose. position );
867
+ findNearestSegmentIndexFromLateralDistance (left_bound, goal_pose, M_PI_2 );
858
868
const size_t goal_right_start_idx =
859
- findNearestSegmentIndexFromLateralDistance (right_bound, goal_pose. position );
869
+ findNearestSegmentIndexFromLateralDistance (right_bound, goal_pose, M_PI_2 );
860
870
const auto left_goal_point =
861
871
calcLongitudinalOffsetGoalPoint (left_bound, goal_pose, goal_left_start_idx, vehicle_length);
862
872
const auto right_goal_point =
863
873
calcLongitudinalOffsetGoalPoint (right_bound, goal_pose, goal_right_start_idx, vehicle_length);
864
874
const size_t left_goal_idx = std::max (
865
- goal_left_start_idx, findNearestSegmentIndexFromLateralDistance (left_bound, left_goal_point));
875
+ goal_left_start_idx, motion_utils::findNearestSegmentIndex (left_bound, left_goal_point));
866
876
const size_t right_goal_idx = std::max (
867
- goal_right_start_idx,
868
- findNearestSegmentIndexFromLateralDistance (right_bound, right_goal_point));
877
+ goal_right_start_idx, motion_utils::findNearestSegmentIndex (right_bound, right_goal_point));
869
878
870
879
// Insert middle points
871
880
for (size_t i = left_start_idx + 1 ; i <= left_goal_idx; ++i) {
0 commit comments