mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
Add a date field to the standard GPS data. This may be zero, and its format is TBD (may be GPS-dependent).
Increase the no-data timeout to slightly more than a second, so that GPS' with a 1Hz update rate don't cause problems. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1461 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
f5ff57a5b7
commit
fa6ebd23d1
@ -53,7 +53,8 @@ public:
|
||||
virtual void init(void) = 0;
|
||||
|
||||
// Properties
|
||||
long time; ///< GPS time in milliseconds from the start of the week
|
||||
long time; ///< GPS time (FORMAT TBD)
|
||||
long date; ///< GPS date (FORMAT TBD)
|
||||
long latitude; ///< latitude in degrees * 10,000,000
|
||||
long longitude; ///< longitude in degrees * 10,000,000
|
||||
long altitude; ///< altitude in cm
|
||||
@ -127,7 +128,10 @@ private:
|
||||
/// Time in milliseconds after which we will assume the GPS is no longer
|
||||
/// sending us updates and attempt a re-init.
|
||||
///
|
||||
static const unsigned long _idleTimeout = 500;
|
||||
/// 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
|
||||
///
|
||||
|
Loading…
Reference in New Issue
Block a user