Browse Source

AP_TECS: fixed throttle demand on underspeed

thanks to Philipp Oettershagen for finding this bug!
master
Andrew Tridgell 10 years ago
parent
commit
2b48434e60
  1. 2
      libraries/AP_TECS/AP_TECS.cpp
  2. 3
      libraries/AP_TECS/AP_TECS.h

2
libraries/AP_TECS/AP_TECS.cpp

@ -455,7 +455,7 @@ void AP_TECS::_update_throttle(void) @@ -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
{

3
libraries/AP_TECS/AP_TECS.h

@ -206,9 +206,6 @@ private: @@ -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;

Loading…
Cancel
Save