Skip to content

Commit b967eb4

Browse files
committed
make covered_by() support concave polygon
Signed-off-by: mitukou1109 <mitukou1109@gmail.com>
1 parent a07876f commit b967eb4

File tree

3 files changed

+83
-0
lines changed

3 files changed

+83
-0
lines changed

common/autoware_universe_utils/include/autoware/universe_utils/geometry/alt_geometry.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -161,6 +161,8 @@ void correct(alt::Polygon2d & poly);
161161

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

164+
bool covered_by(const alt::Point2d & point, const alt::Polygon2d & poly);
165+
164166
bool disjoint(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2);
165167

166168
double distance(

common/autoware_universe_utils/src/geometry/alt_geometry.cpp

+13
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,8 @@
1414

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

17+
#include "autoware/universe_utils/geometry/ear_clipping.hpp"
18+
1719
namespace autoware::universe_utils
1820
{
1921
// Alternatives for Boost.Geometry ----------------------------------------------------------------
@@ -294,6 +296,17 @@ bool covered_by(const alt::Point2d & point, const alt::ConvexPolygon2d & poly)
294296
return winding_number != 0;
295297
}
296298

299+
bool covered_by(const alt::Point2d & point, const alt::Polygon2d & poly)
300+
{
301+
for (const auto & triangle : triangulate(poly)) {
302+
if (covered_by(point, triangle)) {
303+
return true;
304+
}
305+
}
306+
307+
return false;
308+
}
309+
297310
bool disjoint(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2)
298311
{
299312
if (equals(poly1, poly2)) {

common/autoware_universe_utils/test/src/geometry/test_alt_geometry.cpp

+68
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
// limitations under the License.
1414

1515
#include "autoware/universe_utils/geometry/alt_geometry.hpp"
16+
#include "autoware/universe_utils/geometry/ear_clipping.hpp"
1617
#include "autoware/universe_utils/geometry/random_concave_polygon.hpp"
1718
#include "autoware/universe_utils/geometry/random_convex_polygon.hpp"
1819
#include "autoware/universe_utils/system/stop_watch.hpp"
@@ -915,6 +916,73 @@ TEST(alt_geometry, coveredByRand)
915916
}
916917
}
917918

919+
TEST(alt_geometry, coveredByConcaveRand)
920+
{
921+
std::vector<autoware::universe_utils::Polygon2d> polygons;
922+
constexpr auto polygons_nb = 500;
923+
constexpr auto max_vertices = 10;
924+
constexpr auto max_values = 1000;
925+
926+
autoware::universe_utils::StopWatch<std::chrono::nanoseconds, std::chrono::nanoseconds> sw;
927+
for (auto vertices = 4UL; vertices < max_vertices; ++vertices) {
928+
double ground_truth_covered_ns = 0.0;
929+
double ground_truth_not_covered_ns = 0.0;
930+
double alt_covered_ns = 0.0;
931+
double alt_not_covered_ns = 0.0;
932+
int covered_count = 0;
933+
934+
polygons.clear();
935+
for (auto i = 0; i < polygons_nb; ++i) {
936+
polygons.push_back(autoware::universe_utils::random_concave_polygon(vertices, max_values));
937+
}
938+
for (auto i = 0UL; i < polygons.size(); ++i) {
939+
for (const auto & point : polygons[i].outer()) {
940+
for (auto j = 0UL; j < polygons.size(); ++j) {
941+
sw.tic();
942+
const auto ground_truth = boost::geometry::covered_by(point, polygons[j]);
943+
if (ground_truth) {
944+
++covered_count;
945+
ground_truth_covered_ns += sw.toc();
946+
} else {
947+
ground_truth_not_covered_ns += sw.toc();
948+
}
949+
950+
const auto alt_point = autoware::universe_utils::alt::Point2d(point);
951+
const auto alt_poly =
952+
autoware::universe_utils::alt::Polygon2d::create(polygons[j]).value();
953+
sw.tic();
954+
const auto alt = autoware::universe_utils::covered_by(alt_point, alt_poly);
955+
if (alt) {
956+
alt_covered_ns += sw.toc();
957+
} else {
958+
alt_not_covered_ns += sw.toc();
959+
}
960+
961+
if (ground_truth != alt) {
962+
std::cout << "Alt failed for the point and polygon: ";
963+
std::cout << boost::geometry::wkt(point) << boost::geometry::wkt(polygons[j])
964+
<< std::endl;
965+
}
966+
EXPECT_EQ(ground_truth, alt);
967+
}
968+
}
969+
}
970+
std::printf(
971+
"polygons_nb = %d, vertices = %ld, %d / %ld covered pairs\n", polygons_nb, vertices,
972+
covered_count, polygons_nb * vertices * polygons_nb);
973+
std::printf(
974+
"\tCovered:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n",
975+
ground_truth_covered_ns / 1e6, alt_covered_ns / 1e6);
976+
std::printf(
977+
"\tNot covered:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n",
978+
ground_truth_not_covered_ns / 1e6, alt_not_covered_ns / 1e6);
979+
std::printf(
980+
"\tTotal:\n\t\tBoost::geometry = %2.2f ms\n\t\tAlt = %2.2f ms\n",
981+
(ground_truth_not_covered_ns + ground_truth_covered_ns) / 1e6,
982+
(alt_not_covered_ns + alt_covered_ns) / 1e6);
983+
}
984+
}
985+
918986
TEST(alt_geometry, disjointRand)
919987
{
920988
std::vector<autoware::universe_utils::Polygon2d> polygons;

0 commit comments

Comments
 (0)