Skip to content

Commit

Permalink
refactor(static_drivable_area_expansion): define as anon func
Browse files Browse the repository at this point in the history
Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota committed Jan 5, 2024
1 parent 3cbba59 commit a7dcce6
Showing 1 changed file with 35 additions and 33 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -148,6 +148,40 @@ geometry_msgs::msg::Point calcLongitudinalOffsetGoalPoint(

return offset_point ? offset_point.value() : points.at(nearest_segment_idx + 1);
}

std::vector<lanelet::ConstPoint3d> extractBoundFromPolygon(

Check warning on line 152 in planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp#L152

Added line #L152 was not covered by tests
const lanelet::ConstPolygon3d & polygon, const size_t start_idx, const size_t end_idx,
const bool clockwise)
{
std::vector<lanelet::ConstPoint3d> ret{};

Check warning on line 156 in planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp#L156

Added line #L156 was not covered by tests
for (size_t i = start_idx; i != end_idx; i = clockwise ? i + 1 : i - 1) {
ret.push_back(polygon[i]);

if (i + 1 == polygon.size() && clockwise) {
if (end_idx == 0) {
ret.push_back(polygon[end_idx]);
return ret;
}
i = 0;
ret.push_back(polygon[i]);
continue;

Check warning on line 167 in planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp#L167

Added line #L167 was not covered by tests
}

if (i == 0 && !clockwise) {
if (end_idx == polygon.size() - 1) {
ret.push_back(polygon[end_idx]);
return ret;
}
i = polygon.size() - 1;
ret.push_back(polygon[i]);
continue;

Check warning on line 177 in planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp#L177

Added line #L177 was not covered by tests
}
}

ret.push_back(polygon[end_idx]);

return ret;
}

Check warning on line 184 in planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

extractBoundFromPolygon has a cyclomatic complexity of 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.

Check notice on line 184 in planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Bumpy Road Ahead

extractBoundFromPolygon 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.

Check warning on line 184 in planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp#L184

Added line #L184 was not covered by tests
} // namespace

namespace behavior_path_planner::utils::drivable_area_processing
Expand Down Expand Up @@ -1261,38 +1295,6 @@ std::vector<lanelet::ConstPoint3d> getBoundWithIntersectionAreas(
const std::shared_ptr<RouteHandler> & route_handler,
const std::vector<DrivableLanes> & drivable_lanes, const bool is_left)
{
const auto extract_bound_from_polygon =
[](const auto & polygon, const auto start_idx, const auto end_idx, const auto clockwise) {
std::vector<lanelet::ConstPoint3d> ret{};
for (size_t i = start_idx; i != end_idx; i = clockwise ? i + 1 : i - 1) {
ret.push_back(polygon[i]);

if (i + 1 == polygon.size() && clockwise) {
if (end_idx == 0) {
ret.push_back(polygon[end_idx]);
return ret;
}
i = 0;
ret.push_back(polygon[i]);
continue;
}

if (i == 0 && !clockwise) {
if (end_idx == polygon.size() - 1) {
ret.push_back(polygon[end_idx]);
return ret;
}
i = polygon.size() - 1;
ret.push_back(polygon[i]);
continue;
}
}

ret.push_back(polygon[end_idx]);

return ret;
};

std::vector<lanelet::ConstPoint3d> expanded_bound = original_bound;

// expand drivable area by using intersection area.
Expand Down Expand Up @@ -1338,7 +1340,7 @@ std::vector<lanelet::ConstPoint3d> getBoundWithIntersectionAreas(
const size_t end_idx = std::distance(polygon.begin(), intersection_bound_itr_last);

intersection_bound =
extract_bound_from_polygon(polygon, start_idx, end_idx, is_clockwise_iteration);
extractBoundFromPolygon(polygon, start_idx, end_idx, is_clockwise_iteration);

Check notice on line 1343 in planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Method

getBoundWithIntersectionAreas decreases in cyclomatic complexity from 30 to 20, 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 1343 in planning/behavior_path_planner_common/src/utils/drivable_area_expansion/static_drivable_area.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Bumpy Road Ahead

getBoundWithIntersectionAreas is no longer above the threshold for logical blocks with deeply nested code. 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.
}

// Step2. check shared bound point.
Expand Down

0 comments on commit a7dcce6

Please sign in to comment.