diff --git a/ArduPlane/is_flying.cpp b/ArduPlane/is_flying.cpp index 52b840436f..b857d8b7af 100644 --- a/ArduPlane/is_flying.cpp +++ b/ArduPlane/is_flying.cpp @@ -18,7 +18,7 @@ void Plane::update_is_flying_5Hz(void) bool is_flying_bool = false; uint32_t now_ms = AP_HAL::millis(); - uint32_t ground_speed_thresh_cm = (aparm.min_groundspeed > 0) ? ((uint32_t)(aparm.min_groundspeed*90)) : GPS_IS_FLYING_SPEED_CMS; + uint32_t ground_speed_thresh_cm = (aparm.min_groundspeed > 0) ? ((uint32_t)(aparm.min_groundspeed*(100*0.9))) : GPS_IS_FLYING_SPEED_CMS; bool gps_confirmed_movement = (gps.status() >= AP_GPS::GPS_OK_FIX_3D) && (gps.ground_speed_cm() >= ground_speed_thresh_cm);