AP_Math: polygon.cpp correct float comparison
This commit is contained in:
parent
5900653b7f
commit
6bf1322633
@ -88,7 +88,7 @@ bool Polygon_outside(const Vector2<T> &P, const Vector2<T> *V, unsigned n)
|
|||||||
template <typename T>
|
template <typename T>
|
||||||
bool Polygon_complete(const Vector2<T> *V, unsigned n)
|
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
|
// Necessary to avoid linker errors
|
||||||
|
Loading…
Reference in New Issue
Block a user