mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
AP_Math: added Polygon_complete() function
used to veryify user supplied boundaries
This commit is contained in:
parent
cd9fb3c47a
commit
f4bd3cb5a2
@ -55,6 +55,16 @@ void setup(void)
|
||||
Serial.begin(115200);
|
||||
Serial.println("polygon unit tests\n");
|
||||
|
||||
if (!Polygon_complete(OBC_boundary, ARRAY_LENGTH(OBC_boundary))) {
|
||||
Serial.println("OBC boundary is not complete!");
|
||||
all_passed = false;
|
||||
}
|
||||
|
||||
if (Polygon_complete(OBC_boundary, ARRAY_LENGTH(OBC_boundary)-1)) {
|
||||
Serial.println("Polygon_complete test failed");
|
||||
all_passed = false;
|
||||
}
|
||||
|
||||
for (i=0; i<ARRAY_LENGTH(test_points); i++) {
|
||||
bool result;
|
||||
result = Polygon_outside(&test_points[i].point, OBC_boundary, ARRAY_LENGTH(OBC_boundary));
|
||||
@ -79,7 +89,7 @@ void setup(void)
|
||||
}
|
||||
}
|
||||
}
|
||||
Serial.printf("%u usec/call\n", (micros() - start_time)/(count*ARRAY_LENGTH(test_points)));
|
||||
Serial.printf("%u usec/call\n", (unsigned)((micros() - start_time)/(count*ARRAY_LENGTH(test_points))));
|
||||
Serial.println(all_passed?"ALL TESTS PASSED":"TEST FAILED");
|
||||
}
|
||||
|
||||
|
@ -76,3 +76,15 @@ bool Polygon_outside(const Vector2f *P, const Vector2f *V, unsigned n)
|
||||
}
|
||||
return wn == 0;
|
||||
}
|
||||
|
||||
/*
|
||||
check if a polygon is complete.
|
||||
|
||||
We consider a polygon to be complete if we have at least 4 points,
|
||||
and the first point is the same as the last point. That is the
|
||||
minimum requirement for the Polygon_outside function to work
|
||||
*/
|
||||
bool Polygon_complete(const Vector2f *V, unsigned n)
|
||||
{
|
||||
return (n >= 4 && V[n-1].x == V[0].x && V[n-1].y == V[0].y);
|
||||
}
|
||||
|
@ -18,4 +18,5 @@
|
||||
*/
|
||||
|
||||
bool Polygon_outside(const Vector2f *P, const Vector2f *V, unsigned n);
|
||||
bool Polygon_complete(const Vector2f *V, unsigned n);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user