From 81c5770b777337b93191e924e8414fe3fa1ddab6 Mon Sep 17 00:00:00 2001 From: "tridge60@gmail.com" Date: Mon, 4 Apr 2011 22:00:06 +0000 Subject: [PATCH] GPS: fixed the idle timer we need to reset the idle timer only on good data, or a call to init(). Otherwise we never use it. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1849 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/AP_GPS/GPS.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/libraries/AP_GPS/GPS.cpp b/libraries/AP_GPS/GPS.cpp index 6cff11ec38..a85e936130 100644 --- a/libraries/AP_GPS/GPS.cpp +++ b/libraries/AP_GPS/GPS.cpp @@ -16,6 +16,9 @@ GPS::update(void) if ((millis() - _idleTimer) > _idleTimeout) { _status = NO_GPS; init(); + + // reset the idle timer + _idleTimer = millis(); } } else { // we got a message, update our status correspondingly @@ -23,10 +26,10 @@ GPS::update(void) valid_read = true; new_data = true; - } - // reset the idle timer - _idleTimer = millis(); + // reset the idle timer + _idleTimer = millis(); + } } void