clean up idleTimeout

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2606 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
deweibel@gmail.com 2011-06-21 01:20:39 +00:00
parent b53b749fc7
commit 5b9e7eff9d
9 changed files with 14 additions and 19 deletions

View File

@ -27,8 +27,6 @@ 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 //////////////////////////////////////////////////////////////

View File

@ -36,7 +36,6 @@ AP_GPS_Auto::AP_GPS_Auto(FastSerial *s, GPS **gps) :
void
AP_GPS_Auto::init(void)
{
idleTimeout = 1200;
}
// Called the first time that a client tries to kick the GPS to update.

View File

@ -33,8 +33,6 @@ AP_GPS_MTK::init(void)
// set initial epoch code
_epoch = TIME_OF_DAY;
idleTimeout = 1200;
}
// Process bytes available from the stream

View File

@ -36,7 +36,6 @@ AP_GPS_MTK16::init(void)
_epoch = TIME_OF_DAY;
_time_offset = 0;
_offset_calculated = false;
idleTimeout = 1200;
}
// Process bytes available from the stream

View File

@ -116,8 +116,6 @@ 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)

View File

@ -40,7 +40,6 @@ 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

View File

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

View File

@ -13,7 +13,7 @@ GPS::update(void)
// if we did not get a message, and the idle timer has expired, re-init
if (!result) {
if ((millis() - _idleTimer) > idleTimeout) {
if ((millis() - _idleTimer) > _idleTimeout) {
_status = NO_GPS;
init();

View File

@ -85,6 +85,10 @@ public:
/// already seen.
bool new_data;
/// Update the idle timeout value
///
void setIdleTimeout(unsigned long ms) { _idleTimeout = ms; }
// Deprecated properties
bool fix; ///< true if we have a position fix (use ::status instead)
bool valid_read; ///< true if we have seen data from the GPS (use ::status instead)
@ -96,14 +100,6 @@ public:
virtual void setHIL(long time, float latitude, float longitude, float altitude,
float ground_speed, float ground_course, float speed_3d, uint8_t num_sats);
/// Time in milliseconds after which we will assume the GPS is no longer
/// sending us updates and attempt a re-init.
///
/// 1200ms allows a small amount of slack over the worst-case 1Hz update
/// rate.
///
unsigned long idleTimeout;
protected:
Stream *_port; ///< port the GPS is attached to
@ -160,6 +156,15 @@ private:
/// Last time that the GPS driver got a good packet from the GPS
///
unsigned long _idleTimer;
/// Time in milliseconds after which we will assume the GPS is no longer
/// sending us updates and attempt a re-init.
///
/// 1200ms allows a small amount of slack over the worst-case 1Hz update
/// rate.
///
static unsigned long _idleTimeout;
/// Our current status
GPS_Status _status;