@@ -398,11 +398,13 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const
398
398
auto get_gap_between_ego_and_lane_border =
399
399
[&](
400
400
geometry_msgs::msg::Pose & ego_overhang_point_as_pose,
401
- const bool ego_is_merging_from_the_left) -> std::optional<double > {
401
+ const bool ego_is_merging_from_the_left) -> std::optional<std::pair< double , double > > {
402
402
const auto local_vehicle_footprint = vehicle_info_.createFootprint ();
403
403
const auto vehicle_footprint =
404
404
transformVector (local_vehicle_footprint, tier4_autoware_utils::pose2transform (current_pose));
405
405
double smallest_lateral_gap_between_ego_and_border = std::numeric_limits<double >::max ();
406
+ double corresponding_lateral_gap_with_other_lane_bound = std::numeric_limits<double >::max ();
407
+
406
408
for (const auto & point : vehicle_footprint) {
407
409
geometry_msgs::msg::Pose point_pose;
408
410
point_pose.position .x = point.x ();
@@ -413,29 +415,48 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const
413
415
lanelet::utils::query::getClosestLanelet (target_lanes, point_pose, &closest_lanelet);
414
416
lanelet::ConstLanelet closest_lanelet_const (closest_lanelet.constData ());
415
417
416
- const lanelet::ConstLineString2d current_lane_bound = (ego_is_merging_from_the_left)
417
- ? closest_lanelet_const.rightBound2d ()
418
- : closest_lanelet_const.leftBound2d ();
418
+ const auto [current_lane_bound, other_side_lane_bound] =
419
+ (ego_is_merging_from_the_left)
420
+ ? std::make_pair (
421
+ closest_lanelet_const.rightBound2d (), closest_lanelet_const.leftBound2d ())
422
+ : std::make_pair (
423
+ closest_lanelet_const.leftBound2d (), closest_lanelet_const.rightBound2d ());
419
424
const double current_point_lateral_gap =
420
425
calc_absolute_lateral_offset (current_lane_bound, point_pose);
421
426
if (current_point_lateral_gap < smallest_lateral_gap_between_ego_and_border) {
422
427
smallest_lateral_gap_between_ego_and_border = current_point_lateral_gap;
423
428
ego_overhang_point_as_pose.position .x = point.x ();
424
429
ego_overhang_point_as_pose.position .y = point.y ();
425
430
ego_overhang_point_as_pose.position .z = 0.0 ;
431
+ corresponding_lateral_gap_with_other_lane_bound =
432
+ calc_absolute_lateral_offset (other_side_lane_bound, point_pose);
426
433
}
427
434
}
435
+
428
436
if (smallest_lateral_gap_between_ego_and_border == std::numeric_limits<double >::max ()) {
429
437
return std::nullopt;
430
438
}
431
- return smallest_lateral_gap_between_ego_and_border;
439
+ return std::make_pair (
440
+ (smallest_lateral_gap_between_ego_and_border),
441
+ (corresponding_lateral_gap_with_other_lane_bound));
432
442
};
433
443
434
444
geometry_msgs::msg::Pose ego_overhang_point_as_pose;
435
- const auto gap_between_ego_and_lane_border =
445
+ const auto gaps_with_lane_borders_pair =
436
446
get_gap_between_ego_and_lane_border (ego_overhang_point_as_pose, ego_is_merging_from_the_left);
437
- if (!gap_between_ego_and_lane_border) return false ;
438
447
448
+ if (!gaps_with_lane_borders_pair.has_value ()) {
449
+ return false ;
450
+ }
451
+
452
+ const auto & gap_between_ego_and_lane_border = gaps_with_lane_borders_pair.value ().first ;
453
+ const auto & corresponding_lateral_gap_with_other_lane_bound =
454
+ gaps_with_lane_borders_pair.value ().second ;
455
+
456
+ // middle of the lane is crossed, no need to check for collisions anymore
457
+ if (gap_between_ego_and_lane_border < corresponding_lateral_gap_with_other_lane_bound) {
458
+ return true ;
459
+ }
439
460
// Get the lanelets that will be queried for target objects
440
461
const auto relevant_lanelets = std::invoke ([&]() -> std::optional<lanelet::ConstLanelets> {
441
462
lanelet::Lanelet closest_lanelet;
@@ -485,7 +506,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const
485
506
if (!closest_object_width) return false ;
486
507
// Decide if the closest object does not fit in the gap left by the ego vehicle.
487
508
return closest_object_width.value () + parameters_->extra_width_margin_for_rear_obstacle >
488
- gap_between_ego_and_lane_border. value () ;
509
+ gap_between_ego_and_lane_border;
489
510
}
490
511
491
512
bool StartPlannerModule::isCloseToOriginalStartPose () const
0 commit comments