From da059028051dc1ccc49e0d4c5724cf4bb968a30e Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Tue, 31 May 2016 16:08:25 +0900 Subject: [PATCH] AP_MotorsCoax: fix stability patch use of throttle_hover --- libraries/AP_Motors/AP_MotorsCoax.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_MotorsCoax.cpp b/libraries/AP_Motors/AP_MotorsCoax.cpp index ba411a22cb..d06f5a93f5 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.cpp +++ b/libraries/AP_Motors/AP_MotorsCoax.cpp @@ -238,7 +238,7 @@ void AP_MotorsCoax::output_armed_stabilizing() _thrust_yt_cw = thrust_out - 0.5f * yaw_thrust; // limit thrust out for calculation of actuator gains - float thrust_out_actuator = MAX(throttle_thrust_hover*0.5,thrust_out); + float thrust_out_actuator = MAX(_throttle_hover*0.5f,thrust_out); if (is_zero(thrust_out_actuator)) { limit.roll_pitch = true;