From a27ae47ce217cddb0834fad2dc4cac7c51f61033 Mon Sep 17 00:00:00 2001 From: Zulfaqar Azmi Date: Wed, 14 Aug 2024 16:27:40 +0900 Subject: [PATCH] rename function Signed-off-by: Zulfaqar Azmi --- .../behavior_path_lane_change_module/utils/calculation.hpp | 6 +++--- .../autoware_behavior_path_lane_change_module/src/scene.cpp | 2 +- .../src/utils/calculation.cpp | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp index 2e2456faa8760..3dc5e7ee62a57 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/calculation.hpp @@ -43,9 +43,9 @@ double calc_dist_from_pose_to_terminal_end( const Pose & src_pose); /** - * @brief Calculates the backward buffer distance required for safe lane changing. + * @brief Calculates the minimum stopping distance to terminal start. * - * This function computes the minimum required backward buffer distance based on the + * This function computes the minimum stopping distance to terminal start based on the * minimum lane changing velocity and the minimum longitudinal acceleration. It then * compares this calculated distance with a pre-defined backward length buffer parameter * and returns the larger of the two values to ensure safe lane changing. @@ -57,7 +57,7 @@ double calc_dist_from_pose_to_terminal_end( * * @return The required backward buffer distance in meters. */ -double calc_backward_buffer(const LCParamPtr & lc_param_ptr); +double calc_stopping_distance(const LCParamPtr & lc_param_ptr); } // namespace autoware::behavior_path_planner::utils::lane_change::calculation #endif // AUTOWARE__BEHAVIOR_PATH_LANE_CHANGE_MODULE__UTILS__CALCULATION_HPP_ diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp index 745603f90d8eb..9b097a2308b2d 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp @@ -783,7 +783,7 @@ bool NormalLaneChange::is_near_terminal() const const auto min_lane_changing_distance = calcMinimumLaneChangeLength( route_handler_ptr, current_lanes_terminal, *lc_param_ptr, direction); - const auto backward_buffer = calculation::calc_backward_buffer(lc_param_ptr); + const auto backward_buffer = calculation::calc_stopping_distance(lc_param_ptr); const auto min_lc_dist_with_buffer = backward_buffer + min_lane_changing_distance + lc_param_ptr->lane_change_finish_judge_buffer; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp index e20a843f16f34..ac205ceedb34b 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/calculation.cpp @@ -44,7 +44,7 @@ double calc_dist_from_pose_to_terminal_end( return utils::getDistanceToEndOfLane(src_pose, lanes); } -double calc_backward_buffer(const LCParamPtr & lc_param_ptr) +double calc_stopping_distance(const LCParamPtr & lc_param_ptr) { // v^2 = u^2 + 2ad const auto min_lc_vel = lc_param_ptr->minimum_lane_changing_velocity;