From fa2b158f41abfbca3cbc28382316dd0435684ced Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT Date: Thu, 4 Jul 2024 21:40:55 +0900 Subject: [PATCH] fix function name and comments Signed-off-by: Maxime CLEMENT --- .../autoware/universe_utils/geometry/geometry.hpp | 2 +- .../autoware/universe_utils/geometry/gjk_2d.hpp | 4 ++-- .../src/geometry/geometry.cpp | 4 ++-- .../autoware_universe_utils/src/geometry/gjk_2d.cpp | 8 ++------ .../test/src/geometry/test_geometry.cpp | 13 ++++++------- 5 files changed, 13 insertions(+), 18 deletions(-) diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/geometry.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/geometry.hpp index 1be3907f22fe9..d8962f6836744 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/geometry.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/geometry.hpp @@ -584,7 +584,7 @@ std::optional intersect( * @brief Check if 2 convex polygons intersect using the GJK algorithm * @details much faster than boost::geometry::intersects() */ -bool intersect(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2); +bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2); } // namespace autoware::universe_utils diff --git a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/gjk_2d.hpp b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/gjk_2d.hpp index fb023e2b0bd60..45a56c04e8030 100644 --- a/common/autoware_universe_utils/include/autoware/universe_utils/geometry/gjk_2d.hpp +++ b/common/autoware_universe_utils/include/autoware/universe_utils/geometry/gjk_2d.hpp @@ -31,9 +31,9 @@ Point2d cross_product(const Point2d & p1, const Point2d & p2, const Point2d & p3 } // namespace /** * @brief Check if 2 convex polygons intersect using the GJK algorithm - * @details much faster than boost::geometry::intersects() + * @details much faster than boost::geometry::overlaps() but limited to convex polygons */ -bool intersect(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2); +bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2); } // namespace autoware::universe_utils::gjk #endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__GJK_2D_HPP_ diff --git a/common/autoware_universe_utils/src/geometry/geometry.cpp b/common/autoware_universe_utils/src/geometry/geometry.cpp index 23fdcfafe87d6..4f186570178f8 100644 --- a/common/autoware_universe_utils/src/geometry/geometry.cpp +++ b/common/autoware_universe_utils/src/geometry/geometry.cpp @@ -385,9 +385,9 @@ std::optional intersect( return intersect_point; } -bool intersect(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2) +bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2) { - return gjk::intersect(convex_polygon1, convex_polygon2); + return gjk::intersects(convex_polygon1, convex_polygon2); } } // namespace autoware::universe_utils diff --git a/common/autoware_universe_utils/src/geometry/gjk_2d.cpp b/common/autoware_universe_utils/src/geometry/gjk_2d.cpp index df9478e03006e..fb90442eecdaf 100644 --- a/common/autoware_universe_utils/src/geometry/gjk_2d.cpp +++ b/common/autoware_universe_utils/src/geometry/gjk_2d.cpp @@ -31,7 +31,6 @@ double dot_product(const Point2d & p1, const Point2d & p2) return p1.x() * p2.x() + p1.y() * p2.y(); } -/// @brief return the polygon polygon that is the furthest away from a direction vector size_t furthest_vertex_idx(const Polygon2d & poly, const Point2d & direction) { auto furthest_distance = std::numeric_limits::lowest(); @@ -67,11 +66,8 @@ Point2d cross_product(const Point2d & p1, const Point2d & p2, const Point2d & p3 return Point2d(-p3.y() * tmp, p3.x() * tmp); } } // namespace -/** - * @brief Check if 2 convex polygons intersect using the GJK algorithm - * @details much faster than boost::geometry::intersects() - */ -bool intersect(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2) + +bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2) { if (convex_polygon1.outer().empty() || convex_polygon2.outer().empty()) { return false; diff --git a/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp b/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp index fc2173a6fe769..79300db5bf106 100644 --- a/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp +++ b/common/autoware_universe_utils/test/src/geometry/test_geometry.cpp @@ -14,7 +14,6 @@ #include "autoware/universe_utils/geometry/boost_geometry.hpp" #include "autoware/universe_utils/geometry/geometry.hpp" -#include "autoware/universe_utils/geometry/gjk_2d.hpp" #include "autoware/universe_utils/geometry/random_convex_polygon.hpp" #include "autoware/universe_utils/math/unit_conversion.hpp" #include "autoware/universe_utils/system/stop_watch.hpp" @@ -1850,7 +1849,7 @@ TEST(geometry, intersectPolygon) poly2.outer().emplace_back(0, 1); boost::geometry::correct(poly1); boost::geometry::correct(poly2); - EXPECT_TRUE(autoware::universe_utils::intersect(poly1, poly2)); + EXPECT_TRUE(autoware::universe_utils::intersects(poly1, poly2)); } { // 2 triangles with no intersection (but they share an edge) autoware::universe_utils::Polygon2d poly1, poly2; @@ -1862,7 +1861,7 @@ TEST(geometry, intersectPolygon) poly2.outer().emplace_back(2, 2); boost::geometry::correct(poly1); boost::geometry::correct(poly2); - EXPECT_FALSE(autoware::universe_utils::intersect(poly1, poly2)); + EXPECT_FALSE(autoware::universe_utils::intersects(poly1, poly2)); } { // 2 triangles with no intersection (but they share a point) autoware::universe_utils::Polygon2d poly1, poly2; @@ -1874,7 +1873,7 @@ TEST(geometry, intersectPolygon) poly2.outer().emplace_back(2, 2); boost::geometry::correct(poly1); boost::geometry::correct(poly2); - EXPECT_FALSE(autoware::universe_utils::intersect(poly1, poly2)); + EXPECT_FALSE(autoware::universe_utils::intersects(poly1, poly2)); } { // 2 triangles with no intersection and no touching autoware::universe_utils::Polygon2d poly1, poly2; @@ -1886,7 +1885,7 @@ TEST(geometry, intersectPolygon) poly2.outer().emplace_back(3, 5); boost::geometry::correct(poly1); boost::geometry::correct(poly2); - EXPECT_FALSE(autoware::universe_utils::intersect(poly1, poly2)); + EXPECT_FALSE(autoware::universe_utils::intersects(poly1, poly2)); } { // triangle and quadrilateral with intersection autoware::universe_utils::Polygon2d poly1, poly2; @@ -1899,7 +1898,7 @@ TEST(geometry, intersectPolygon) poly2.outer().emplace_back(12, 7); boost::geometry::correct(poly1); boost::geometry::correct(poly2); - EXPECT_TRUE(autoware::universe_utils::intersect(poly1, poly2)); + EXPECT_TRUE(autoware::universe_utils::intersects(poly1, poly2)); } } @@ -1922,7 +1921,7 @@ TEST(geometry, intersectPolygonRand) const auto ground_truth = boost::geometry::intersects(polygons[i], polygons[j]); ground_truth_ns += sw.toc(); sw.tic(); - const auto gjk = autoware::universe_utils::gjk::intersect(polygons[i], polygons[j]); + const auto gjk = autoware::universe_utils::intersects(polygons[i], polygons[j]); gjk_ns += sw.toc(); if (ground_truth != gjk) { std::cout << "Failed for the 2 polygons: ";