Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(behavior_path_planner): potentially speed up cut overlapped lanes #5906

Merged
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023 TIER IV, Inc.

Check notice on line 1 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 worse: Lines of Code in a Single File

The lines of code increases from 1458 to 1461, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.

Check notice on line 1 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: Overall Code Complexity

The mean cyclomatic complexity decreases from 10.06 to 9.94, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -586,48 +586,44 @@
[&has_same_id_lane, &p](const auto & lanelet) { return has_same_id_lane(lanelet, p); });
};

// Step1. find first path point within drivable lanes
size_t start_point_idx = std::numeric_limits<size_t>::max();
for (const auto & lanes : shorten_lanes) {
for (size_t i = 0; i < original_points.size(); ++i) {
// check right lane
if (has_same_id_lane(lanes.right_lane, original_points.at(i))) {
start_point_idx = std::min(start_point_idx, i);
}
const auto is_point_in_drivable_lanes = [&has_same_id_lane, &has_same_id_lanes](
const auto & lanes, const auto & p) {

Check warning on line 590 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#L589-L590

Added lines #L589 - L590 were not covered by tests
if (has_same_id_lane(lanes.right_lane, p)) {
return true;
}
// check left lane
if (has_same_id_lane(lanes.left_lane, p)) {
return true;
}
// check middle lanes
if (has_same_id_lanes(lanes.middle_lanes, p)) {
return true;

Check warning on line 600 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#L600

Added line #L600 was not covered by tests
}
return false;
};

Check warning on line 603 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#L603

Added line #L603 was not covered by tests

// check left lane
if (has_same_id_lane(lanes.left_lane, original_points.at(i))) {
start_point_idx = std::min(start_point_idx, i);
}
// Step1. find first path point within drivable lanes
size_t start_point_idx = original_points.size();

// check middle lanes
if (has_same_id_lanes(lanes.middle_lanes, original_points.at(i))) {
start_point_idx = std::min(start_point_idx, i);
}
for (size_t i = 0; i < original_points.size(); ++i) {
const bool first_path_point_in_drivable_lane_found = std::any_of(
shorten_lanes.begin(), shorten_lanes.end(),
[&is_point_in_drivable_lanes, &original_points, i](const auto & lanes) {
return is_point_in_drivable_lanes(lanes, original_points.at(i));

Check warning on line 612 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#L611-L612

Added lines #L611 - L612 were not covered by tests
});
if (first_path_point_in_drivable_lane_found) {
start_point_idx = i;
break;
}
}

// Step2. pick up only path points within drivable lanes
for (const auto & lanes : shorten_lanes) {
for (size_t i = start_point_idx; i < original_points.size(); ++i) {
// check right lane
if (has_same_id_lane(lanes.right_lane, original_points.at(i))) {
path.points.push_back(original_points.at(i));
continue;
}

// check left lane
if (has_same_id_lane(lanes.left_lane, original_points.at(i))) {
if (is_point_in_drivable_lanes(lanes, original_points.at(i))) {
path.points.push_back(original_points.at(i));
continue;
}

Check notice on line 626 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

cutOverlappedLanes decreases in cyclomatic complexity from 15 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.

// check middle lanes
if (has_same_id_lanes(lanes.middle_lanes, original_points.at(i))) {
path.points.push_back(original_points.at(i));
continue;
}

start_point_idx = i;
break;
}
Expand Down
Loading