Plane: make the 90x factor more obvios

This commit is contained in:
Andrew Tridgell 2024-01-20 10:19:39 +11:00
parent f6ff3b2fbb
commit 649fbe9f24
1 changed files with 1 additions and 1 deletions

View File

@ -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);