Skip to content

Commit

Permalink
refactor getMostInnerLane
Browse files Browse the repository at this point in the history
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
  • Loading branch information
kosuke55 committed Dec 3, 2024
1 parent a125a20 commit 30ba1bd
Showing 1 changed file with 7 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -719,17 +719,13 @@ lanelet::Lanelet createDepartureCheckLanelet(
};

const auto getMostInnerLane = [&](const lanelet::ConstLanelet & lane) -> lanelet::ConstLanelet {
if (left_side_parking) {
const auto most_right_lane = route_handler.getMostRightLanelet(lane, true, true);
const auto most_right_opposite_lanes =
route_handler.getRightOppositeLanelets(most_right_lane);
return most_right_opposite_lanes.empty() ? most_right_lane
: most_right_opposite_lanes.front();
} else {
const auto most_left_lane = route_handler.getMostLeftLanelet(lane, true, true);
const auto most_left_opposite_lanes = route_handler.getLeftOppositeLanelets(most_left_lane);
return most_left_opposite_lanes.empty() ? most_left_lane : most_left_opposite_lanes.front();
}
const auto getInnerLanelet =
left_side_parking ? &RouteHandler::getMostRightLanelet : &RouteHandler::getMostLeftLanelet;
const auto getOppositeLanelets = left_side_parking ? &RouteHandler::getRightOppositeLanelets
: &RouteHandler::getLeftOppositeLanelets;
const auto inner_lane = (route_handler.*getInnerLanelet)(lane, true, true);
const auto opposite_lanes = (route_handler.*getOppositeLanelets)(inner_lane);
return opposite_lanes.empty() ? inner_lane : opposite_lanes.front();

Check warning on line 728 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

createDepartureCheckLanelet increases in cyclomatic complexity from 9 to 11, 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.
};

lanelet::Points3d outer_bound_points{};
Expand Down

0 comments on commit 30ba1bd

Please sign in to comment.