From cc86011d20708d59f66689e332d12f484729a9e4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 20 Oct 2016 13:30:55 +1100 Subject: [PATCH] Copter: use abs() on integers; Location alts are in integer cm --- ArduCopter/control_rtl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/control_rtl.cpp b/ArduCopter/control_rtl.cpp index 650b922792..8703ec7ed7 100644 --- a/ArduCopter/control_rtl.cpp +++ b/ArduCopter/control_rtl.cpp @@ -335,7 +335,7 @@ void Copter::rtl_descent_run() attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate, get_smoothing_gain()); // check if we've reached within 20cm of final altitude - rtl_state_complete = fabsf(rtl_path.descent_target.alt - current_loc.alt) < 20.0f; + rtl_state_complete = abs(rtl_path.descent_target.alt - current_loc.alt) < 20; } // rtl_loiterathome_start - initialise controllers to loiter over home