diff --git a/libraries/AP_Math/polygon.cpp b/libraries/AP_Math/polygon.cpp index 6897b156a7..ae111c5dae 100644 --- a/libraries/AP_Math/polygon.cpp +++ b/libraries/AP_Math/polygon.cpp @@ -128,11 +128,12 @@ template bool Polygon_complete(const Vector2f *V, unsigned n); /* determine if the polygon of N verticies defined by points V is intersected by a line from point p1 to point p2 + intersection argument returns the intersection closest to p1 */ -bool Polygon_intersects(const Vector2f *V, unsigned N, const Vector2f &p1, const Vector2f &p2) +bool Polygon_intersects(const Vector2f *V, unsigned N, const Vector2f &p1, const Vector2f &p2, Vector2f &intersection) { + float intersect_dist_sq = FLT_MAX; for (uint8_t i=0; i *V, unsigned n); /* determine if the polygon of N verticies defined by points V is intersected by a line from point p1 to point p2 + intersection argument returns the intersection closest to p1 */ -bool Polygon_intersects(const Vector2f *V, unsigned N, const Vector2f &p1, const Vector2f &p2); +bool Polygon_intersects(const Vector2f *V, unsigned N, const Vector2f &p1, const Vector2f &p2, Vector2f &intersection); /* return the closest distance that a line from p1 to p2 comes to an edge of closed polygon V, defined by N points + negative numbers indicate the line cross into the polygon with the negative size being the distance from p2 to the intersection point closest to p1 */ float Polygon_closest_distance_line(const Vector2f *V, unsigned N, const Vector2f &p1, const Vector2f &p2);