made timeout public, settable

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2563 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-06-16 16:33:08 +00:00
parent cb7da41e55
commit dafe217178
3 changed files with 17 additions and 15 deletions

View File

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

@ -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();
@ -32,7 +32,7 @@ GPS::update(void)
}
}
void
void
GPS::setHIL(long _time, float _latitude, float _longitude, float _altitude,
float _ground_speed, float _ground_course, float _speed_3d, uint8_t _num_sats)
{

View File

@ -46,12 +46,12 @@ public:
/// GPS time epoch codes
///
enum GPS_Time_Epoch {
TIME_OF_DAY = 0, ///<
TIME_OF_DAY = 0, ///<
TIME_OF_WEEK = 1, ///< Ublox
TIME_OF_YEAR = 2, ///< MTK, NMEA
UNIX_EPOCH = 3 ///< If available
}; ///< SIFR?
}; ///< SIFR?
/// Query GPS time epoch
///
@ -91,11 +91,19 @@ public:
// Debug support
bool print_errors; ///< deprecated
// HIL support
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
@ -142,19 +150,12 @@ protected:
/// printf vs. the potential benefits
///
void _error(const char *msg);
/// Time epoch code for the gps in use
GPS_Time_Epoch _epoch;
private:
/// 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 const unsigned long _idleTimeout = 1200;
/// Last time that the GPS driver got a good packet from the GPS
///
@ -162,7 +163,7 @@ private:
/// Our current status
GPS_Status _status;
};
inline long