mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_GPS: fixed types to be stdint types
This commit is contained in:
parent
3419d8e006
commit
8a6fcf998b
@ -89,14 +89,14 @@ public:
|
|||||||
|
|
||||||
// Properties
|
// Properties
|
||||||
uint32_t time; ///< GPS time (milliseconds from epoch)
|
uint32_t time; ///< GPS time (milliseconds from epoch)
|
||||||
long date; ///< GPS date (FORMAT TBD)
|
uint32_t date; ///< GPS date (FORMAT TBD)
|
||||||
long latitude; ///< latitude in degrees * 10,000,000
|
int32_t latitude; ///< latitude in degrees * 10,000,000
|
||||||
long longitude; ///< longitude in degrees * 10,000,000
|
int32_t longitude; ///< longitude in degrees * 10,000,000
|
||||||
long altitude; ///< altitude in cm
|
int32_t altitude; ///< altitude in cm
|
||||||
long ground_speed; ///< ground speed in cm/sec
|
uint32_t ground_speed; ///< ground speed in cm/sec
|
||||||
long ground_course; ///< ground course in 100ths of a degree
|
int32_t ground_course; ///< ground course in 100ths of a degree
|
||||||
long speed_3d; ///< 3D speed in cm/sec (not always available)
|
int32_t speed_3d; ///< 3D speed in cm/sec (not always available)
|
||||||
int hdop; ///< horizontal dilution of precision in cm
|
int16_t hdop; ///< horizontal dilution of precision in cm
|
||||||
uint8_t num_sats; ///< Number of visible satelites
|
uint8_t num_sats; ///< Number of visible satelites
|
||||||
|
|
||||||
/// Set to true when new data arrives. A client may set this
|
/// Set to true when new data arrives. A client may set this
|
||||||
|
Loading…
Reference in New Issue
Block a user