Skip to content

Commit a940adc

Browse files
fix(lane_change): limit prepare and lane changing length (autowarefoundation#6734)
Signed-off-by: Zulfaqar Azmi <zulfaqar.azmi@tier4.jp>
1 parent 90ff601 commit a940adc

File tree

3 files changed

+32
-6
lines changed

3 files changed

+32
-6
lines changed

planning/behavior_path_lane_change_module/include/behavior_path_lane_change_module/utils/utils.hpp

+17
Original file line numberDiff line numberDiff line change
@@ -261,5 +261,22 @@ Polygon2d getEgoCurrentFootprint(
261261
bool isWithinIntersection(
262262
const std::shared_ptr<RouteHandler> & route_handler, const lanelet::ConstLanelet & lanelet,
263263
const Polygon2d & polygon);
264+
265+
/**
266+
* @brief Calculates the distance required during a lane change operation.
267+
*
268+
* Used for computing prepare or lane change length based on current and maximum velocity,
269+
* acceleration, and duration, returning the lesser of accelerated distance or distance at max
270+
* velocity.
271+
*
272+
* @param velocity The current velocity of the vehicle in meters per second (m/s).
273+
* @param maximum_velocity The maximum velocity the vehicle can reach in meters per second (m/s).
274+
* @param acceleration The acceleration of the vehicle in meters per second squared (m/s^2).
275+
* @param duration The duration of the lane change in seconds (s).
276+
* @return The calculated minimum distance in meters (m).
277+
*/
278+
double calcPhaseLength(
279+
const double velocity, const double maximum_velocity, const double acceleration,
280+
const double time);
264281
} // namespace behavior_path_planner::utils::lane_change
265282
#endif // BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__UTILS_HPP_

planning/behavior_path_lane_change_module/src/scene.cpp

+5-6
Original file line numberDiff line numberDiff line change
@@ -1274,9 +1274,8 @@ bool NormalLaneChange::getLaneChangePaths(
12741274
(prepare_duration < 1e-3) ? 0.0
12751275
: ((prepare_velocity - current_velocity) / prepare_duration);
12761276

1277-
const double prepare_length =
1278-
current_velocity * prepare_duration +
1279-
0.5 * longitudinal_acc_on_prepare * std::pow(prepare_duration, 2);
1277+
const auto prepare_length = utils::lane_change::calcPhaseLength(
1278+
current_velocity, getCommonParam().max_vel, longitudinal_acc_on_prepare, prepare_duration);
12801279

12811280
auto prepare_segment = getPrepareSegment(current_lanes, backward_path_length, prepare_length);
12821281

@@ -1328,9 +1327,9 @@ bool NormalLaneChange::getLaneChangePaths(
13281327
utils::lane_change::calcLaneChangingAcceleration(
13291328
initial_lane_changing_velocity, max_path_velocity, lane_changing_time,
13301329
sampled_longitudinal_acc);
1331-
const auto lane_changing_length =
1332-
initial_lane_changing_velocity * lane_changing_time +
1333-
0.5 * longitudinal_acc_on_lane_changing * lane_changing_time * lane_changing_time;
1330+
const auto lane_changing_length = utils::lane_change::calcPhaseLength(
1331+
initial_lane_changing_velocity, getCommonParam().max_vel,
1332+
longitudinal_acc_on_lane_changing, lane_changing_time);
13341333
const auto terminal_lane_changing_velocity = std::min(
13351334
initial_lane_changing_velocity + longitudinal_acc_on_lane_changing * lane_changing_time,
13361335
getCommonParam().max_vel);

planning/behavior_path_lane_change_module/src/utils/utils.cpp

+10
Original file line numberDiff line numberDiff line change
@@ -1221,4 +1221,14 @@ bool isWithinIntersection(
12211221
return boost::geometry::within(
12221222
polygon, utils::toPolygon2d(lanelet::utils::to2D(lanelet_polygon.basicPolygon())));
12231223
}
1224+
1225+
double calcPhaseLength(
1226+
const double velocity, const double maximum_velocity, const double acceleration,
1227+
const double duration)
1228+
{
1229+
const auto length_with_acceleration =
1230+
velocity * duration + 0.5 * acceleration * std::pow(duration, 2);
1231+
const auto length_with_max_velocity = maximum_velocity * duration;
1232+
return std::min(length_with_acceleration, length_with_max_velocity);
1233+
}
12241234
} // namespace behavior_path_planner::utils::lane_change

0 commit comments

Comments
 (0)