From 8fff32bde3611e3bf0dbe7fb2db80fa4a35f3131 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Tue, 31 May 2016 16:08:36 +0900 Subject: [PATCH] AP_MotorsSingle: fix stability patch use of throttle_hover --- libraries/AP_Motors/AP_MotorsSingle.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_MotorsSingle.cpp b/libraries/AP_Motors/AP_MotorsSingle.cpp index ca881723a6..0368b156ec 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.cpp +++ b/libraries/AP_Motors/AP_MotorsSingle.cpp @@ -274,7 +274,7 @@ void AP_MotorsSingle::output_armed_stabilizing() } // 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.5,_thrust_out); // force of a lifting surface is approximately equal to the angle of attack times the airflow velocity squared // static thrust is proportional to the airflow velocity squared