Browse Source

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

c415-sdk
Samuel Tabor 4 years ago committed by Tom Pittenger
parent
commit
baf31fd825
  1. 5
      ArduPlane/navigation.cpp

5
ArduPlane/navigation.cpp

@ -203,7 +203,10 @@ void Plane::calc_airspeed_errors() @@ -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

Loading…
Cancel
Save