Copter: gps failsafe on lengthy glitches

This commit is contained in:
Randy Mackay 2013-09-22 22:21:57 +09:00
parent 4c8227c050
commit 29b30cf752
1 changed files with 1 additions and 1 deletions

View File

@ -138,7 +138,7 @@ static void failsafe_gps_check()
}
// calc time since last gps update
last_gps_update_ms = millis() - g_gps->last_fix_time;
last_gps_update_ms = millis() - gps_glitch.last_good_update();
// check if all is well
if( last_gps_update_ms < FAILSAFE_GPS_TIMEOUT_MS) {