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(behavior_path_planner): add new lateral acc condition #3304

Merged
merged 4 commits into from
Apr 10, 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,8 +8,10 @@
backward_length_buffer_for_end_of_lane: 3.0 # [m]
lane_change_finish_judge_buffer: 2.0 # [m]

lane_changing_lateral_jerk: 0.5 # [m/s3]
lane_changing_lateral_acc: 0.5 # [m/s2]
lane_changing_lateral_jerk: 0.5 # [m/s3]
lane_changing_lateral_acc: 0.315 # [m/s2]
lane_changing_lateral_acc_at_low_velocity: 0.15 # [m/s2]
lateral_acc_switching_velocity: 4.0 #[m/s]

minimum_lane_changing_velocity: 2.78 # [m/s]
prediction_time_resolution: 0.5 # [s]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,9 @@ struct LaneChangeParameters
// trajectory generation
double prepare_duration{2.0};
double lane_changing_lateral_jerk{0.5};
double lane_changing_lateral_acc{0.5};
double lane_changing_lateral_acc{0.315};
double lane_changing_lateral_acc_at_low_velocity{0.15};
double lateral_acc_switching_velocity{0.4};
double lane_change_finish_judge_buffer{3.0};
double minimum_lane_changing_velocity{5.6};
double prediction_time_resolution{0.5};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -737,6 +737,10 @@ LaneChangeParameters BehaviorPathPlannerNode::getLaneChangeParam()
p.prepare_duration = declare_parameter<double>(parameter("prepare_duration"));
p.lane_changing_lateral_jerk = declare_parameter<double>(parameter("lane_changing_lateral_jerk"));
p.lane_changing_lateral_acc = declare_parameter<double>(parameter("lane_changing_lateral_acc"));
p.lane_changing_lateral_acc_at_low_velocity =
declare_parameter<double>(parameter("lane_changing_lateral_acc_at_low_velocity"));
p.lateral_acc_switching_velocity =
declare_parameter<double>(parameter("lateral_acc_switching_velocity"));
p.lane_change_finish_judge_buffer =
declare_parameter<double>(parameter("lane_change_finish_judge_buffer"));
p.minimum_lane_changing_velocity =
Expand Down
5 changes: 4 additions & 1 deletion planning/behavior_path_planner/src/util/lane_change/util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -710,8 +710,11 @@ double calcLaneChangingLength(
const double lane_changing_velocity, const double shift_length,
const BehaviorPathPlannerParameters & com_param, const LaneChangeParameters & lc_param)
{
const double lateral_acc = lane_changing_velocity < lc_param.lateral_acc_switching_velocity
? lc_param.lane_changing_lateral_acc_at_low_velocity
: lc_param.lane_changing_lateral_acc;
const auto required_time = PathShifter::calcShiftTimeFromJerk(
shift_length, lc_param.lane_changing_lateral_jerk, lc_param.lane_changing_lateral_acc);
shift_length, lc_param.lane_changing_lateral_jerk, lateral_acc);

const double & min_lane_change_length = com_param.minimum_lane_changing_length;
const double lane_changing_length =
Expand Down