From c24759d3df5d082d9005b4e966f0ec6f5ab3f2b6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 18 Feb 2019 13:04:51 +1100 Subject: [PATCH] Plane: use abs not fabsf for integers --- ArduPlane/commands_logic.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index ced1b170c2..cc259f3a28 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -1055,7 +1055,7 @@ bool Plane::verify_loiter_heading(bool init) return true; } - if (get_distance(next_WP_loc, next_nav_cmd.content.location) < fabsf(aparm.loiter_radius)) { + if (get_distance(next_WP_loc, next_nav_cmd.content.location) < abs(aparm.loiter_radius)) { /* Whenever next waypoint is within the loiter radius, maintaining loiter would prevent us from ever pointing toward the next waypoint. Hence break out of loiter immediately