Plane: only call TECS when throttle is not suppressed

this helps prevent integrator buildup on the ground
This commit is contained in:
Andrew Tridgell 2013-07-06 12:26:07 +10:00
parent 649cbf6b68
commit 9f612f6f78
1 changed files with 4 additions and 2 deletions

View File

@ -785,7 +785,8 @@ static void fast_loop()
*/
static void update_speed_height(void)
{
if (g.alt_control_algorithm == ALT_CONTROL_TECS && auto_throttle_mode) {
if (g.alt_control_algorithm == ALT_CONTROL_TECS &&
auto_throttle_mode && !throttle_suppressed) {
// Call TECS 50Hz update
SpdHgt_Controller->update_50hz();
}
@ -1248,7 +1249,8 @@ static void update_alt()
// add_altitude_data(millis() / 100, g_gps->altitude / 10);
// Update the speed & height controller states
if (g.alt_control_algorithm == ALT_CONTROL_TECS && auto_throttle_mode) {
if (g.alt_control_algorithm == ALT_CONTROL_TECS &&
auto_throttle_mode && !throttle_suppressed) {
SpdHgt_Controller->update_pitch_throttle(target_altitude_cm - home.alt, target_airspeed_cm,
(control_mode==AUTO && takeoff_complete == false),
takeoff_pitch_cd);