Skip to content

Commit 5123ac0

Browse files
committed
Revert "fix(lane_change): consider max velocity during path planning (autowarefoundation#6615) (#1203)"
This reverts commit 2d2d556.
1 parent 1ce9482 commit 5123ac0

File tree

3 files changed

+4
-7
lines changed

3 files changed

+4
-7
lines changed

planning/behavior_path_lane_change_module/src/scene.cpp

+4-5
Original file line numberDiff line numberDiff line change
@@ -1253,9 +1253,9 @@ bool NormalLaneChange::getLaneChangePaths(
12531253
};
12541254

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

12601260
// compute actual longitudinal acceleration
12611261
const double longitudinal_acc_on_prepare =
@@ -1319,9 +1319,8 @@ bool NormalLaneChange::getLaneChangePaths(
13191319
const auto lane_changing_length =
13201320
initial_lane_changing_velocity * lane_changing_time +
13211321
0.5 * longitudinal_acc_on_lane_changing * lane_changing_time * lane_changing_time;
1322-
const auto terminal_lane_changing_velocity = std::min(
1323-
initial_lane_changing_velocity + longitudinal_acc_on_lane_changing * lane_changing_time,
1324-
getCommonParam().max_vel);
1322+
const auto terminal_lane_changing_velocity =
1323+
initial_lane_changing_velocity + longitudinal_acc_on_lane_changing * lane_changing_time;
13251324
utils::lane_change::setPrepareVelocity(
13261325
prepare_segment, current_velocity, terminal_lane_changing_velocity);
13271326

planning/behavior_path_planner/src/behavior_path_planner_node.cpp

-1
Original file line numberDiff line numberDiff line change
@@ -238,7 +238,6 @@ BehaviorPathPlannerParameters BehaviorPathPlannerNode::getCommonParam()
238238
p.min_acc = declare_parameter<double>("normal.min_acc");
239239
p.max_acc = declare_parameter<double>("normal.max_acc");
240240

241-
p.max_vel = declare_parameter<double>("max_vel");
242241
p.backward_length_buffer_for_end_of_pull_over =
243242
declare_parameter<double>("backward_length_buffer_for_end_of_pull_over");
244243
p.backward_length_buffer_for_end_of_pull_out =

planning/behavior_path_planner_common/include/behavior_path_planner_common/parameters.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,6 @@ struct BehaviorPathPlannerParameters
4242
// common parameters
4343
double min_acc;
4444
double max_acc;
45-
double max_vel;
4645

4746
double minimum_pull_over_length;
4847
double minimum_pull_out_length;

0 commit comments

Comments
 (0)