Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(lane_change): delay lane change cancel (#8048) (for RT0-33952) #1626

Merged
merged 1 commit into from
Nov 7, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
20 changes: 19 additions & 1 deletion planning/behavior_path_lane_change_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1375,7 +1375,7 @@ bool NormalLaneChange::getLaneChangePaths(
std::vector<ExtendedPredictedObject> filtered_objects =
filterObjectsInTargetLane(target_objects, target_lanes);
if (
!is_stuck && utils::lane_change::passParkedObject(
!is_stuck && !utils::lane_change::passParkedObject(
route_handler, *candidate_path, filtered_objects, lane_change_buffer,
is_goal_in_route, *lane_change_parameters_, object_debug_)) {
debug_print(
Expand Down Expand Up @@ -1417,6 +1417,24 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const

CollisionCheckDebugMap debug_data;
const bool is_stuck = isVehicleStuck(current_lanes);

const auto & route_handler = *getRouteHandler();
const auto & lc_param = *lane_change_parameters_;

const auto min_lc_length = utils::lane_change::calcMinimumLaneChangeLength(
*lane_change_parameters_,
route_handler.getLateralIntervalsToPreferredLane(current_lanes.back()));
const auto is_goal_in_route = route_handler.isInGoalRouteSection(current_lanes.back());

const auto has_passed_parked_objects = utils::lane_change::passParkedObject(
route_handler, path, target_objects.target_lane, min_lc_length, is_goal_in_route, lc_param,
debug_data);

if (!has_passed_parked_objects) {
RCLCPP_DEBUG(logger_, "Lane change has been delayed.");
return {false, false};
}

const auto safety_status = isLaneChangePathSafe(
path, target_objects, lane_change_parameters_->rss_params_for_abort, is_stuck, debug_data);
{
Expand Down
10 changes: 5 additions & 5 deletions planning/behavior_path_lane_change_module/src/utils/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -991,22 +991,22 @@ bool passParkedObject(
route_handler.getCenterLinePath(current_lanes, 0.0, std::numeric_limits<double>::max());

if (objects.empty() || path.points.empty() || current_lane_path.points.empty()) {
return false;
return true;
}

const auto leading_obj_idx = getLeadingStaticObjectIdx(
route_handler, lane_change_path, objects, object_check_min_road_shoulder_width,
object_shiftable_ratio_threshold);
if (!leading_obj_idx) {
return false;
return true;
}

const auto & leading_obj = objects.at(*leading_obj_idx);
auto debug = utils::path_safety_checker::createObjectDebug(leading_obj);
const auto leading_obj_poly =
tier4_autoware_utils::toPolygon2d(leading_obj.initial_pose.pose, leading_obj.shape);
if (leading_obj_poly.outer().empty()) {
return false;
return true;
}

const auto & current_path_end = current_lane_path.points.back().point.pose.position;
Expand All @@ -1028,10 +1028,10 @@ bool passParkedObject(
if (min_dist_to_end_of_current_lane > minimum_lane_change_length) {
debug.second.unsafe_reason = "delay lane change";
utils::path_safety_checker::updateCollisionCheckDebugMap(object_debug, debug, false);
return true;
return false;
}

return false;
return true;
}

std::optional<size_t> getLeadingStaticObjectIdx(
Expand Down
Loading