Skip to content

Commit

Permalink
refactor(goal_planner): rename shoulder_lane to pull_over_lane (autow…
Browse files Browse the repository at this point in the history
…arefoundation#9422)

Signed-off-by: kosuke55 <[email protected]>
  • Loading branch information
kosuke55 committed Nov 22, 2024
1 parent fb15603 commit 179c125
Show file tree
Hide file tree
Showing 4 changed files with 20 additions and 20 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ class ShiftPullOver : public PullOverPlannerBase
std::optional<PathWithLaneId> cropPrevModulePath(
const PathWithLaneId & prev_module_path, const Pose & shift_end_pose) const;
std::optional<PullOverPath> generatePullOverPath(
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes,
const Pose & goal_pose, const double lateral_jerk) const;
static double calcBeforeShiftedArcLength(
const PathWithLaneId & path, const double after_shifted_arc_length, const double dr);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ std::optional<PathWithLaneId> ShiftPullOver::cropPrevModulePath(
}

std::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes,
const Pose & goal_pose, const double lateral_jerk) const
{
const double pull_over_velocity = parameters_.pull_over_velocity;
Expand Down Expand Up @@ -216,7 +216,7 @@ std::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
p.point.longitudinal_velocity_mps = 0.0;
p.point.pose = goal_pose;
p.lane_ids = shifted_path.path.points.back().lane_ids;
for (const auto & lane : shoulder_lanes) {
for (const auto & lane : pull_over_lanes) {
p.lane_ids.push_back(lane.id());
}
shifted_path.path.points.push_back(p);
Expand All @@ -238,7 +238,7 @@ std::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
}
}
// add shoulder lane_id if not found
for (const auto & lane : shoulder_lanes) {
for (const auto & lane : pull_over_lanes) {
if (
std::find(point.lane_ids.begin(), point.lane_ids.end(), lane.id()) ==
point.lane_ids.end()) {
Expand Down Expand Up @@ -285,7 +285,7 @@ std::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
});
const bool is_in_lanes = std::invoke([&]() -> bool {
const auto drivable_lanes =
utils::generateDrivableLanesWithShoulderLanes(road_lanes, shoulder_lanes);
utils::generateDrivableLanesWithShoulderLanes(road_lanes, pull_over_lanes);
const auto & dp = planner_data_->drivable_area_expansion_parameters;
const auto expanded_lanes = utils::expandLanelets(
drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,11 +70,11 @@ class GeometricParallelParking
bool isParking() const;
bool planPullOver(
const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes,
const lanelet::ConstLanelets & shoulder_lanes, const bool is_forward,
const lanelet::ConstLanelets & pull_over_lanes, const bool is_forward,
const bool left_side_parking);
bool planPullOut(
const Pose & start_pose, const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes,
const lanelet::ConstLanelets & shoulder_lanes, const bool left_side_start,
const lanelet::ConstLanelets & pull_over_lanes, const bool left_side_start,
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
autoware_lane_departure_checker);
void setParameters(const ParallelParkingParameters & parameters) { parameters_ = parameters; }
Expand Down Expand Up @@ -117,7 +117,7 @@ class GeometricParallelParking
void clearPaths();
std::vector<PathWithLaneId> planOneTrial(
const Pose & start_pose, const Pose & goal_pose, const double R_E_far,
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes,
const bool is_forward, const bool left_side_parking, const double end_pose_offset,
const double lane_departure_margin, const double arc_path_interval,
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
Expand All @@ -134,7 +134,7 @@ class GeometricParallelParking
const bool left_side_parking);
std::vector<PathWithLaneId> generatePullOverPaths(
const Pose & start_pose, const Pose & goal_pose, const double R_E_far,
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes,
const bool is_forward, const bool left_side_parking, const double end_pose_offset,
const double velocity);
PathWithLaneId generateStraightPath(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ void GeometricParallelParking::setVelocityToArcPaths(

std::vector<PathWithLaneId> GeometricParallelParking::generatePullOverPaths(
const Pose & start_pose, const Pose & goal_pose, const double R_E_far,
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes,
const bool is_forward, const bool left_side_parking, const double end_pose_offset,
const double velocity)
{
Expand All @@ -117,7 +117,7 @@ std::vector<PathWithLaneId> GeometricParallelParking::generatePullOverPaths(
const double arc_path_interval = is_forward ? parameters_.forward_parking_path_interval
: parameters_.backward_parking_path_interval;
auto arc_paths = planOneTrial(
start_pose, goal_pose, R_E_far, road_lanes, shoulder_lanes, is_forward, left_side_parking,
start_pose, goal_pose, R_E_far, road_lanes, pull_over_lanes, is_forward, left_side_parking,
end_pose_offset, lane_departure_margin, arc_path_interval, {});
if (arc_paths.empty()) {
return std::vector<PathWithLaneId>{};
Expand Down Expand Up @@ -158,7 +158,7 @@ void GeometricParallelParking::clearPaths()

bool GeometricParallelParking::planPullOver(
const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes,
const lanelet::ConstLanelets & shoulder_lanes, const bool is_forward,
const lanelet::ConstLanelets & pull_over_lanes, const bool is_forward,
const bool left_side_parking)
{
const auto & common_params = planner_data_->parameters;
Expand Down Expand Up @@ -188,7 +188,7 @@ bool GeometricParallelParking::planPullOver(
}

const auto paths = generatePullOverPaths(
*start_pose, goal_pose, R_E_far, road_lanes, shoulder_lanes, is_forward, left_side_parking,
*start_pose, goal_pose, R_E_far, road_lanes, pull_over_lanes, is_forward, left_side_parking,
end_pose_offset, parameters_.forward_parking_velocity);
if (!paths.empty()) {
paths_ = paths;
Expand All @@ -210,8 +210,8 @@ bool GeometricParallelParking::planPullOver(
}

const auto paths = generatePullOverPaths(
*start_pose, goal_pose, R_E_min_, road_lanes, shoulder_lanes, is_forward, left_side_parking,
end_pose_offset, parameters_.backward_parking_velocity);
*start_pose, goal_pose, R_E_min_, road_lanes, pull_over_lanes, is_forward,
left_side_parking, end_pose_offset, parameters_.backward_parking_velocity);
if (!paths.empty()) {
paths_ = paths;
return true;
Expand All @@ -224,7 +224,7 @@ bool GeometricParallelParking::planPullOver(

bool GeometricParallelParking::planPullOut(
const Pose & start_pose, const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes,
const lanelet::ConstLanelets & shoulder_lanes, const bool left_side_start,
const lanelet::ConstLanelets & pull_over_lanes, const bool left_side_start,
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
lane_departure_checker)
{
Expand All @@ -244,7 +244,7 @@ bool GeometricParallelParking::planPullOut(

// plan reverse path of parking. end_pose <-> start_pose
auto arc_paths = planOneTrial(
*end_pose, start_pose, R_E_min_, road_lanes, shoulder_lanes, is_forward, left_side_start,
*end_pose, start_pose, R_E_min_, road_lanes, pull_over_lanes, is_forward, left_side_start,
start_pose_offset, parameters_.pull_out_lane_departure_margin,
parameters_.pull_out_arc_path_interval, lane_departure_checker);
if (arc_paths.empty()) {
Expand Down Expand Up @@ -376,7 +376,7 @@ PathWithLaneId GeometricParallelParking::generateStraightPath(

std::vector<PathWithLaneId> GeometricParallelParking::planOneTrial(
const Pose & start_pose, const Pose & goal_pose, const double R_E_far,
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes,
const bool is_forward, const bool left_side_parking, const double end_pose_offset,
const double lane_departure_margin, const double arc_path_interval,
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
Expand Down Expand Up @@ -421,15 +421,15 @@ std::vector<PathWithLaneId> GeometricParallelParking::planOneTrial(
}
lanes.push_back(lane);
}
lanes.insert(lanes.end(), shoulder_lanes.begin(), shoulder_lanes.end());
lanes.insert(lanes.end(), pull_over_lanes.begin(), pull_over_lanes.end());

// If start_pose is parallel to goal_pose, we can know lateral deviation of edges of vehicle,
// and detect lane departure.
if (is_forward) { // Check near bound
const double R_front_near =
std::hypot(R_E_far + common_params.vehicle_width / 2, common_params.base_link2front);
const double distance_to_near_bound =
utils::getSignedDistanceFromBoundary(shoulder_lanes, arc_end_pose, left_side_parking);
utils::getSignedDistanceFromBoundary(pull_over_lanes, arc_end_pose, left_side_parking);
const double near_deviation = R_front_near - R_E_far;
if (std::abs(distance_to_near_bound) - near_deviation < lane_departure_margin) {
return std::vector<PathWithLaneId>{};
Expand Down

0 comments on commit 179c125

Please sign in to comment.