Skip to content

Commit

Permalink
make covered_by() support concave polygon
Browse files Browse the repository at this point in the history
Signed-off-by: mitukou1109 <[email protected]>
  • Loading branch information
mitukou1109 committed Sep 27, 2024
1 parent a07876f commit b967eb4
Show file tree
Hide file tree
Showing 3 changed files with 83 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -161,6 +161,8 @@ void correct(alt::Polygon2d & poly);

bool covered_by(const alt::Point2d & point, const alt::ConvexPolygon2d & poly);

bool covered_by(const alt::Point2d & point, const alt::Polygon2d & poly);

bool disjoint(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2);

double distance(
Expand Down
13 changes: 13 additions & 0 deletions common/autoware_universe_utils/src/geometry/alt_geometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "autoware/universe_utils/geometry/alt_geometry.hpp"

#include "autoware/universe_utils/geometry/ear_clipping.hpp"

namespace autoware::universe_utils
{
// Alternatives for Boost.Geometry ----------------------------------------------------------------
Expand Down Expand Up @@ -294,6 +296,17 @@ bool covered_by(const alt::Point2d & point, const alt::ConvexPolygon2d & poly)
return winding_number != 0;
}

bool covered_by(const alt::Point2d & point, const alt::Polygon2d & poly)
{
for (const auto & triangle : triangulate(poly)) {
if (covered_by(point, triangle)) {
return true;
}
}

return false;
}

bool disjoint(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2)
{
if (equals(poly1, poly2)) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
// limitations under the License.

#include "autoware/universe_utils/geometry/alt_geometry.hpp"
#include "autoware/universe_utils/geometry/ear_clipping.hpp"
#include "autoware/universe_utils/geometry/random_concave_polygon.hpp"
#include "autoware/universe_utils/geometry/random_convex_polygon.hpp"
#include "autoware/universe_utils/system/stop_watch.hpp"
Expand Down Expand Up @@ -915,6 +916,73 @@ TEST(alt_geometry, coveredByRand)
}
}

TEST(alt_geometry, coveredByConcaveRand)
{
std::vector<autoware::universe_utils::Polygon2d> polygons;
constexpr auto polygons_nb = 500;
constexpr auto max_vertices = 10;
constexpr auto max_values = 1000;

autoware::universe_utils::StopWatch<std::chrono::nanoseconds, std::chrono::nanoseconds> sw;
for (auto vertices = 4UL; vertices < max_vertices; ++vertices) {
double ground_truth_covered_ns = 0.0;
double ground_truth_not_covered_ns = 0.0;
double alt_covered_ns = 0.0;
double alt_not_covered_ns = 0.0;
int covered_count = 0;

polygons.clear();
for (auto i = 0; i < polygons_nb; ++i) {
polygons.push_back(autoware::universe_utils::random_concave_polygon(vertices, max_values));
}
for (auto i = 0UL; i < polygons.size(); ++i) {
for (const auto & point : polygons[i].outer()) {
for (auto j = 0UL; j < polygons.size(); ++j) {
sw.tic();
const auto ground_truth = boost::geometry::covered_by(point, polygons[j]);
if (ground_truth) {
++covered_count;
ground_truth_covered_ns += sw.toc();
} else {
ground_truth_not_covered_ns += sw.toc();
}

const auto alt_point = autoware::universe_utils::alt::Point2d(point);
const auto alt_poly =
autoware::universe_utils::alt::Polygon2d::create(polygons[j]).value();
sw.tic();
const auto alt = autoware::universe_utils::covered_by(alt_point, alt_poly);
if (alt) {
alt_covered_ns += sw.toc();
} else {
alt_not_covered_ns += sw.toc();
}

if (ground_truth != alt) {
std::cout << "Alt failed for the point and polygon: ";
std::cout << boost::geometry::wkt(point) << boost::geometry::wkt(polygons[j])
<< std::endl;
}
EXPECT_EQ(ground_truth, alt);
}
}
}
std::printf(
"polygons_nb = %d, vertices = %ld, %d / %ld covered pairs\n", polygons_nb, vertices,
covered_count, polygons_nb * vertices * polygons_nb);
std::printf(
"\tCovered:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n",
ground_truth_covered_ns / 1e6, alt_covered_ns / 1e6);
std::printf(
"\tNot covered:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n",
ground_truth_not_covered_ns / 1e6, alt_not_covered_ns / 1e6);
std::printf(
"\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n",
(ground_truth_not_covered_ns + ground_truth_covered_ns) / 1e6,
(alt_not_covered_ns + alt_covered_ns) / 1e6);
}
}

Check warning on line 984 in common/autoware_universe_utils/test/src/geometry/test_alt_geometry.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

TEST:alt_geometry:coveredByConcaveRand 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 984 in common/autoware_universe_utils/test/src/geometry/test_alt_geometry.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Bumpy Road Ahead

TEST:alt_geometry:coveredByConcaveRand 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 984 in common/autoware_universe_utils/test/src/geometry/test_alt_geometry.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Deep, Nested Complexity

TEST:alt_geometry:coveredByConcaveRand has a nested complexity depth of 5, threshold = 4. This function contains deeply nested logic such as if statements and/or loops. The deeper the nesting, the lower the code health.

TEST(alt_geometry, disjointRand)
{
std::vector<autoware::universe_utils::Polygon2d> polygons;
Expand Down

0 comments on commit b967eb4

Please sign in to comment.