Skip to content

Commit

Permalink
change functions names to snake case
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 fa5a5fe commit f64d80a
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 70 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -153,24 +153,15 @@ class NormalLaneChange : public LaneChangeBase
const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes,
const lanelet::ConstLanelets & target_lanes, const Direction direction = Direction::NONE) const;

bool hasEnoughLengthToCrosswalk(
const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes) const;
bool get_lane_change_paths(LaneChangePaths & candidate_paths) const;

bool hasEnoughLengthToIntersection(
const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes) const;

bool hasEnoughLengthToTrafficLight(
const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes) const;

bool getLaneChangePaths(LaneChangePaths & candidate_paths) const;

LaneChangePath getCandidatePath(
LaneChangePath get_candidate_path(
const LaneChangePhaseMetrics & prep_metrics, const LaneChangePhaseMetrics & lc_metrics,
const PathWithLaneId & prep_segment, const std::vector<std::vector<int64_t>> & sorted_lane_ids,
const Pose & lc_start_pose, const double target_lane_length, const double shift_length,
const double next_lc_buffer, const bool is_goal_in_route) const;

bool checkCandidatePathSafety(
bool check_candidate_path_safety(
const LaneChangePath & candidate_path, const lane_change::TargetObjects & target_objects,
const double lane_change_buffer, const bool is_stuck) const;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ std::pair<bool, bool> NormalLaneChange::getSafePath(LaneChangePath & safe_path)
}

LaneChangePaths valid_paths{};
bool found_safe_path = getLaneChangePaths(valid_paths);
bool found_safe_path = get_lane_change_paths(valid_paths);
// if no safe path is found and ego is stuck, try to find a path with a small margin

lane_change_debug_.valid_paths = valid_paths;
Expand Down Expand Up @@ -1349,59 +1349,7 @@ bool NormalLaneChange::hasEnoughLength(
return true;
}

bool NormalLaneChange::hasEnoughLengthToCrosswalk(
const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes) const
{
const auto current_pose = getEgoPose();
const auto & route_handler = *getRouteHandler();
const auto overall_graphs_ptr = route_handler.getOverallGraphPtr();

const double dist_to_crosswalk_from_lane_change_start_pose =
utils::getDistanceToCrosswalk(current_pose, current_lanes, *overall_graphs_ptr) -
path.info.length.prepare;
// Check lane changing section includes crosswalk
if (
dist_to_crosswalk_from_lane_change_start_pose > 0.0 &&
dist_to_crosswalk_from_lane_change_start_pose < path.info.length.lane_changing) {
return false;
}

return true;
}

bool NormalLaneChange::hasEnoughLengthToIntersection(
const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes) const
{
const auto current_pose = getEgoPose();
const auto & route_handler = *getRouteHandler();
const auto overall_graphs_ptr = route_handler.getOverallGraphPtr();

const double dist_to_intersection_from_lane_change_start_pose =
utils::getDistanceToNextIntersection(current_pose, current_lanes) - path.info.length.prepare;
// Check lane changing section includes intersection
if (
dist_to_intersection_from_lane_change_start_pose > 0.0 &&
dist_to_intersection_from_lane_change_start_pose < path.info.length.lane_changing) {
return false;
}

return true;
}

bool NormalLaneChange::hasEnoughLengthToTrafficLight(
const LaneChangePath & path, const lanelet::ConstLanelets & current_lanes) const
{
const auto current_pose = getEgoPose();
const auto dist_to_next_traffic_light =
getDistanceToNextTrafficLight(current_pose, current_lanes);
const auto dist_to_next_traffic_light_from_lc_start_pose =
dist_to_next_traffic_light - path.info.length.prepare;

return dist_to_next_traffic_light_from_lc_start_pose <= 0.0 ||
dist_to_next_traffic_light_from_lc_start_pose >= path.info.length.lane_changing;
}

bool NormalLaneChange::getLaneChangePaths(LaneChangePaths & candidate_paths) const
bool NormalLaneChange::get_lane_change_paths(LaneChangePaths & candidate_paths) const
{
lane_change_debug_.collision_check_objects.clear();

Expand Down Expand Up @@ -1570,7 +1518,7 @@ bool NormalLaneChange::getLaneChangePaths(LaneChangePaths & candidate_paths) con

LaneChangePath candidate_path;
try {
candidate_path = getCandidatePath(
candidate_path = get_candidate_path(
prep_metric, lc_metric, prepare_segment, sorted_lane_ids, lane_changing_start_pose,
target_lane_length, shift_length, next_lane_change_buffer, is_goal_in_route);
} catch (const std::exception & e) {
Expand All @@ -1583,7 +1531,7 @@ bool NormalLaneChange::getLaneChangePaths(LaneChangePaths & candidate_paths) con
bool is_safe = false;
try {
is_safe =
checkCandidatePathSafety(candidate_path, target_objects, lane_change_buffer, is_stuck);
check_candidate_path_safety(candidate_path, target_objects, lane_change_buffer, is_stuck);
} catch (const std::exception & e) {
debug_print_lat(std::string("Reject: ") + e.what());
return false;
Expand All @@ -1602,7 +1550,7 @@ bool NormalLaneChange::getLaneChangePaths(LaneChangePaths & candidate_paths) con
return false;
}

Check notice on line 1551 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Complex Method

NormalLaneChange::get_lane_change_paths has a cyclomatic complexity of 26, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check notice on line 1551 in planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Bumpy Road Ahead

NormalLaneChange::get_lane_change_paths has 2 blocks with nested conditional logic. Any nesting of 2 or deeper is considered. Threshold is one single, nested block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.

LaneChangePath NormalLaneChange::getCandidatePath(
LaneChangePath NormalLaneChange::get_candidate_path(
const LaneChangePhaseMetrics & prep_metrics, const LaneChangePhaseMetrics & lc_metrics,
const PathWithLaneId & prep_segment, const std::vector<std::vector<int64_t>> & sorted_lane_ids,
const Pose & lc_start_pose, const double target_lane_length, const double shift_length,
Expand Down Expand Up @@ -1649,7 +1597,7 @@ LaneChangePath NormalLaneChange::getCandidatePath(
return *candidate_path;
}

bool NormalLaneChange::checkCandidatePathSafety(
bool NormalLaneChange::check_candidate_path_safety(
const LaneChangePath & candidate_path, const lane_change::TargetObjects & target_objects,
const double lane_change_buffer, const bool is_stuck) const
{
Expand Down

0 comments on commit f64d80a

Please sign in to comment.