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(universe_utils): add SAT implementation for 2D convex polygon collision check #8239

Merged
merged 11 commits into from
Aug 28, 2024
1 change: 1 addition & 0 deletions common/autoware_universe_utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ ament_auto_add_library(autoware_universe_utils SHARED
src/geometry/boost_polygon_utils.cpp
src/geometry/random_convex_polygon.cpp
src/geometry/gjk_2d.cpp
src/geometry/sat_2d.cpp
src/math/sin_table.cpp
src/math/trigonometry.cpp
src/ros/msg_operation.cpp
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
// Copyright 2024 Tier IV, Inc.
mraditya01 marked this conversation as resolved.
Show resolved Hide resolved
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__UNIVERSE_UTILS__GEOMETRY__SAT_2D_HPP_
#define AUTOWARE__UNIVERSE_UTILS__GEOMETRY__SAT_2D_HPP_

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

namespace autoware::universe_utils::sat
{
/**
* @brief Check if 2 convex polygons intersect using the SAT algorithm
* @details faster than boost::geometry::overlap() but speed decline sharply as vertices increase
*/
bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2);

} // namespace autoware::universe_utils::sat

#endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__SAT_2D_HPP_
82 changes: 82 additions & 0 deletions common/autoware_universe_utils/src/geometry/sat_2d.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
// Copyright 2024 Tier IV, Inc.
mraditya01 marked this conversation as resolved.
Show resolved Hide resolved
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

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

#include <boost/geometry/algorithms/for_each.hpp>
mraditya01 marked this conversation as resolved.
Show resolved Hide resolved

namespace autoware::universe_utils::sat
{

namespace
{
/// @brief calculate the edge normal of two points
Point2d edge_normal(const Point2d & p1, const Point2d & p2)
{
return {p2.y() - p1.y(), p1.x() - p2.x()};
}

/// @brief project a polygon onto an axis and return the minimum and maximum values
std::pair<double, double> project_polygon(const Polygon2d & poly, const Point2d & axis)
{
double min = poly.outer()[0].dot(axis);
double max = min;
for (const auto & point : poly.outer()) {
double projection = point.dot(axis);
if (projection < min) {
min = projection;
}
if (projection > max) {
max = projection;
}
}
return {min, max};
}

/// @brief check if two projections overlap
bool projections_overlap(
const std::pair<double, double> & proj1, const std::pair<double, double> & proj2)
{
return proj1.second >= proj2.first && proj2.second >= proj1.first;
}

/// @brief check is all edges of a polygon can be separated from the other polygon with a separating
/// axis
bool has_separating_axis(const Polygon2d & polygon, const Polygon2d & other)
{
for (size_t i = 0; i < polygon.outer().size(); ++i) {
const size_t next_i = (i + 1) % polygon.outer().size();
const Point2d edge = edge_normal(polygon.outer()[i], polygon.outer()[next_i]);
const auto projection1 = project_polygon(polygon, edge);
const auto projection2 = project_polygon(other, edge);
if (!projections_overlap(projection1, projection2)) {
return false;
mkquda marked this conversation as resolved.
Show resolved Hide resolved
}
}
return true;
}
} // namespace

/// @brief check if two convex polygons intersect using the SAT algorithm
/// @details this function uses the Separating Axis Theorem (SAT) to determine if two convex
/// polygons intersect. If projections overlap on all tested axes, the function returns `true`;
/// otherwise, it returns `false`. Note that touching polygons (e.g., at a point or along an edge)
/// will be considered as not intersecting.
bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2)
{
return has_separating_axis(convex_polygon1, convex_polygon2) &&
mkquda marked this conversation as resolved.
Show resolved Hide resolved
has_separating_axis(convex_polygon2, convex_polygon1);
}

} // namespace autoware::universe_utils::sat
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 2536 to 2552, 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 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 better: Code Duplication

reduced similar code in: TEST:geometry:intersectPolygonRand. Avoid duplicated, aka copy-pasted, code inside the module. More duplication 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 All @@ -15,6 +15,7 @@
#include "autoware/universe_utils/geometry/boost_geometry.hpp"
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "autoware/universe_utils/geometry/random_convex_polygon.hpp"
#include "autoware/universe_utils/geometry/sat_2d.hpp"
#include "autoware/universe_utils/math/unit_conversion.hpp"
#include "autoware/universe_utils/system/stop_watch.hpp"

