AP_TECS: fixed throttle demand on underspeed

thanks to Philipp Oettershagen for finding this bug!
This commit is contained in:
Andrew Tridgell 2014-11-05 07:55:18 +11:00
parent d6508acfa5
commit 2b48434e60
2 changed files with 1 additions and 4 deletions

View File

@ -455,7 +455,7 @@ void AP_TECS::_update_throttle(void)
// If underspeed condition is set, then demand full throttle
if (_underspeed)
{
_throttle_dem_unc = 1.0f;
_throttle_dem = 1.0f;
}
else
{

View File

@ -206,9 +206,6 @@ private:
// climbout mode
enum FlightStage _flight_stage;
// throttle demand before limiting
float _throttle_dem_unc;
// pitch demand before limiting
float _pitch_dem_unc;