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

fix(lane_departure_checker): empty lanelet polygon #6588

Merged
Merged
Show file tree
Hide file tree
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
Expand Up @@ -121,7 +121,7 @@ class LaneDepartureChecker
std::vector<std::pair<double, lanelet::Lanelet>> getLaneletsFromPath(
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const;

std::optional<lanelet::BasicPolygon2d> getFusedLaneletPolygonForPath(
std::optional<tier4_autoware_utils::Polygon2d> getFusedLaneletPolygonForPath(
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const;

bool checkPathWillLeaveLane(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -321,33 +321,39 @@
lanelet_map_ptr->laneletLayer, footprint_hull_basic_polygon, 0.0);
}

std::optional<lanelet::BasicPolygon2d> LaneDepartureChecker::getFusedLaneletPolygonForPath(
std::optional<tier4_autoware_utils::Polygon2d> LaneDepartureChecker::getFusedLaneletPolygonForPath(

Check warning on line 324 in control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp

View check run for this annotation

Codecov / codecov/patch

control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp#L324

Added line #L324 was not covered by tests
const lanelet::LaneletMapPtr lanelet_map_ptr, const PathWithLaneId & path) const
{
const auto lanelets_distance_pair = getLaneletsFromPath(lanelet_map_ptr, path);
auto to_polygon2d = [](const lanelet::BasicPolygon2d & poly) -> tier4_autoware_utils::Polygon2d {

Check warning on line 328 in control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp

View check run for this annotation

Codecov / codecov/patch

control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp#L328

Added line #L328 was not covered by tests
tier4_autoware_utils::Polygon2d p;
auto & outer = p.outer();

for (const auto & p : poly) {
tier4_autoware_utils::Point2d p2d(p.x(), p.y());
outer.push_back(p2d);
}
boost::geometry::correct(p);
return p;
};

Check warning on line 338 in control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp

View check run for this annotation

Codecov / codecov/patch

control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp#L337-L338

Added lines #L337 - L338 were not covered by tests

// Fuse lanelets into a single BasicPolygon2d
auto fused_lanelets = [&lanelets_distance_pair]() -> std::optional<lanelet::BasicPolygon2d> {
auto fused_lanelets = [&]() -> std::optional<tier4_autoware_utils::Polygon2d> {

Check warning on line 341 in control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp

View check run for this annotation

Codecov / codecov/patch

control/lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker.cpp#L341

Added line #L341 was not covered by tests
if (lanelets_distance_pair.empty()) return std::nullopt;
if (lanelets_distance_pair.size() == 1)
return lanelets_distance_pair.at(0).second.polygon2d().basicPolygon();
tier4_autoware_utils::MultiPolygon2d lanelet_unions;
tier4_autoware_utils::MultiPolygon2d result;

lanelet::BasicPolygon2d merged_polygon =
lanelets_distance_pair.at(0).second.polygon2d().basicPolygon();
for (size_t i = 1; i < lanelets_distance_pair.size(); ++i) {
for (size_t i = 0; i < lanelets_distance_pair.size(); ++i) {
const auto & route_lanelet = lanelets_distance_pair.at(i).second;
const auto & poly = route_lanelet.polygon2d().basicPolygon();

std::vector<lanelet::BasicPolygon2d> lanelet_union_temp;
boost::geometry::union_(poly, merged_polygon, lanelet_union_temp);

// Update merged_polygon by accumulating all merged results
merged_polygon.clear();
for (const auto & temp_poly : lanelet_union_temp) {
merged_polygon.insert(merged_polygon.end(), temp_poly.begin(), temp_poly.end());
}
const auto & p = route_lanelet.polygon2d().basicPolygon();
tier4_autoware_utils::Polygon2d poly = to_polygon2d(p);
boost::geometry::union_(lanelet_unions, poly, result);
lanelet_unions = result;
result.clear();
}
if (merged_polygon.empty()) return std::nullopt;
return merged_polygon;

if (lanelet_unions.empty()) return std::nullopt;
return lanelet_unions.front();
}();

return fused_lanelets;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@

const auto cropped_path = lane_departure_checker_->cropPointsOutsideOfLanes(
lanelet_map_ptr, shift_path, start_segment_idx);

if (cropped_path.points.empty()) continue;

Check warning on line 113 in planning/behavior_path_start_planner_module/src/shift_pull_out.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

ShiftPullOut::plan has a cyclomatic complexity of 9, 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 warning on line 113 in planning/behavior_path_start_planner_module/src/shift_pull_out.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_start_planner_module/src/shift_pull_out.cpp#L113

Added line #L113 was not covered by tests
shift_path.points = cropped_path.points;
shift_path.header = planner_data_->route_handler->getRouteHeader();

Expand Down
Loading