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(autoware_utils): address self-intersecting polygons in random_concave_generator and handle empty inners() during triangulation #8995

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 4 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 @@ -83,6 +83,11 @@ std::size_t eliminate_holes(
const std::vector<alt::PointList2d> & inners, std::size_t outer_index, std::size_t & vertices,
std::vector<LinkedPoint> & points);

/**
* @brief helper function to calcuate total area of triangles
*/
double calculate_total_triangle(const std::vector<autoware::universe_utils::Polygon2d> & triangles);

/**
* @brief triangulates a polygon into convex triangles
* @details simplifies a concave polygon, with or without holes, into a set of triangles
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2023-2024 TIER IV, Inc.

Check notice on line 1 in common/autoware_universe_utils/src/geometry/alt_geometry.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 4.50 to 4.57, 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 @@ -68,6 +68,9 @@
std::vector<PointList2d> inners;
for (const auto & inner : polygon.inners()) {
PointList2d _inner;
if (inner.empty()) {
continue;
}
for (const auto & point : inner) {
_inner.push_back(Point2d(point));
}
Expand Down
29 changes: 25 additions & 4 deletions common/autoware_universe_utils/src/geometry/ear_clipping.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2024 TIER IV, Inc.

Check notice on line 1 in common/autoware_universe_utils/src/geometry/ear_clipping.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 5.59 to 5.34, 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 @@ -420,6 +420,9 @@
std::vector<std::size_t> queue;

for (const auto & ring : inners) {
if (ring.empty()) {
continue;
}
auto inner_index = linked_list(ring, false, vertices, points);

if (points[inner_index].next_index.value() == inner_index) {
Expand Down Expand Up @@ -561,6 +564,28 @@
}
}

double calculate_triangle_area(const autoware::universe_utils::Polygon2d & triangle)
{
const auto & points = triangle.outer();
double x1 = points[0].x();
double y1 = points[0].y();
double x2 = points[1].x();
double y2 = points[1].y();
double x3 = points[2].x();
double y3 = points[2].y();

return std::abs((x1 * (y2 - y3) + x2 * (y3 - y1) + x3 * (y1 - y2)) / 2.0);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can you add a source for this formula ?
Or if this function is only needed for the test then just use boost::geometry::area in the tests.

}

double calculate_total_triangle(const std::vector<autoware::universe_utils::Polygon2d> & triangles)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the name of this function is not clear.
I also think it only needs to be defined in the tests.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok, I will move the function to test and use boost::geometry::area instead

{
double totalArea = 0.0;
for (const auto & triangle : triangles) {
totalArea += calculate_triangle_area(triangle);
}
return totalArea;
}

std::vector<LinkedPoint> perform_triangulation(
const alt::Polygon2d & polygon, std::vector<std::size_t> & indices)
{
Expand Down Expand Up @@ -617,10 +642,6 @@
std::vector<Polygon2d> triangulate(const Polygon2d & poly)
{
const auto alt_poly = alt::Polygon2d::create(poly);
if (!alt_poly.has_value()) {
return {};
}

const auto alt_triangles = triangulate(alt_poly.value());
std::vector<Polygon2d> triangles;
for (const auto & alt_triangle : alt_triangles) {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2024 TIER IV, Inc.

Check notice on line 1 in common/autoware_universe_utils/src/geometry/random_concave_polygon.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 4.73 to 4.67, 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 @@ -140,24 +140,17 @@
/// @brief checks if an edge is valid for a given polygon and set of points
bool is_valid(const Edge & e, const Polygon2d & P, const std::vector<Point2d> & Q)
{
bool valid = false;
size_t i = 0;

while (!valid && i < Q.size()) {
const Point2d & q = Q[i];
for (const Point2d & q : Q) {
Edge e1 = {e.first, q};
Edge e2 = {q, e.second};
bool intersects_e1 = intersecting(e1, P);
bool intersects_e2 = intersecting(e2, P);

if (!intersects_e1 && !intersects_e2) {
valid = true;
if (intersects_e1 || intersects_e2) {
return false;
}

++i;
}

return valid;
return true;
}

/// @brief finds the nearest node from a set of points to an edge
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020-2024 Tier IV, Inc.

Check notice on line 1 in common/autoware_universe_utils/test/src/geometry/test_geometry.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 1898 to 1968, 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.
//
// 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 @@ -2021,6 +2021,96 @@
}
}

TEST(geometry, PolygonTriangulation)
{
using autoware::universe_utils::calculate_total_triangle;
using autoware::universe_utils::Polygon2d;
using autoware::universe_utils::triangulate;

{ // concave polygon
Polygon2d poly;

poly.outer().emplace_back(0.0, 0.0);
poly.outer().emplace_back(4.0, 0.0);
poly.outer().emplace_back(4.0, 4.0);
poly.outer().emplace_back(2.0, 2.0);
poly.outer().emplace_back(0.0, 4.0);
boost::geometry::correct(poly);

const auto triangles = triangulate(poly);

const auto triangle_area = calculate_total_triangle(triangles);
const auto poly_area = boost::geometry::area(poly);
EXPECT_NEAR(triangle_area, poly_area, epsilon);
}

{ // concave polygon with empty inners
Polygon2d poly;

poly.outer().emplace_back(0.0, 0.0);
poly.outer().emplace_back(4.0, 0.0);
poly.outer().emplace_back(4.0, 4.0);
poly.outer().emplace_back(2.0, 2.0);
poly.outer().emplace_back(0.0, 4.0);
boost::geometry::correct(poly);

poly.inners().emplace_back();

const auto triangles = triangulate(poly);

const auto triangle_area = calculate_total_triangle(triangles);
const auto poly_area = boost::geometry::area(poly);
EXPECT_NEAR(triangle_area, poly_area, epsilon);
}

{ // concave polygon with hole
Polygon2d poly;

poly.outer().emplace_back(0.0, 0.0);
poly.outer().emplace_back(4.0, 0.0);
poly.outer().emplace_back(4.0, 4.0);
poly.outer().emplace_back(2.0, 2.0);
poly.outer().emplace_back(0.0, 4.0);

poly.inners().emplace_back();
poly.inners().back().emplace_back(1.0, 1.0);
poly.inners().back().emplace_back(1.5, 1.0);
poly.inners().back().emplace_back(1.5, 1.5);
poly.inners().back().emplace_back(1.0, 1.5);
boost::geometry::correct(poly);

const auto triangles = triangulate(poly);

const auto triangle_area = calculate_total_triangle(triangles);
const auto poly_area = boost::geometry::area(poly);
EXPECT_NEAR(triangle_area, poly_area, epsilon);
}

{ // concave polygon with one empty inner followed by one hole
Polygon2d poly;

poly.outer().emplace_back(0.0, 0.0);
poly.outer().emplace_back(4.0, 0.0);
poly.outer().emplace_back(4.0, 4.0);
poly.outer().emplace_back(2.0, 2.0);
poly.outer().emplace_back(0.0, 4.0);

poly.inners().emplace_back();
poly.inners().emplace_back();
poly.inners().back().emplace_back(1.0, 1.0);
poly.inners().back().emplace_back(1.5, 1.0);
poly.inners().back().emplace_back(1.5, 1.5);
poly.inners().back().emplace_back(1.0, 1.5);
boost::geometry::correct(poly);

const auto triangles = triangulate(poly);

const auto triangle_area = calculate_total_triangle(triangles);
const auto poly_area = boost::geometry::area(poly);
EXPECT_NEAR(triangle_area, poly_area, epsilon);
}
}

Check notice on line 2112 in common/autoware_universe_utils/test/src/geometry/test_geometry.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ New issue: Large Method

TEST:geometry:PolygonTriangulation has 70 lines, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.

TEST(geometry, intersectPolygonWithHoles)
{
using autoware::universe_utils::Polygon2d;
Expand Down
Loading