From 4ec11f608d083a3d1933cf1b48c1b98605b0b1d6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 18 Feb 2019 13:06:42 +1100 Subject: [PATCH] AC_Landing: use abs not fabsf for integers --- libraries/AP_Landing/AP_Landing_Deepstall.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Landing/AP_Landing_Deepstall.cpp b/libraries/AP_Landing/AP_Landing_Deepstall.cpp index 53f54698d7..0c0234b598 100644 --- a/libraries/AP_Landing/AP_Landing_Deepstall.cpp +++ b/libraries/AP_Landing/AP_Landing_Deepstall.cpp @@ -187,7 +187,7 @@ bool AP_Landing_Deepstall::verify_land(const Location &prev_WP_loc, Location &ne { switch (stage) { case DEEPSTALL_STAGE_FLY_TO_LANDING: - if (get_distance(current_loc, landing_point) > fabsf(2 * landing.aparm.loiter_radius)) { + if (get_distance(current_loc, landing_point) > abs(2 * landing.aparm.loiter_radius)) { landing.nav_controller->update_waypoint(current_loc, landing_point); return false; }