Skip to content

Commit 09e4351

Browse files
fix(lane_change): delay lane change cancel (autowarefoundation#8048) (for RT0-33952) (#1626)
fix(lane_change): delay lane change cancel (autowarefoundation#8048) RT1-6955: delay lane change cancel Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent f18e714 commit 09e4351

File tree

2 files changed

+24
-6
lines changed

2 files changed

+24
-6
lines changed

planning/behavior_path_lane_change_module/src/scene.cpp

+19-1
Original file line numberDiff line numberDiff line change
@@ -1405,7 +1405,7 @@ bool NormalLaneChange::getLaneChangePaths(
14051405
std::vector<ExtendedPredictedObject> filtered_objects =
14061406
filterObjectsInTargetLane(target_objects, target_lanes);
14071407
if (
1408-
!is_stuck && utils::lane_change::passParkedObject(
1408+
!is_stuck && !utils::lane_change::passParkedObject(
14091409
route_handler, *candidate_path, filtered_objects, lane_change_buffer,
14101410
is_goal_in_route, *lane_change_parameters_, object_debug_)) {
14111411
debug_print(
@@ -1453,6 +1453,24 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
14531453
}
14541454
CollisionCheckDebugMap debug_data;
14551455
const bool is_stuck = isVehicleStuck(current_lanes);
1456+
1457+
const auto & route_handler = *getRouteHandler();
1458+
const auto & lc_param = *lane_change_parameters_;
1459+
1460+
const auto min_lc_length = utils::lane_change::calcMinimumLaneChangeLength(
1461+
*lane_change_parameters_,
1462+
route_handler.getLateralIntervalsToPreferredLane(current_lanes.back()));
1463+
const auto is_goal_in_route = route_handler.isInGoalRouteSection(current_lanes.back());
1464+
1465+
const auto has_passed_parked_objects = utils::lane_change::passParkedObject(
1466+
route_handler, path, target_objects.target_lane, min_lc_length, is_goal_in_route, lc_param,
1467+
debug_data);
1468+
1469+
if (!has_passed_parked_objects) {
1470+
RCLCPP_DEBUG(logger_, "Lane change has been delayed.");
1471+
return {false, false};
1472+
}
1473+
14561474
const auto safety_status = isLaneChangePathSafe(
14571475
path, target_objects, lane_change_parameters_->rss_params_for_abort, is_stuck, debug_data);
14581476
{

planning/behavior_path_lane_change_module/src/utils/utils.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -991,22 +991,22 @@ bool passParkedObject(
991991
route_handler.getCenterLinePath(current_lanes, 0.0, std::numeric_limits<double>::max());
992992

993993
if (objects.empty() || path.points.empty() || current_lane_path.points.empty()) {
994-
return false;
994+
return true;
995995
}
996996

997997
const auto leading_obj_idx = getLeadingStaticObjectIdx(
998998
route_handler, lane_change_path, objects, object_check_min_road_shoulder_width,
999999
object_shiftable_ratio_threshold);
10001000
if (!leading_obj_idx) {
1001-
return false;
1001+
return true;
10021002
}
10031003

10041004
const auto & leading_obj = objects.at(*leading_obj_idx);
10051005
auto debug = utils::path_safety_checker::createObjectDebug(leading_obj);
10061006
const auto leading_obj_poly =
10071007
tier4_autoware_utils::toPolygon2d(leading_obj.initial_pose.pose, leading_obj.shape);
10081008
if (leading_obj_poly.outer().empty()) {
1009-
return false;
1009+
return true;
10101010
}
10111011

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

1034-
return false;
1034+
return true;
10351035
}
10361036

10371037
std::optional<size_t> getLeadingStaticObjectIdx(

0 commit comments

Comments
 (0)