Expand Down Expand Up @@ -1933,54 +1934,82 @@
constexpr auto max_values = 1000;

autoware::universe_utils::StopWatch<std::chrono::nanoseconds, std::chrono::nanoseconds> sw;

for (auto vertices = 3UL; vertices < max_vertices; ++vertices) {
double ground_truth_intersect_ns = 0.0;
double ground_truth_no_intersect_ns = 0.0;
double gjk_intersect_ns = 0.0;
double gjk_no_intersect_ns = 0.0;
double sat_intersect_ns = 0.0;
double sat_no_intersect_ns = 0.0;
int intersect_count = 0;
polygons.clear();

for (auto i = 0; i < polygons_nb; ++i) {
polygons.push_back(autoware::universe_utils::random_convex_polygon(vertices, max_values));
}

for (auto i = 0UL; i < polygons.size(); ++i) {
for (auto j = 0UL; j < polygons.size(); ++j) {
sw.tic();
const auto ground_truth = boost::geometry::intersects(polygons[i], polygons[j]);
if (ground_truth) {
++intersect_count;
ground_truth_intersect_ns += sw.toc();
} else {
ground_truth_no_intersect_ns += sw.toc();
}

sw.tic();
const auto gjk = autoware::universe_utils::intersects_convex(polygons[i], polygons[j]);
if (gjk) {
gjk_intersect_ns += sw.toc();
} else {
gjk_no_intersect_ns += sw.toc();
}

sw.tic();
const auto sat = autoware::universe_utils::sat::intersects(polygons[i], polygons[j]);
if (sat) {
sat_intersect_ns += sw.toc();
} else {
sat_no_intersect_ns += sw.toc();
}

EXPECT_EQ(ground_truth, gjk);
EXPECT_EQ(ground_truth, sat);

if (ground_truth != gjk) {
std::cout << "Failed for the 2 polygons: ";
std::cout << "Failed for the 2 polygons with GJK: ";
std::cout << boost::geometry::wkt(polygons[i]) << boost::geometry::wkt(polygons[j])
<< std::endl;
}

if (ground_truth != sat) {
std::cout << "Failed for the 2 polygons with SAT: ";
std::cout << boost::geometry::wkt(polygons[i]) << boost::geometry::wkt(polygons[j])
<< std::endl;
}
EXPECT_EQ(ground_truth, gjk);
}
}

std::printf(
"polygons_nb = %d, vertices = %ld, %d / %d pairs with intersects\n", polygons_nb, vertices,
intersect_count, polygons_nb * polygons_nb);

std::printf(
"\tIntersect:\n\t\tBoost::geometry = %2.2f ms\n\t\tGJK = %2.2f ms\n",
ground_truth_intersect_ns / 1e6, gjk_intersect_ns / 1e6);
"\tIntersect:\n\t\tBoost::geometry = %2.2f ms\n\t\tGJK = %2.2f ms\n\t\tSAT = %2.2f ms\n",
ground_truth_intersect_ns / 1e6, gjk_intersect_ns / 1e6, sat_intersect_ns / 1e6);

std::printf(
"\tNo Intersect:\n\t\tBoost::geometry = %2.2f ms\n\t\tGJK = %2.2f ms\n",
ground_truth_no_intersect_ns / 1e6, gjk_no_intersect_ns / 1e6);
"\tNo Intersect:\n\t\tBoost::geometry = %2.2f ms\n\t\tGJK = %2.2f ms\n\t\tSAT = %2.2f ms\n",
ground_truth_no_intersect_ns / 1e6, gjk_no_intersect_ns / 1e6, sat_no_intersect_ns / 1e6);

std::printf(
"\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tGJK = %2.2f ms\n",
"\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tGJK = %2.2f ms\n\t\tSAT = %2.2f ms\n",
(ground_truth_no_intersect_ns + ground_truth_intersect_ns) / 1e6,
(gjk_no_intersect_ns + gjk_intersect_ns) / 1e6);
(gjk_no_intersect_ns + gjk_intersect_ns) / 1e6,
(sat_no_intersect_ns + sat_intersect_ns) / 1e6);

Check warning on line 2012 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: Complex Method

TEST:geometry:intersectPolygonRand has a cyclomatic complexity of 10, 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.
}
}

Expand Down
Loading