Skip to content

Commit

Permalink
feat(start_planner): run start planner even if ego is out of lane (au…
Browse files Browse the repository at this point in the history
…towarefoundation#4895)

Signed-off-by: kosuke55 <[email protected]>
  • Loading branch information
kosuke55 authored Sep 5, 2023
1 parent dec3d06 commit 23851b6
Showing 1 changed file with 0 additions and 20 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -136,26 +136,6 @@ bool StartPlannerModule::isExecutionRequested() const
return false;
}

// Create vehicle footprint
const auto local_vehicle_footprint = createVehicleFootprint(vehicle_info_);
const auto vehicle_footprint = transformVector(
local_vehicle_footprint,
tier4_autoware_utils::pose2transform(planner_data_->self_odometry->pose.pose));

// Check if ego is not out of lanes
const double backward_path_length =
planner_data_->parameters.backward_path_length + parameters_->max_back_distance;
const auto current_lanes = utils::getExtendedCurrentLanes(
planner_data_, backward_path_length, std::numeric_limits<double>::max(),
/*forward_only_in_route*/ true);
const auto pull_out_lanes =
start_planner_utils::getPullOutLanes(planner_data_, backward_path_length);
const auto lanes = utils::combineLanelets(current_lanes, pull_out_lanes);

if (LaneDepartureChecker::isOutOfLane(lanes, vehicle_footprint)) {
return false;
}

return true;
}

Expand Down

0 comments on commit 23851b6

Please sign in to comment.