Skip to content

Commit 60dbc46

Browse files
authoredNov 21, 2024··
refactor(goal_planner): rename shoulder_lane to pull_over_lane (#9422)
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent 74ca3ab commit 60dbc46

File tree

4 files changed

+20
-20
lines changed

4 files changed

+20
-20
lines changed
 

‎planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/include/autoware/behavior_path_goal_planner_module/pull_over_planner/shift_pull_over.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ class ShiftPullOver : public PullOverPlannerBase
5050
const GoalCandidate & goal_candidate, const size_t id,
5151
const std::shared_ptr<const PlannerData> planner_data,
5252
const BehaviorModuleOutput & previous_module_output, const lanelet::ConstLanelets & road_lanes,
53-
const lanelet::ConstLanelets & shoulder_lanes, const double lateral_jerk) const;
53+
const lanelet::ConstLanelets & pull_over_lanes, const double lateral_jerk) const;
5454
static double calcBeforeShiftedArcLength(
5555
const PathWithLaneId & path, const double after_shifted_arc_length, const double dr);
5656
static std::vector<double> splineTwoPoints(

‎planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -132,7 +132,7 @@ std::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
132132
const GoalCandidate & goal_candidate, const size_t id,
133133
const std::shared_ptr<const PlannerData> planner_data,
134134
const BehaviorModuleOutput & previous_module_output, const lanelet::ConstLanelets & road_lanes,
135-
const lanelet::ConstLanelets & shoulder_lanes, const double lateral_jerk) const
135+
const lanelet::ConstLanelets & pull_over_lanes, const double lateral_jerk) const
136136
{
137137
const double pull_over_velocity = parameters_.pull_over_velocity;
138138
const double after_shift_straight_distance = parameters_.after_shift_straight_distance;
@@ -224,7 +224,7 @@ std::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
224224
p.point.longitudinal_velocity_mps = 0.0;
225225
p.point.pose = goal_pose;
226226
p.lane_ids = shifted_path.path.points.back().lane_ids;
227-
for (const auto & lane : shoulder_lanes) {
227+
for (const auto & lane : pull_over_lanes) {
228228
p.lane_ids.push_back(lane.id());
229229
}
230230
shifted_path.path.points.push_back(p);
@@ -246,7 +246,7 @@ std::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
246246
}
247247
}
248248
// add shoulder lane_id if not found
249-
for (const auto & lane : shoulder_lanes) {
249+
for (const auto & lane : pull_over_lanes) {
250250
if (
251251
std::find(point.lane_ids.begin(), point.lane_ids.end(), lane.id()) ==
252252
point.lane_ids.end()) {
@@ -294,7 +294,7 @@ std::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
294294
});
295295
const bool is_in_lanes = std::invoke([&]() -> bool {
296296
const auto drivable_lanes =
297-
utils::generateDrivableLanesWithShoulderLanes(road_lanes, shoulder_lanes);
297+
utils::generateDrivableLanesWithShoulderLanes(road_lanes, pull_over_lanes);
298298
const auto & dp = planner_data->drivable_area_expansion_parameters;
299299
const auto expanded_lanes = utils::expandLanelets(
300300
drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset,

‎planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/parking_departure/geometric_parallel_parking.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -70,11 +70,11 @@ class GeometricParallelParking
7070
bool isParking() const;
7171
bool planPullOver(
7272
const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes,
73-
const lanelet::ConstLanelets & shoulder_lanes, const bool is_forward,
73+
const lanelet::ConstLanelets & pull_over_lanes, const bool is_forward,
7474
const bool left_side_parking);
7575
bool planPullOut(
7676
const Pose & start_pose, const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes,
77-
const lanelet::ConstLanelets & shoulder_lanes, const bool left_side_start,
77+
const lanelet::ConstLanelets & pull_over_lanes, const bool left_side_start,
7878
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
7979
autoware_lane_departure_checker);
8080
void setParameters(const ParallelParkingParameters & parameters) { parameters_ = parameters; }
@@ -117,7 +117,7 @@ class GeometricParallelParking
117117
void clearPaths();
118118
std::vector<PathWithLaneId> planOneTrial(
119119
const Pose & start_pose, const Pose & goal_pose, const double R_E_far,
120-
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
120+
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes,
121121
const bool is_forward, const bool left_side_parking, const double end_pose_offset,
122122
const double lane_departure_margin, const double arc_path_interval,
123123
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
@@ -134,7 +134,7 @@ class GeometricParallelParking
134134
const bool left_side_parking);
135135
std::vector<PathWithLaneId> generatePullOverPaths(
136136
const Pose & start_pose, const Pose & goal_pose, const double R_E_far,
137-
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
137+
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes,
138138
const bool is_forward, const bool left_side_parking, const double end_pose_offset,
139139
const double velocity);
140140
PathWithLaneId generateStraightPath(

‎planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/parking_departure/geometric_parallel_parking.cpp

+11-11
Original file line numberDiff line numberDiff line change
@@ -105,7 +105,7 @@ void GeometricParallelParking::setVelocityToArcPaths(
105105

106106
std::vector<PathWithLaneId> GeometricParallelParking::generatePullOverPaths(
107107
const Pose & start_pose, const Pose & goal_pose, const double R_E_far,
108-
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
108+
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes,
109109
const bool is_forward, const bool left_side_parking, const double end_pose_offset,
110110
const double velocity)
111111
{
@@ -115,7 +115,7 @@ std::vector<PathWithLaneId> GeometricParallelParking::generatePullOverPaths(
115115
const double arc_path_interval = is_forward ? parameters_.forward_parking_path_interval
116116
: parameters_.backward_parking_path_interval;
117117
auto arc_paths = planOneTrial(
118-
start_pose, goal_pose, R_E_far, road_lanes, shoulder_lanes, is_forward, left_side_parking,
118+
start_pose, goal_pose, R_E_far, road_lanes, pull_over_lanes, is_forward, left_side_parking,
119119
end_pose_offset, lane_departure_margin, arc_path_interval, {});
120120
if (arc_paths.empty()) {
121121
return std::vector<PathWithLaneId>{};
@@ -156,7 +156,7 @@ void GeometricParallelParking::clearPaths()
156156

157157
bool GeometricParallelParking::planPullOver(
158158
const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes,
159-
const lanelet::ConstLanelets & shoulder_lanes, const bool is_forward,
159+
const lanelet::ConstLanelets & pull_over_lanes, const bool is_forward,
160160
const bool left_side_parking)
161161
{
162162
const auto & common_params = planner_data_->parameters;
@@ -186,7 +186,7 @@ bool GeometricParallelParking::planPullOver(
186186
}
187187

188188
const auto paths = generatePullOverPaths(
189-
*start_pose, goal_pose, R_E_far, road_lanes, shoulder_lanes, is_forward, left_side_parking,
189+
*start_pose, goal_pose, R_E_far, road_lanes, pull_over_lanes, is_forward, left_side_parking,
190190
end_pose_offset, parameters_.forward_parking_velocity);
191191
if (!paths.empty()) {
192192
paths_ = paths;
@@ -208,8 +208,8 @@ bool GeometricParallelParking::planPullOver(
208208
}
209209

210210
const auto paths = generatePullOverPaths(
211-
*start_pose, goal_pose, R_E_min_, road_lanes, shoulder_lanes, is_forward, left_side_parking,
212-
end_pose_offset, parameters_.backward_parking_velocity);
211+
*start_pose, goal_pose, R_E_min_, road_lanes, pull_over_lanes, is_forward,
212+
left_side_parking, end_pose_offset, parameters_.backward_parking_velocity);
213213
if (!paths.empty()) {
214214
paths_ = paths;
215215
return true;
@@ -222,7 +222,7 @@ bool GeometricParallelParking::planPullOver(
222222

223223
bool GeometricParallelParking::planPullOut(
224224
const Pose & start_pose, const Pose & goal_pose, const lanelet::ConstLanelets & road_lanes,
225-
const lanelet::ConstLanelets & shoulder_lanes, const bool left_side_start,
225+
const lanelet::ConstLanelets & pull_over_lanes, const bool left_side_start,
226226
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
227227
lane_departure_checker)
228228
{
@@ -242,7 +242,7 @@ bool GeometricParallelParking::planPullOut(
242242

243243
// plan reverse path of parking. end_pose <-> start_pose
244244
auto arc_paths = planOneTrial(
245-
*end_pose, start_pose, R_E_min_, road_lanes, shoulder_lanes, is_forward, left_side_start,
245+
*end_pose, start_pose, R_E_min_, road_lanes, pull_over_lanes, is_forward, left_side_start,
246246
start_pose_offset, parameters_.pull_out_lane_departure_margin,
247247
parameters_.pull_out_arc_path_interval, lane_departure_checker);
248248
if (arc_paths.empty()) {
@@ -374,7 +374,7 @@ PathWithLaneId GeometricParallelParking::generateStraightPath(
374374

375375
std::vector<PathWithLaneId> GeometricParallelParking::planOneTrial(
376376
const Pose & start_pose, const Pose & goal_pose, const double R_E_far,
377-
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & shoulder_lanes,
377+
const lanelet::ConstLanelets & road_lanes, const lanelet::ConstLanelets & pull_over_lanes,
378378
const bool is_forward, const bool left_side_parking, const double end_pose_offset,
379379
const double lane_departure_margin, const double arc_path_interval,
380380
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
@@ -419,15 +419,15 @@ std::vector<PathWithLaneId> GeometricParallelParking::planOneTrial(
419419
}
420420
lanes.push_back(lane);
421421
}
422-
lanes.insert(lanes.end(), shoulder_lanes.begin(), shoulder_lanes.end());
422+
lanes.insert(lanes.end(), pull_over_lanes.begin(), pull_over_lanes.end());
423423

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

0 commit comments

Comments
 (0)
Please sign in to comment.