mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Math: make Polygon_outside cope with being passed unclosed polygons
This commit is contained in:
parent
2061621951
commit
36fe9a18a0
@ -37,9 +37,21 @@
|
||||
template <typename T>
|
||||
bool Polygon_outside(const Vector2<T> &P, const Vector2<T> *V, unsigned n)
|
||||
{
|
||||
const bool complete = Polygon_complete(V, n);
|
||||
if (complete) {
|
||||
// the last point is the same as the first point; treat as if
|
||||
// the last point wasn't passed in
|
||||
n--;
|
||||
}
|
||||
|
||||
unsigned i, j;
|
||||
// step through each edge pair-wise looking for crossings:
|
||||
bool outside = true;
|
||||
for (i = 0, j = n-1; i < n; j = i++) {
|
||||
for (i=0; i<n; i++) {
|
||||
j = i+1;
|
||||
if (j >= n) {
|
||||
j = 0;
|
||||
}
|
||||
if ((V[i].y > P.y) == (V[j].y > P.y)) {
|
||||
continue;
|
||||
}
|
||||
|
@ -104,6 +104,19 @@ TEST(Polygon, outside_long)
|
||||
}
|
||||
}
|
||||
|
||||
TEST(Polygon, outside_long_closed_equal_to_unclosed)
|
||||
{
|
||||
// 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(Polygon_outside(pb.point, v, 3),
|
||||
Polygon_outside(pb.point, v, 4));
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#define TEST_POLYGON_POINTS(POLYGON, TEST_POINTS) \
|
||||
do { \
|
||||
|
Loading…
Reference in New Issue
Block a user