Skip to content

Commit ecbd383

Browse files
fix(lane_change): fix abort distance enough check (autowarefoundation#8979)
* RT1-7991 fix abort distance enough check Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> * RT-7991 remove unused function Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp> --------- Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent ad36fc1 commit ecbd383

File tree

4 files changed

+16
-57
lines changed

4 files changed

+16
-57
lines changed

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_planner_module.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -1542,8 +1542,7 @@ BehaviorModuleOutput GoalPlannerModule::planPullOverAsOutput()
15421542

15431543
// return to lane parking if it is possible
15441544
if (
1545-
is_freespace &&
1546-
thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE &&
1545+
is_freespace && thread_safe_data_.getPullOverPlannerType() == PullOverPlannerType::FREESPACE &&
15471546
canReturnToLaneParking()) {
15481547
thread_safe_data_.set_pull_over_path(thread_safe_data_.get_lane_parking_pull_over_path());
15491548
}

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp

-11
Original file line numberDiff line numberDiff line change
@@ -141,17 +141,6 @@ std::vector<DrivableLanes> generateDrivableLanes(
141141

142142
double getLateralShift(const LaneChangePath & path);
143143

144-
bool hasEnoughLengthToLaneChangeAfterAbort(
145-
const std::shared_ptr<RouteHandler> & route_handler, const lanelet::ConstLanelets & current_lanes,
146-
const Pose & curent_pose, const double abort_return_dist,
147-
const LaneChangeParameters & lane_change_parameters, const Direction direction);
148-
149-
double calcLateralBufferForFiltering(const double vehicle_width, const double lateral_buffer = 0.0);
150-
151-
double calcLateralBufferForFiltering(const double vehicle_width, const double lateral_buffer);
152-
153-
std::string getStrDirection(const std::string & name, const Direction direction);
154-
155144
CandidateOutput assignToCandidate(
156145
const LaneChangePath & lane_change_path, const Point & ego_position);
157146
std::optional<lanelet::ConstLanelet> getLaneChangeTargetLane(

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

+15-3
Original file line numberDiff line numberDiff line change
@@ -2034,9 +2034,21 @@ bool NormalLaneChange::calcAbortPath()
20342034
return false;
20352035
}
20362036

2037-
if (!utils::lane_change::hasEnoughLengthToLaneChangeAfterAbort(
2038-
route_handler, reference_lanelets, current_pose, abort_return_dist,
2039-
*lane_change_parameters_, direction)) {
2037+
const auto dist_to_terminal_start = std::invoke([&]() {
2038+
const auto dist_to_terminal_end = calculation::calc_dist_from_pose_to_terminal_end(
2039+
common_data_ptr_, get_current_lanes(), common_data_ptr_->get_ego_pose());
2040+
const auto min_lc_length = utils::lane_change::calcMinimumLaneChangeLength(
2041+
route_handler, get_current_lanes().back(), *common_data_ptr_->lc_param_ptr,
2042+
common_data_ptr_->direction);
2043+
return dist_to_terminal_end - min_lc_length;
2044+
});
2045+
2046+
const auto enough_abort_dist =
2047+
abort_start_dist + abort_return_dist +
2048+
calculation::calc_stopping_distance(common_data_ptr_->lc_param_ptr) <=
2049+
dist_to_terminal_start;
2050+
2051+
if (!enough_abort_dist) {
20402052
RCLCPP_ERROR(logger_, "insufficient distance to abort.");
20412053
return false;
20422054
}

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp

-41
Original file line numberDiff line numberDiff line change
@@ -644,47 +644,6 @@ double getLateralShift(const LaneChangePath & path)
644644
return path.shifted_path.shift_length.at(end_idx) - path.shifted_path.shift_length.at(start_idx);
645645
}
646646

647-
bool hasEnoughLengthToLaneChangeAfterAbort(
648-
const std::shared_ptr<RouteHandler> & route_handler, const lanelet::ConstLanelets & current_lanes,
649-
const Pose & current_pose, const double abort_return_dist,
650-
const LaneChangeParameters & lane_change_parameters, const Direction direction)
651-
{
652-
if (current_lanes.empty()) {
653-
return false;
654-
}
655-
656-
const auto minimum_lane_change_length = calcMinimumLaneChangeLength(
657-
route_handler, current_lanes.back(), lane_change_parameters, direction);
658-
const auto abort_plus_lane_change_length = abort_return_dist + minimum_lane_change_length;
659-
if (abort_plus_lane_change_length > utils::getDistanceToEndOfLane(current_pose, current_lanes)) {
660-
return false;
661-
}
662-
663-
if (
664-
abort_plus_lane_change_length >
665-
utils::getSignedDistance(current_pose, route_handler->getGoalPose(), current_lanes)) {
666-
return false;
667-
}
668-
669-
return true;
670-
}
671-
672-
double calcLateralBufferForFiltering(const double vehicle_width, const double lateral_buffer)
673-
{
674-
return lateral_buffer + 0.5 * vehicle_width;
675-
}
676-
677-
std::string getStrDirection(const std::string & name, const Direction direction)
678-
{
679-
if (direction == Direction::LEFT) {
680-
return name + "_left";
681-
}
682-
if (direction == Direction::RIGHT) {
683-
return name + "_right";
684-
}
685-
return "";
686-
}
687-
688647
std::vector<std::vector<int64_t>> getSortedLaneIds(
689648
const RouteHandler & route_handler, const Pose & current_pose,
690649
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes)

0 commit comments

Comments
 (0)