@@ -83,8 +83,17 @@ std::pair<bool, bool> NormalLaneChange::getSafePath(LaneChangePath & safe_path)
83
83
84
84
// find candidate paths
85
85
LaneChangePaths valid_paths{};
86
- const auto found_safe_path =
87
- getLaneChangePaths (current_lanes, target_lanes, direction_, &valid_paths);
86
+ const bool is_stuck = isVehicleStuckByObstacle (current_lanes);
87
+ bool found_safe_path = getLaneChangePaths (
88
+ current_lanes, target_lanes, direction_, &valid_paths, lane_change_parameters_->rss_params ,
89
+ is_stuck);
90
+ // if no safe path is found and ego is stuck, try to find a path with a small margin
91
+ if (!found_safe_path && is_stuck) {
92
+ found_safe_path = getLaneChangePaths (
93
+ current_lanes, target_lanes, direction_, &valid_paths,
94
+ lane_change_parameters_->rss_params_for_stuck , is_stuck);
95
+ }
96
+
88
97
debug_valid_path_ = valid_paths;
89
98
90
99
if (valid_paths.empty ()) {
@@ -1006,7 +1015,9 @@ bool NormalLaneChange::hasEnoughLengthToIntersection(
1006
1015
1007
1016
bool NormalLaneChange::getLaneChangePaths (
1008
1017
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & target_lanes,
1009
- Direction direction, LaneChangePaths * candidate_paths, const bool check_safety) const
1018
+ Direction direction, LaneChangePaths * candidate_paths,
1019
+ const utils::path_safety_checker::RSSparams rss_params, const bool is_stuck,
1020
+ const bool check_safety) const
1010
1021
{
1011
1022
object_debug_.clear ();
1012
1023
if (current_lanes.empty () || target_lanes.empty ()) {
@@ -1237,9 +1248,11 @@ bool NormalLaneChange::getLaneChangePaths(
1237
1248
}
1238
1249
1239
1250
candidate_paths->push_back (*candidate_path);
1240
- if (utils::lane_change::passParkedObject (
1241
- route_handler, *candidate_path, target_objects.target_lane , lane_change_buffer,
1242
- is_goal_in_route, *lane_change_parameters_, object_debug_)) {
1251
+ if (
1252
+ !is_stuck &&
1253
+ utils::lane_change::passParkedObject (
1254
+ route_handler, *candidate_path, target_objects.target_lane , lane_change_buffer,
1255
+ is_goal_in_route, *lane_change_parameters_, object_debug_)) {
1243
1256
return false ;
1244
1257
}
1245
1258
@@ -1248,7 +1261,7 @@ bool NormalLaneChange::getLaneChangePaths(
1248
1261
}
1249
1262
1250
1263
const auto [is_safe, is_object_coming_from_rear] = isLaneChangePathSafe (
1251
- *candidate_path, target_objects, lane_change_parameters_-> rss_params , object_debug_);
1264
+ *candidate_path, target_objects, rss_params, is_stuck , object_debug_);
1252
1265
1253
1266
if (is_safe) {
1254
1267
return true ;
@@ -1270,8 +1283,9 @@ PathSafetyStatus NormalLaneChange::isApprovedPathSafe() const
1270
1283
debug_filtered_objects_ = target_objects;
1271
1284
1272
1285
CollisionCheckDebugMap debug_data;
1286
+ const bool is_stuck = isVehicleStuckByObstacle (current_lanes);
1273
1287
const auto safety_status = isLaneChangePathSafe (
1274
- path, target_objects, lane_change_parameters_->rss_params_for_abort , debug_data);
1288
+ path, target_objects, lane_change_parameters_->rss_params_for_abort , is_stuck, debug_data);
1275
1289
{
1276
1290
// only for debug purpose
1277
1291
object_debug_.clear ();
@@ -1528,7 +1542,7 @@ bool NormalLaneChange::getAbortPath()
1528
1542
1529
1543
PathSafetyStatus NormalLaneChange::isLaneChangePathSafe (
1530
1544
const LaneChangePath & lane_change_path, const LaneChangeTargetObjects & target_objects,
1531
- const utils::path_safety_checker::RSSparams & rss_params,
1545
+ const utils::path_safety_checker::RSSparams & rss_params, const bool is_stuck,
1532
1546
CollisionCheckDebugMap & debug_data) const
1533
1547
{
1534
1548
PathSafetyStatus path_safety_status;
@@ -1552,7 +1566,6 @@ PathSafetyStatus NormalLaneChange::isLaneChangePathSafe(
1552
1566
1553
1567
auto collision_check_objects = target_objects.target_lane ;
1554
1568
const auto current_lanes = getCurrentLanes ();
1555
- const auto is_stuck = isVehicleStuckByObstacle (current_lanes);
1556
1569
1557
1570
if (lane_change_parameters_->check_objects_on_current_lanes || is_stuck) {
1558
1571
collision_check_objects.insert (
0 commit comments