From a1ce8dafb09f40cd6f25bd4c7cb811a8b798a2bf Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 9 Sep 2019 15:34:39 +1000 Subject: [PATCH] Copter: wrap_180_cd no longer returns floats for integer arguments --- ArduCopter/mode_rtl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index 7793951f34..6c332ad5a8 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -242,7 +242,7 @@ void ModeRTL::loiterathome_run() if ((millis() - _loiter_start_time) >= (uint32_t)g.rtl_loiter_time.get()) { if (auto_yaw.mode() == AUTO_YAW_RESETTOARMEDYAW) { // check if heading is within 2 degrees of heading when vehicle was armed - if (fabsf(wrap_180_cd(ahrs.yaw_sensor-copter.initial_armed_bearing)) <= 200) { + if (abs(wrap_180_cd(ahrs.yaw_sensor-copter.initial_armed_bearing)) <= 200) { _state_complete = true; } } else {