Browse Source

AP_Math: polygon.cpp correct float comparison

master
Pierre Kancir 8 years ago committed by Tom Pittenger
parent
commit
6bf1322633
  1. 2
      libraries/AP_Math/polygon.cpp

2
libraries/AP_Math/polygon.cpp

@ -88,7 +88,7 @@ bool Polygon_outside(const Vector2<T> &P, const Vector2<T> *V, unsigned n) @@ -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

Loading…
Cancel
Save