From f46cb6fd2d447e3b80d298d8bd7f58223139c0d6 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Wed, 2 Oct 2024 08:56:30 +0900 Subject: [PATCH] AC_WPNav: fixes from lthall --- libraries/AC_WPNav/AC_Circle.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_WPNav/AC_Circle.cpp b/libraries/AC_WPNav/AC_Circle.cpp index d42f1a124a3c40..33d6964d6912aa 100644 --- a/libraries/AC_WPNav/AC_Circle.cpp +++ b/libraries/AC_WPNav/AC_Circle.cpp @@ -249,7 +249,7 @@ void AC_Circle::get_closest_point_on_circle(Vector3f& result, float& dist_cm) co dist_cm = vec.length(); // return center if radius is zero - if (_radius <= 0) { + if (!is_positive(_radius)) { result = _center.tofloat(); return; }