Skip to content

Commit

Permalink
use snake case for function names
Browse files Browse the repository at this point in the history
Signed-off-by: mohammad alqudah <[email protected]>
  • Loading branch information
mkquda committed Sep 25, 2024
1 parent f64d80a commit a57b585
Show file tree
Hide file tree
Showing 5 changed files with 11 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2038,7 +2038,7 @@ std::optional<lanelet::routing::LaneletPath> 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;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<LaneChangePath> constructCandidatePath(
std::optional<LaneChangePath> 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<std::vector<int64_t>> & 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);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down Expand Up @@ -1739,7 +1739,7 @@ std::optional<LaneChangePath> 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);

Expand All @@ -1752,7 +1752,7 @@ std::optional<LaneChangePath> 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);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -230,7 +230,7 @@ bool pathFootprintExceedsTargetLaneBound(
return false;
}

std::optional<LaneChangePath> constructCandidatePath(
std::optional<LaneChangePath> 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<std::vector<int64_t>> & sorted_lane_ids)
Expand Down Expand Up @@ -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)
{
Expand Down

0 comments on commit a57b585

Please sign in to comment.