@@ -105,7 +105,7 @@ void GeometricParallelParking::setVelocityToArcPaths(
105
105
106
106
std::vector<PathWithLaneId> GeometricParallelParking::generatePullOverPaths (
107
107
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 ,
109
109
const bool is_forward, const bool left_side_parking, const double end_pose_offset,
110
110
const double velocity)
111
111
{
@@ -115,7 +115,7 @@ std::vector<PathWithLaneId> GeometricParallelParking::generatePullOverPaths(
115
115
const double arc_path_interval = is_forward ? parameters_.forward_parking_path_interval
116
116
: parameters_.backward_parking_path_interval ;
117
117
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,
119
119
end_pose_offset, lane_departure_margin, arc_path_interval, {});
120
120
if (arc_paths.empty ()) {
121
121
return std::vector<PathWithLaneId>{};
@@ -156,7 +156,7 @@ void GeometricParallelParking::clearPaths()
156
156
157
157
bool GeometricParallelParking::planPullOver (
158
158
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,
160
160
const bool left_side_parking)
161
161
{
162
162
const auto & common_params = planner_data_->parameters ;
@@ -186,7 +186,7 @@ bool GeometricParallelParking::planPullOver(
186
186
}
187
187
188
188
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,
190
190
end_pose_offset, parameters_.forward_parking_velocity );
191
191
if (!paths.empty ()) {
192
192
paths_ = paths;
@@ -208,8 +208,8 @@ bool GeometricParallelParking::planPullOver(
208
208
}
209
209
210
210
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 );
213
213
if (!paths.empty ()) {
214
214
paths_ = paths;
215
215
return true ;
@@ -222,7 +222,7 @@ bool GeometricParallelParking::planPullOver(
222
222
223
223
bool GeometricParallelParking::planPullOut (
224
224
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,
226
226
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
227
227
lane_departure_checker)
228
228
{
@@ -242,7 +242,7 @@ bool GeometricParallelParking::planPullOut(
242
242
243
243
// plan reverse path of parking. end_pose <-> start_pose
244
244
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,
246
246
start_pose_offset, parameters_.pull_out_lane_departure_margin ,
247
247
parameters_.pull_out_arc_path_interval , lane_departure_checker);
248
248
if (arc_paths.empty ()) {
@@ -374,7 +374,7 @@ PathWithLaneId GeometricParallelParking::generateStraightPath(
374
374
375
375
std::vector<PathWithLaneId> GeometricParallelParking::planOneTrial (
376
376
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 ,
378
378
const bool is_forward, const bool left_side_parking, const double end_pose_offset,
379
379
const double lane_departure_margin, const double arc_path_interval,
380
380
const std::shared_ptr<autoware::lane_departure_checker::LaneDepartureChecker>
@@ -419,15 +419,15 @@ std::vector<PathWithLaneId> GeometricParallelParking::planOneTrial(
419
419
}
420
420
lanes.push_back (lane);
421
421
}
422
- lanes.insert (lanes.end (), shoulder_lanes .begin (), shoulder_lanes .end ());
422
+ lanes.insert (lanes.end (), pull_over_lanes .begin (), pull_over_lanes .end ());
423
423
424
424
// If start_pose is parallel to goal_pose, we can know lateral deviation of edges of vehicle,
425
425
// and detect lane departure.
426
426
if (is_forward) { // Check near bound
427
427
const double R_front_near =
428
428
std::hypot (R_E_far + common_params.vehicle_width / 2 , common_params.base_link2front );
429
429
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);
431
431
const double near_deviation = R_front_near - R_E_far;
432
432
if (std::abs (distance_to_near_bound) - near_deviation < lane_departure_margin) {
433
433
return std::vector<PathWithLaneId>{};
0 commit comments