From ce6dcacb1171b40f68973f185732c542e6d162e0 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 18 Dec 2024 18:44:01 +0000 Subject: [PATCH] AP_Math: buidl fix for templates --- libraries/AP_Math/polygon.cpp | 40 +++++++++++++++++------------------ libraries/AP_Math/vector2.cpp | 9 +------- 2 files changed, 21 insertions(+), 28 deletions(-) diff --git a/libraries/AP_Math/polygon.cpp b/libraries/AP_Math/polygon.cpp index a53a82c253c18..0cca79f944246 100644 --- a/libraries/AP_Math/polygon.cpp +++ b/libraries/AP_Math/polygon.cpp @@ -118,6 +118,26 @@ bool Polygon_complete(const Vector2 *V, unsigned n) return (n >= 4 && V[n-1] == V[0]); } +/* + return the closest distance that point p comes to an edge of closed + polygon V, defined by N points + */ +template +float Polygon_closest_distance_point(const Vector2 *V, unsigned N, const Vector2 &p) +{ + T closest_sq = std::numeric_limits::max(); + for (uint8_t i=0; i &v1 = V[i]; + const Vector2 &v2 = V[i+1]; + + T dist_sq = Vector2::closest_distance_between_line_and_point_squared(v1, v2, p); + if (dist_sq < closest_sq) { + closest_sq = dist_sq; + } + } + return sqrtF(closest_sq); +} + // Necessary to avoid linker errors template bool Polygon_outside(const Vector2l &P, const Vector2l *V, unsigned n); template bool Polygon_complete(const Vector2l *V, unsigned n); @@ -196,23 +216,3 @@ float Polygon_closest_distance_line(const Vector2f *V, unsigned N, const Vector2 } return sqrtf(closest_sq); } - -/* - return the closest distance that point p comes to an edge of closed - polygon V, defined by N points - */ -template -float Polygon_closest_distance_point(const Vector2 *V, unsigned N, const Vector2 &p) -{ - T closest_sq = std::numeric_limits::max(); - for (uint8_t i=0; i &v1 = V[i]; - const Vector2 &v2 = V[i+1]; - - T dist_sq = Vector2::closest_distance_between_line_and_point_squared(v1, v2, p); - if (dist_sq < closest_sq) { - closest_sq = dist_sq; - } - } - return sqrtf(closest_sq); -} diff --git a/libraries/AP_Math/vector2.cpp b/libraries/AP_Math/vector2.cpp index a7e5943a567f4..bffa80ab09ca1 100644 --- a/libraries/AP_Math/vector2.cpp +++ b/libraries/AP_Math/vector2.cpp @@ -20,13 +20,6 @@ #include "AP_Math.h" -template float Vector2f::closest_distance_between_line_and_point_squared(const Vector2f &w1, - const Vector2f &w2, - const Vector2f &p); -template int32_t Vector2l::closest_distance_between_line_and_point_squared(const Vector2l &w1, - const Vector2l &w2, - const Vector2l &p); - template T Vector2::length_squared() const { @@ -464,4 +457,4 @@ template bool Vector2::operator ==(const Vector2 &v) const; template bool Vector2::operator !=(const Vector2 &v) const; template bool Vector2::operator ==(const Vector2 &v) const; template bool Vector2::operator !=(const Vector2 &v) const; - +template int Vector2::closest_distance_between_line_and_point_squared(Vector2 const&, Vector2 const&, Vector2 const&);