File tree 3 files changed +6
-25
lines changed
planning/behavior_path_planner/autoware_behavior_path_lane_change_module
include/autoware/behavior_path_lane_change_module/utils
3 files changed +6
-25
lines changed Original file line number Diff line number Diff line change @@ -121,9 +121,6 @@ std::vector<DrivableLanes> generateDrivableLanes(
121
121
122
122
double getLateralShift (const LaneChangePath & path);
123
123
124
- bool hasEnoughLengthToLaneChangeAfterAbort (
125
- const CommonDataPtr & common_data_ptr, const double abort_return_dist);
126
-
127
124
CandidateOutput assignToCandidate (
128
125
const LaneChangePath & lane_change_path, const Point & ego_position);
129
126
std::optional<lanelet::ConstLanelet> getLaneChangeTargetLane (
Original file line number Diff line number Diff line change @@ -1963,8 +1963,12 @@ bool NormalLaneChange::calcAbortPath()
1963
1963
return false ;
1964
1964
}
1965
1965
1966
- if (!utils::lane_change::hasEnoughLengthToLaneChangeAfterAbort (
1967
- common_data_ptr_, abort_return_dist)) {
1966
+ const auto enough_abort_dist =
1967
+ abort_start_dist + abort_return_dist +
1968
+ calculation::calc_stopping_distance (common_data_ptr_->lc_param_ptr ) <=
1969
+ common_data_ptr_->transient_data .dist_to_terminal_start ;
1970
+
1971
+ if (!enough_abort_dist) {
1968
1972
RCLCPP_ERROR (logger_, " insufficient distance to abort." );
1969
1973
return false ;
1970
1974
}
Original file line number Diff line number Diff line change @@ -548,26 +548,6 @@ double getLateralShift(const LaneChangePath & path)
548
548
return path.shifted_path .shift_length .at (end_idx) - path.shifted_path .shift_length .at (start_idx);
549
549
}
550
550
551
- bool hasEnoughLengthToLaneChangeAfterAbort (
552
- const CommonDataPtr & common_data_ptr, const double abort_return_dist)
553
- {
554
- const auto & current_lanes = common_data_ptr->lanes_ptr ->current ;
555
- if (current_lanes.empty ()) {
556
- return false ;
557
- }
558
-
559
- const auto & current_pose = common_data_ptr->get_ego_pose ();
560
- const auto abort_plus_lane_change_length =
561
- abort_return_dist + common_data_ptr->transient_data .current_dist_buffer .min ;
562
- if (abort_plus_lane_change_length > utils::getDistanceToEndOfLane (current_pose, current_lanes)) {
563
- return false ;
564
- }
565
-
566
- const auto goal_pose = common_data_ptr->route_handler_ptr ->getGoalPose ();
567
- return abort_plus_lane_change_length <=
568
- utils::getSignedDistance (current_pose, goal_pose, current_lanes);
569
- }
570
-
571
551
std::vector<std::vector<int64_t >> getSortedLaneIds (
572
552
const RouteHandler & route_handler, const Pose & current_pose,
573
553
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes)
You can’t perform that action at this time.
0 commit comments