@@ -1257,32 +1257,45 @@ bool AvoidanceModule::isValidShiftLine(
1257
1257
}
1258
1258
}
1259
1259
1260
+ const auto is_return_shift =
1261
+ [](const double start_shift_length, const double end_shift_length, const double threshold) {
1262
+ return std::abs (start_shift_length) > threshold && std::abs (end_shift_length) < threshold;
1263
+ };
1264
+
1260
1265
// check if the vehicle is in road. (yaw angle is not considered)
1261
1266
{
1262
1267
const auto minimum_distance = 0.5 * planner_data_->parameters .vehicle_width +
1263
1268
parameters_->hard_road_shoulder_margin -
1264
1269
parameters_->max_deviation_from_lane ;
1265
1270
1266
- const size_t start_idx = shift_lines.front ().start_idx ;
1267
- const size_t end_idx = shift_lines.back ().end_idx ;
1271
+ for (const auto & shift_line : shift_lines) {
1272
+ const size_t start_idx = shift_line.start_idx ;
1273
+ const size_t end_idx = shift_line.end_idx ;
1268
1274
1269
- const auto path = shifter_for_validate.getReferencePath ();
1270
- const auto left_bound = lanelet::utils::to2D (toLineString3d (avoid_data_.left_bound ));
1271
- const auto right_bound = lanelet::utils::to2D (toLineString3d (avoid_data_.right_bound ));
1272
- for (size_t i = start_idx; i <= end_idx; ++i) {
1273
- const auto p = getPoint (path.points .at (i));
1274
- lanelet::BasicPoint2d basic_point{p.x , p.y };
1275
-
1276
- const auto shift_length = proposed_shift_path.shift_length .at (i);
1277
- const auto THRESHOLD = minimum_distance + std::abs (shift_length);
1275
+ if (is_return_shift (
1276
+ shift_line.start_shift_length , shift_line.end_shift_length ,
1277
+ parameters_->lateral_small_shift_threshold )) {
1278
+ continue ;
1279
+ }
1278
1280
1279
- if (
1280
- boost::geometry::distance (basic_point, (shift_length > 0.0 ? left_bound : right_bound)) <
1281
- THRESHOLD) {
1282
- RCLCPP_DEBUG_THROTTLE (
1283
- getLogger (), *clock_, 1000 ,
1284
- " following latest new shift line may cause deviation from drivable area." );
1285
- return false ;
1281
+ const auto path = shifter_for_validate.getReferencePath ();
1282
+ const auto left_bound = lanelet::utils::to2D (toLineString3d (avoid_data_.left_bound ));
1283
+ const auto right_bound = lanelet::utils::to2D (toLineString3d (avoid_data_.right_bound ));
1284
+ for (size_t i = start_idx; i <= end_idx; ++i) {
1285
+ const auto p = getPoint (path.points .at (i));
1286
+ lanelet::BasicPoint2d basic_point{p.x , p.y };
1287
+
1288
+ const auto shift_length = proposed_shift_path.shift_length .at (i);
1289
+ const auto THRESHOLD = minimum_distance + std::abs (shift_length);
1290
+
1291
+ if (
1292
+ boost::geometry::distance (basic_point, (shift_length > 0.0 ? left_bound : right_bound)) <
1293
+ THRESHOLD) {
1294
+ RCLCPP_DEBUG_THROTTLE (
1295
+ getLogger (), *clock_, 1000 ,
1296
+ " following latest new shift line may cause deviation from drivable area." );
1297
+ return false ;
1298
+ }
1286
1299
}
1287
1300
}
1288
1301
}
0 commit comments