mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Math: add Polygon_outside tests for long template instantiation
This commit is contained in:
parent
51a0401383
commit
64aafb2af2
@ -53,6 +53,58 @@ TEST(Polygon, outside)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
struct PB_long {
|
||||
Vector2l point;
|
||||
Vector2l boundary[3];
|
||||
bool outside;
|
||||
};
|
||||
|
||||
static const PB_long points_boundaries_long[] = {
|
||||
{ {1000000,1000000}, {{0,0}, {0,10000000}, {10000000,0}}, false },
|
||||
|
||||
// test for winding order issues:
|
||||
{ {9000000,9000000}, {{0,0}, {10000000,0}, {0,10000000}}, true },
|
||||
{ {9000000,9000000}, {{0,10000000}, {0,0}, {10000000,0}}, true },
|
||||
{ {9000000,9000000}, {{10000000,0}, {0,10000000}, {0,0}}, true },
|
||||
{ {9000000,9000000}, {{0,10000000}, {10000000,0}, {0,0}}, true },
|
||||
|
||||
{ {1000000,1000000}, {{0,0}, {10000000,0}, {0,10000000}}, false },
|
||||
{ {1000000,1000000}, {{0,10000000}, {0,0}, {10000000,0}}, false },
|
||||
{ {1000000,1000000}, {{10000000,0}, {0,10000000}, {0,0}}, false },
|
||||
{ {1000000,1000000}, {{0,10000000}, {10000000,0}, {0,0}}, false },
|
||||
|
||||
{ {9900000-10,9900000-10}, {{0-10,10000000-10}, {10000000-10,0-10}, {0-10,0-10}}, true },
|
||||
|
||||
{ {990000000,990000000}, {{0,100}, {100,0}, {0,0}}, true },
|
||||
|
||||
{ {1000000,0}, {{0,0}, {0,10000000}, {10000000,0}}, false },
|
||||
{ {0,9900000}, {{0,0}, {0,10000000}, {10000000,0}}, false },
|
||||
{ {9900000,0}, {{0,0}, {0,10000000}, {10000000,0}}, false },
|
||||
|
||||
{ {10100000,0}, {{0,0}, {0,10000000}, {10000000,0}}, true },
|
||||
{ {0,10100000}, {{0,0}, {0,10000000}, {10000000,0}}, true },
|
||||
|
||||
{ {20000000,20000000}, {{0,0}, {0,10000000}, {10000000,0}}, true },
|
||||
{ {-20000000,-20000000}, {{0,0}, {0,10000000}, {10000000,0}}, true },
|
||||
|
||||
{ {-500000,0}, {{0,0}, {0,10000000}, {10000000,0}}, true },
|
||||
{ {0,-500000}, {{0,0}, {0,10000000}, {10000000,0}}, true },
|
||||
};
|
||||
|
||||
TEST(Polygon, outside_long)
|
||||
{
|
||||
// uint8_t count = 0;
|
||||
for (const struct PB_long &pb : points_boundaries_long) {
|
||||
// ::fprintf(stderr, "count=%u\n", count++);
|
||||
Vector2l v[4];
|
||||
memcpy(v, pb.boundary, sizeof(pb.boundary));
|
||||
v[3] = v[0]; // close it
|
||||
EXPECT_EQ(pb.outside, Polygon_outside(pb.point, v, 4));
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#define TEST_POLYGON_POINTS(POLYGON, TEST_POINTS) \
|
||||
do { \
|
||||
for (uint32_t i = 0; i < ARRAY_SIZE(TEST_POINTS); i++) { \
|
||||
|
Loading…
Reference in New Issue
Block a user