Browse Source

Fix initialization of idleTimeout

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2602 f9c3cf11-9bcb-44bc-f272-b75c42450872
master
deweibel@gmail.com 14 years ago
parent
commit
b53b749fc7
  1. 2
      libraries/AP_GPS/AP_GPS_406.cpp
  2. 2
      libraries/AP_GPS/AP_GPS_MTK.cpp
  3. 1
      libraries/AP_GPS/AP_GPS_MTK16.cpp
  4. 2
      libraries/AP_GPS/AP_GPS_NMEA.cpp
  5. 1
      libraries/AP_GPS/AP_GPS_SIRF.cpp
  6. 1
      libraries/AP_GPS/AP_GPS_UBLOX.cpp
  7. 2
      libraries/AP_GPS/GPS.cpp

2
libraries/AP_GPS/AP_GPS_406.cpp

@ -27,6 +27,8 @@ void AP_GPS_406::init(void) @@ -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 //////////////////////////////////////////////////////////////

2
libraries/AP_GPS/AP_GPS_MTK.cpp

@ -33,6 +33,8 @@ AP_GPS_MTK::init(void) @@ -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

1
libraries/AP_GPS/AP_GPS_MTK16.cpp

@ -36,6 +36,7 @@ AP_GPS_MTK16::init(void) @@ -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

2
libraries/AP_GPS/AP_GPS_NMEA.cpp

@ -116,6 +116,8 @@ void AP_GPS_NMEA::init(void) @@ -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)

1
libraries/AP_GPS/AP_GPS_SIRF.cpp

@ -40,6 +40,7 @@ AP_GPS_SIRF::init(void) @@ -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

1
libraries/AP_GPS/AP_GPS_UBLOX.cpp

@ -29,6 +29,7 @@ AP_GPS_UBLOX::init(void) @@ -29,6 +29,7 @@ AP_GPS_UBLOX::init(void)
_port->flush();
_epoch = TIME_OF_WEEK;
idleTimeout = 1200;
}
// Process bytes available from the stream

2
libraries/AP_GPS/GPS.cpp

@ -15,8 +15,8 @@ GPS::update(void) @@ -15,8 +15,8 @@ GPS::update(void)
if (!result) {
if ((millis() - _idleTimer) > idleTimeout) {
_status = NO_GPS;
init();
// reset the idle timer
_idleTimer = millis();
}

Loading…
Cancel
Save