mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: Updated highest airspeed limit when armed
This commit is contained in:
parent
71cc0dc02d
commit
ec2a33589c
@ -9,7 +9,7 @@ float Plane::calc_speed_scaler(void)
|
||||
{
|
||||
float aspeed, speed_scaler;
|
||||
if (ahrs.airspeed_estimate(aspeed)) {
|
||||
if (aspeed > auto_state.highest_airspeed) {
|
||||
if (aspeed > auto_state.highest_airspeed && hal.util->get_soft_armed()) {
|
||||
auto_state.highest_airspeed = aspeed;
|
||||
}
|
||||
if (aspeed > 0.0001f) {
|
||||
|
Loading…
Reference in New Issue
Block a user