Plane: Ensure trim airspeed is applied if in auto with no DO_SPEED command received.

This commit is contained in:
Samuel Tabor 2021-04-13 22:52:36 +01:00 committed by Tom Pittenger
parent 7cf4195f86
commit baf31fd825

View File

@ -203,7 +203,10 @@ void Plane::calc_airspeed_errors()
// normal AUTO mode and new_airspeed variable was set by DO_CHANGE_SPEED command while in AUTO mode
if (new_airspeed_cm > 0) {
target_airspeed_cm = new_airspeed_cm;
}
} else {
// fallover to normal airspeed
target_airspeed_cm = aparm.airspeed_cruise_cm;
}
}
} else {
// Normal airspeed target for all other cases