mirror of https://github.com/ArduPilot/ardupilot
Plane: Constrain target_airspeed_cm by min as well as max airspeed.
This commit is contained in:
parent
baf31fd825
commit
4cc92c6b3e
|
@ -238,8 +238,7 @@ void Plane::calc_airspeed_errors()
|
|||
}
|
||||
|
||||
// Apply airspeed limit
|
||||
if (target_airspeed_cm > (aparm.airspeed_max * 100))
|
||||
target_airspeed_cm = (aparm.airspeed_max * 100);
|
||||
target_airspeed_cm = constrain_int32(target_airspeed_cm, aparm.airspeed_min*100, aparm.airspeed_max*100);
|
||||
|
||||
// use the TECS view of the target airspeed for reporting, to take
|
||||
// account of the landing speed
|
||||
|
|
Loading…
Reference in New Issue