AP_Math: polygon.cpp correct float comparison

This commit is contained in:
Pierre Kancir 2016-12-06 14:33:11 +01:00 committed by Tom Pittenger
parent 5900653b7f
commit 6bf1322633
1 changed files with 1 additions and 1 deletions

View File

@ -88,7 +88,7 @@ bool Polygon_outside(const Vector2<T> &P, const Vector2<T> *V, unsigned n)
template <typename T>
bool Polygon_complete(const Vector2<T> *V, unsigned n)
{
return (n >= 4 && V[n-1].x == V[0].x && V[n-1].y == V[0].y);
return (n >= 4 && V[n-1] == V[0]);
}
// Necessary to avoid linker errors