Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(start_planner): add option for lane departure #4151

Merged
merged 1 commit into from
Jul 3, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
collision_check_distance_from_end: 1.0
# shift pull out
enable_shift_pull_out: true
check_shift_path_lane_departure: false
minimum_shift_pull_out_distance: 0.0
deceleration_interval: 15.0
lateral_jerk: 0.5
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,6 +105,7 @@ Pull out distance is calculated by the speed, lateral deviation, and the lateral
| Name | Unit | Type | Description | Default value |
| :------------------------------ | :----- | :----- | :------------------------------------------------------------------------------------------------------------------- | :------------ |
| enable_shift_pull_out | [-] | bool | flag whether to enable shift pull out | true |
| check_shift_path_lane_departure | [-] | bool | flag whether to check if shift path footprints are out of lane | false |
| shift_pull_out_velocity | [m/s] | double | velocity of shift pull out | 2.0 |
| pull_out_sampling_num | [-] | int | Number of samplings in the minimum to maximum range of lateral_jerk | 4 |
| maximum_lateral_jerk | [m/s3] | double | maximum lateral jerk | 2.0 |
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ struct StartPlannerParameters
double collision_check_distance_from_end;
// shift pull out
bool enable_shift_pull_out;
bool check_shift_path_lane_departure;
double minimum_shift_pull_out_distance;
int lateral_acceleration_sampling_num;
double lateral_jerk;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@ StartPlannerModuleManager::StartPlannerModuleManager(
node->declare_parameter<double>(ns + "collision_check_distance_from_end");
// shift pull out
p.enable_shift_pull_out = node->declare_parameter<bool>(ns + "enable_shift_pull_out");
p.check_shift_path_lane_departure =
node->declare_parameter<bool>(ns + "check_shift_path_lane_departure");
p.minimum_shift_pull_out_distance =
node->declare_parameter<double>(ns + "minimum_shift_pull_out_distance");
p.lateral_acceleration_sampling_num =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,8 +100,10 @@ boost::optional<PullOutPath> ShiftPullOut::plan(Pose start_pose, Pose goal_pose)
const auto expanded_lanes = utils::expandLanelets(
drivable_lanes, dp.drivable_area_left_bound_offset, dp.drivable_area_right_bound_offset,
dp.drivable_area_types_to_skip);
if (lane_departure_checker_->checkPathWillLeaveLane(
utils::transformToLanelets(expanded_lanes), path_start_to_end)) {
if (
parameters_.check_shift_path_lane_departure &&
lane_departure_checker_->checkPathWillLeaveLane(
utils::transformToLanelets(expanded_lanes), path_start_to_end)) {
continue;
}

Expand Down