diff --git a/planning/autoware_route_handler/include/autoware/route_handler/route_handler.hpp b/planning/autoware_route_handler/include/autoware/route_handler/route_handler.hpp index 8b8fca4818b52..6202be28e7e87 100644 --- a/planning/autoware_route_handler/include/autoware/route_handler/route_handler.hpp +++ b/planning/autoware_route_handler/include/autoware/route_handler/route_handler.hpp @@ -326,7 +326,7 @@ class RouteHandler */ lanelet::ConstLanelets getShoulderLaneletsAtPose(const Pose & pose) const; - Pose getPoseFrom2DArcLength( + Pose get_pose_from_2d_arc_length( const lanelet::ConstLanelets & lanelet_sequence, const double s) const; private: diff --git a/planning/autoware_route_handler/src/route_handler.cpp b/planning/autoware_route_handler/src/route_handler.cpp index 075710c061687..616b91d1bc5f9 100644 --- a/planning/autoware_route_handler/src/route_handler.cpp +++ b/planning/autoware_route_handler/src/route_handler.cpp @@ -2038,7 +2038,7 @@ std::optional RouteHandler::findDrivableLanePath( return {}; } -Pose RouteHandler::getPoseFrom2DArcLength( +Pose RouteHandler::get_pose_from_2d_arc_length( const lanelet::ConstLanelets & lanelet_sequence, const double s) const { double accumulated_distance2d = 0; diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp index e7768455490d0..c9990747f57a7 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp @@ -95,12 +95,12 @@ bool pathFootprintExceedsTargetLaneBound( const CommonDataPtr & common_data_ptr, const PathWithLaneId & path, const VehicleInfo & ego_info, const double margin = 0.1); -std::optional constructCandidatePath( +std::optional construct_candidate_path( const CommonDataPtr & common_data_ptr, const LaneChangeInfo & lane_change_info, const PathWithLaneId & prepare_segment, const PathWithLaneId & target_lane_reference_path, const std::vector> & sorted_lane_ids); -ShiftLine getLaneChangingShiftLine( +ShiftLine get_lane_changing_shift_line( const Pose & lane_changing_start_pose, const Pose & lane_changing_end_pose, const PathWithLaneId & reference_path, const double shift_length); 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 3d098807fc1d5..e8a63c09580e1 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 @@ -1575,15 +1575,15 @@ LaneChangePath NormalLaneChange::get_candidate_path( const auto dist_to_lc_start = lanelet::utils::getArcCoordinates(target_lanes, lc_start_pose).length; const auto dist_to_lc_end = dist_to_lc_start + lc_metrics.length; - return route_handler.getPoseFrom2DArcLength(target_lanes, dist_to_lc_end); + return route_handler.get_pose_from_2d_arc_length(target_lanes, dist_to_lc_end); }); - const auto shift_line = utils::lane_change::getLaneChangingShiftLine( + const auto shift_line = utils::lane_change::get_lane_changing_shift_line( lc_start_pose, lc_end_pose, target_lane_reference_path, shift_length); LaneChangeInfo lane_change_info{prep_metrics, lc_metrics, lc_start_pose, lc_end_pose, shift_line}; - const auto candidate_path = utils::lane_change::constructCandidatePath( + const auto candidate_path = utils::lane_change::construct_candidate_path( common_data_ptr_, lane_change_info, prep_segment, target_lane_reference_path, sorted_lane_ids); if (!candidate_path) { @@ -1739,7 +1739,7 @@ std::optional NormalLaneChange::calcTerminalLaneChangePath( return {}; } - lane_change_info.shift_line = utils::lane_change::getLaneChangingShiftLine( + lane_change_info.shift_line = utils::lane_change::get_lane_changing_shift_line( lane_changing_start_pose.value(), target_segment.points.front().point.pose, target_lane_reference_path, shift_length); @@ -1752,7 +1752,7 @@ std::optional NormalLaneChange::calcTerminalLaneChangePath( reference_segment.points.pop_back(); reference_segment.points.back().point.longitudinal_velocity_mps = minimum_lane_changing_velocity; - const auto terminal_lane_change_path = utils::lane_change::constructCandidatePath( + const auto terminal_lane_change_path = utils::lane_change::construct_candidate_path( common_data_ptr_, lane_change_info, reference_segment, target_lane_reference_path, sorted_lane_ids); diff --git a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp index 920ff4c4d7edb..36aedf5c99a53 100644 --- a/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp +++ b/planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp @@ -230,7 +230,7 @@ bool pathFootprintExceedsTargetLaneBound( return false; } -std::optional constructCandidatePath( +std::optional construct_candidate_path( const CommonDataPtr & common_data_ptr, const LaneChangeInfo & lane_change_info, const PathWithLaneId & prepare_segment, const PathWithLaneId & target_lane_reference_path, const std::vector> & sorted_lane_ids) @@ -355,7 +355,7 @@ PathWithLaneId getReferencePathFromTargetLane( lane_changing_reference_path, resample_interval, true, {0.0, lane_changing_length}); } -ShiftLine getLaneChangingShiftLine( +ShiftLine get_lane_changing_shift_line( const Pose & lane_changing_start_pose, const Pose & lane_changing_end_pose, const PathWithLaneId & reference_path, const double shift_length) {