@@ -334,11 +334,13 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const
334
334
auto get_gap_between_ego_and_lane_border =
335
335
[&](
336
336
geometry_msgs::msg::Pose & ego_overhang_point_as_pose,
337
- const bool ego_is_merging_from_the_left) -> std::optional<double > {
337
+ const bool ego_is_merging_from_the_left) -> std::optional<std::pair< double , double > > {
338
338
const auto local_vehicle_footprint = vehicle_info_.createFootprint ();
339
339
const auto vehicle_footprint =
340
340
transformVector (local_vehicle_footprint, tier4_autoware_utils::pose2transform (current_pose));
341
341
double smallest_lateral_gap_between_ego_and_border = std::numeric_limits<double >::max ();
342
+ double corresponding_lateral_gap_with_other_lane_bound = std::numeric_limits<double >::max ();
343
+
342
344
for (const auto & point : vehicle_footprint) {
343
345
geometry_msgs::msg::Pose point_pose;
344
346
point_pose.position .x = point.x ();
@@ -349,29 +351,48 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const
349
351
lanelet::utils::query::getClosestLanelet (target_lanes, point_pose, &closest_lanelet);
350
352
lanelet::ConstLanelet closest_lanelet_const (closest_lanelet.constData ());
351
353
352
- const lanelet::ConstLineString2d current_lane_bound = (ego_is_merging_from_the_left)
353
- ? closest_lanelet_const.rightBound2d ()
354
- : closest_lanelet_const.leftBound2d ();
354
+ const auto [current_lane_bound, other_side_lane_bound] =
355
+ (ego_is_merging_from_the_left)
356
+ ? std::make_pair (
357
+ closest_lanelet_const.rightBound2d (), closest_lanelet_const.leftBound2d ())
358
+ : std::make_pair (
359
+ closest_lanelet_const.leftBound2d (), closest_lanelet_const.rightBound2d ());
355
360
const double current_point_lateral_gap =
356
361
calc_absolute_lateral_offset (current_lane_bound, point_pose);
357
362
if (current_point_lateral_gap < smallest_lateral_gap_between_ego_and_border) {
358
363
smallest_lateral_gap_between_ego_and_border = current_point_lateral_gap;
359
364
ego_overhang_point_as_pose.position .x = point.x ();
360
365
ego_overhang_point_as_pose.position .y = point.y ();
361
366
ego_overhang_point_as_pose.position .z = 0.0 ;
367
+ corresponding_lateral_gap_with_other_lane_bound =
368
+ calc_absolute_lateral_offset (other_side_lane_bound, point_pose);
362
369
}
363
370
}
371
+
364
372
if (smallest_lateral_gap_between_ego_and_border == std::numeric_limits<double >::max ()) {
365
373
return std::nullopt;
366
374
}
367
- return smallest_lateral_gap_between_ego_and_border;
375
+ return std::make_pair (
376
+ (smallest_lateral_gap_between_ego_and_border),
377
+ (corresponding_lateral_gap_with_other_lane_bound));
368
378
};
369
379
370
380
geometry_msgs::msg::Pose ego_overhang_point_as_pose;
371
- const auto gap_between_ego_and_lane_border =
381
+ const auto gaps_with_lane_borders_pair =
372
382
get_gap_between_ego_and_lane_border (ego_overhang_point_as_pose, ego_is_merging_from_the_left);
373
- if (!gap_between_ego_and_lane_border) return false ;
374
383
384
+ if (!gaps_with_lane_borders_pair.has_value ()) {
385
+ return false ;
386
+ }
387
+
388
+ const auto & gap_between_ego_and_lane_border = gaps_with_lane_borders_pair.value ().first ;
389
+ const auto & corresponding_lateral_gap_with_other_lane_bound =
390
+ gaps_with_lane_borders_pair.value ().second ;
391
+
392
+ // middle of the lane is crossed, no need to check for collisions anymore
393
+ if (gap_between_ego_and_lane_border < corresponding_lateral_gap_with_other_lane_bound) {
394
+ return true ;
395
+ }
375
396
// Get the lanelets that will be queried for target objects
376
397
const auto relevant_lanelets = std::invoke ([&]() -> std::optional<lanelet::ConstLanelets> {
377
398
lanelet::Lanelet closest_lanelet;
@@ -421,7 +442,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const
421
442
if (!closest_object_width) return false ;
422
443
// Decide if the closest object does not fit in the gap left by the ego vehicle.
423
444
return closest_object_width.value () + parameters_->extra_width_margin_for_rear_obstacle >
424
- gap_between_ego_and_lane_border. value () ;
445
+ gap_between_ego_and_lane_border;
425
446
}
426
447
427
448
bool StartPlannerModule::isCloseToOriginalStartPose () const
0 commit comments