diff --git a/libraries/AP_GPS/AP_GPS_406.cpp b/libraries/AP_GPS/AP_GPS_406.cpp index 379d096cdd..5e9cb9f675 100644 --- a/libraries/AP_GPS/AP_GPS_406.cpp +++ b/libraries/AP_GPS/AP_GPS_406.cpp @@ -27,6 +27,8 @@ void AP_GPS_406::init(void) _configure_gps(); // Function to configure GPS, to output only the desired msg's AP_GPS_SIRF::init(); // let the superclass do anything it might need here + + idleTimeout = 1200; } // Private Methods ////////////////////////////////////////////////////////////// diff --git a/libraries/AP_GPS/AP_GPS_MTK.cpp b/libraries/AP_GPS/AP_GPS_MTK.cpp index 3f1a5cec46..6375f61ab6 100644 --- a/libraries/AP_GPS/AP_GPS_MTK.cpp +++ b/libraries/AP_GPS/AP_GPS_MTK.cpp @@ -33,6 +33,8 @@ AP_GPS_MTK::init(void) // set initial epoch code _epoch = TIME_OF_DAY; + + idleTimeout = 1200; } // Process bytes available from the stream diff --git a/libraries/AP_GPS/AP_GPS_MTK16.cpp b/libraries/AP_GPS/AP_GPS_MTK16.cpp index 47a8b86beb..bf7180f112 100644 --- a/libraries/AP_GPS/AP_GPS_MTK16.cpp +++ b/libraries/AP_GPS/AP_GPS_MTK16.cpp @@ -36,6 +36,7 @@ AP_GPS_MTK16::init(void) _epoch = TIME_OF_DAY; _time_offset = 0; _offset_calculated = false; + idleTimeout = 1200; } // Process bytes available from the stream diff --git a/libraries/AP_GPS/AP_GPS_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index 119ead871c..9748d20743 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -116,6 +116,8 @@ void AP_GPS_NMEA::init(void) // send the ublox init strings bs->print_P((const prog_char_t *)_ublox_init_string); + + idleTimeout = 1200; } bool AP_GPS_NMEA::read(void) diff --git a/libraries/AP_GPS/AP_GPS_SIRF.cpp b/libraries/AP_GPS/AP_GPS_SIRF.cpp index 65fbb25c41..4b247153ca 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.cpp +++ b/libraries/AP_GPS/AP_GPS_SIRF.cpp @@ -40,6 +40,7 @@ AP_GPS_SIRF::init(void) // send SiRF binary setup messages _port->write(init_messages, sizeof(init_messages)); + idleTimeout = 1200; } // Process bytes available from the stream diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index ae1361ddd6..74339f87de 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -29,6 +29,7 @@ AP_GPS_UBLOX::init(void) _port->flush(); _epoch = TIME_OF_WEEK; + idleTimeout = 1200; } // Process bytes available from the stream diff --git a/libraries/AP_GPS/GPS.cpp b/libraries/AP_GPS/GPS.cpp index 55fbdcde19..57502643da 100644 --- a/libraries/AP_GPS/GPS.cpp +++ b/libraries/AP_GPS/GPS.cpp @@ -15,8 +15,8 @@ GPS::update(void) if (!result) { if ((millis() - _idleTimer) > idleTimeout) { _status = NO_GPS; + init(); - // reset the idle timer _idleTimer = millis(); }