@@ -366,7 +366,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough() const
366
366
const auto & current_pose = planner_data_->self_odometry ->pose .pose ;
367
367
std::vector<Pose> preventing_check_pose{current_pose};
368
368
const auto min_stop_distance =
369
- autoware:: behavior_path_planner::utils::parking_departure::calcFeasibleDecelDistance (
369
+ behavior_path_planner::utils::parking_departure::calcFeasibleDecelDistance (
370
370
planner_data_, parameters_->maximum_deceleration_for_stop , parameters_->maximum_jerk_for_stop ,
371
371
0.0 );
372
372
debug_data_.estimated_stop_pose .reset (); // debug
@@ -500,7 +500,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough(const Pose &
500
500
// Check backwards just in case the Vehicle behind ego is in a different lanelet
501
501
constexpr double backwards_length = 200.0 ;
502
502
const auto prev_lanes = behavior_path_planner::utils::getBackwardLanelets (
503
- *route_handler, target_lanes, current_pose , backwards_length);
503
+ *route_handler, target_lanes, ego_pose , backwards_length);
504
504
// return all the relevant lanelets
505
505
lanelet::ConstLanelets relevant_lanelets{closest_lanelet_const};
506
506
relevant_lanelets.insert (relevant_lanelets.end (), prev_lanes.begin (), prev_lanes.end ());
@@ -527,7 +527,7 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough(const Pose &
527
527
target_objects_on_lane.on_current_lane .begin (), target_objects_on_lane.on_current_lane .end (),
528
528
[&](const auto & o) {
529
529
const auto arc_length = motion_utils::calcSignedArcLength (
530
- centerline_path.points , current_pose .position , o.initial_pose .pose .position );
530
+ centerline_path.points , ego_pose .position , o.initial_pose .pose .position );
531
531
if (arc_length > 0.0 ) return ;
532
532
if (std::abs (arc_length) >= std::abs (arc_length_to_closet_object)) return ;
533
533
arc_length_to_closet_object = arc_length;
0 commit comments