mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 09:33:59 -03:00
Plane: Ensure trim airspeed is applied if in auto with no DO_SPEED command received.
This commit is contained in:
parent
7cf4195f86
commit
baf31fd825
@ -203,6 +203,9 @@ void Plane::calc_airspeed_errors()
|
|||||||
// normal AUTO mode and new_airspeed variable was set by DO_CHANGE_SPEED command while in AUTO mode
|
// normal AUTO mode and new_airspeed variable was set by DO_CHANGE_SPEED command while in AUTO mode
|
||||||
if (new_airspeed_cm > 0) {
|
if (new_airspeed_cm > 0) {
|
||||||
target_airspeed_cm = new_airspeed_cm;
|
target_airspeed_cm = new_airspeed_cm;
|
||||||
|
} else {
|
||||||
|
// fallover to normal airspeed
|
||||||
|
target_airspeed_cm = aparm.airspeed_cruise_cm;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
|
Loading…
Reference in New Issue
Block a user