From f68211a0110a38caa4e3d242311cf0a4be0d0912 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 11 Aug 2012 11:59:03 +1000 Subject: [PATCH] AP_GPS: fixed types to be stdint types --- libraries/AP_GPS/GPS.h | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/libraries/AP_GPS/GPS.h b/libraries/AP_GPS/GPS.h index 3d739c0017..7c3438045e 100644 --- a/libraries/AP_GPS/GPS.h +++ b/libraries/AP_GPS/GPS.h @@ -89,14 +89,14 @@ public: // Properties uint32_t time; ///< GPS time (milliseconds from epoch) - 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 - long ground_speed; ///< ground speed in cm/sec - long ground_course; ///< ground course in 100ths of a degree - long speed_3d; ///< 3D speed in cm/sec (not always available) - int hdop; ///< horizontal dilution of precision in cm + uint32_t date; ///< GPS date (FORMAT TBD) + int32_t latitude; ///< latitude in degrees * 10,000,000 + int32_t longitude; ///< longitude in degrees * 10,000,000 + int32_t altitude; ///< altitude in cm + uint32_t ground_speed; ///< ground speed in cm/sec + int32_t ground_course; ///< ground course in 100ths of a degree + int32_t speed_3d; ///< 3D speed in cm/sec (not always available) + int16_t hdop; ///< horizontal dilution of precision in cm uint8_t num_sats; ///< Number of visible satelites /// Set to true when new data arrives. A client may set this