From 2c0e8515d5bc2311d019e9a32223386c9277a9de Mon Sep 17 00:00:00 2001 From: DrZiplok Date: Mon, 10 Jan 2011 00:44:09 +0000 Subject: [PATCH] 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 --- libraries/AP_GPS/GPS.h | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/libraries/AP_GPS/GPS.h b/libraries/AP_GPS/GPS.h index 2fcb8c4a2c..cd6aea6037 100644 --- a/libraries/AP_GPS/GPS.h +++ b/libraries/AP_GPS/GPS.h @@ -29,8 +29,8 @@ public: /// \note Non-intuitive ordering for legacy reasons /// enum GPS_Status { - NO_GPS = 0, ///< No GPS connected/detected - NO_FIX = 1, ///< Receiving valid GPS messages but no lock + NO_GPS = 0, ///< No GPS connected/detected + NO_FIX = 1, ///< Receiving valid GPS messages but no lock GPS_OK = 2 ///< Receiving valid messages and locked }; @@ -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 @@ -83,7 +84,7 @@ protected: /// @note The stream is expected to be set up and configured for the /// correct bitrate before ::init is called. /// - /// @param s Stream connected to the GPS module. + /// @param s Stream connected to the GPS module. /// GPS(Stream *s) : _port(s) {}; @@ -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 ///