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

fix(lane_change): consider max velocity during path planning #1206

Merged
merged 2 commits into from
Mar 25, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
Next Next commit
fix(lane_change): consider max velocity during path planning (autowar…
…efoundation#6615) (#1203)

Signed-off-by: Muhammad Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
  • Loading branch information
zulfaqar-azmi-t4 committed Mar 25, 2024
commit a44f28c50c5cafaab0b07b73955cdbb2109094d8
9 changes: 5 additions & 4 deletions planning/behavior_path_lane_change_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1253,9 +1253,9 @@ bool NormalLaneChange::getLaneChangePaths(
};

// get path on original lanes
const auto prepare_velocity = std::max(
const auto prepare_velocity = std::clamp(
current_velocity + sampled_longitudinal_acc * prepare_duration,
minimum_lane_changing_velocity);
minimum_lane_changing_velocity, getCommonParam().max_vel);

// compute actual longitudinal acceleration
const double longitudinal_acc_on_prepare =
Expand Down Expand Up @@ -1319,8 +1319,9 @@ bool NormalLaneChange::getLaneChangePaths(
const auto lane_changing_length =
initial_lane_changing_velocity * lane_changing_time +
0.5 * longitudinal_acc_on_lane_changing * lane_changing_time * lane_changing_time;
const auto terminal_lane_changing_velocity =
initial_lane_changing_velocity + longitudinal_acc_on_lane_changing * lane_changing_time;
const auto terminal_lane_changing_velocity = std::min(
initial_lane_changing_velocity + longitudinal_acc_on_lane_changing * lane_changing_time,
getCommonParam().max_vel);
utils::lane_change::setPrepareVelocity(
prepare_segment, current_velocity, terminal_lane_changing_velocity);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -238,6 +238,7 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam()
p.min_acc = declare_parameter<double>("normal.min_acc");
p.max_acc = declare_parameter<double>("normal.max_acc");

p.max_vel = declare_parameter<double>("max_vel");
p.backward_length_buffer_for_end_of_pull_over =
declare_parameter<double>("backward_length_buffer_for_end_of_pull_over");
p.backward_length_buffer_for_end_of_pull_out =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ struct BehaviorPathPlannerParameters
// common parameters
double min_acc;
double max_acc;
double max_vel;

double minimum_pull_over_length;
double minimum_pull_out_length;
Expand Down