From 6e0cceff0d8df300b79a13a0dcff55c3e729aa76 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Tue, 11 Jun 2019 17:17:17 -0700 Subject: [PATCH] AP_Common: Remove extra comparison from longitude_scale() --- libraries/AP_Common/Location.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index 083016c557..4cf553861f 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -271,7 +271,7 @@ void Location::offset_bearing(float bearing, float distance) float Location::longitude_scale() const { float scale = cosf(lat * (1.0e-7f * DEG_TO_RAD)); - return constrain_float(scale, 0.01f, 1.0f); + return MAX(scale, 0.01f); } /*