mirror of https://github.com/ArduPilot/ardupilot
GPS time set to unsigned int32
This commit is contained in:
parent
826cffe688
commit
1ebfb8fe25
|
@ -30,7 +30,7 @@ public:
|
|||
/// defines a member function set_<variable>(<type>)
|
||||
///
|
||||
#define __GPS_SHIM_SET(__type, __name) void set_##__name(__type v) { __name = v; _updated = true; }
|
||||
__GPS_SHIM_SET(long, time);
|
||||
__GPS_SHIM_SET(uint32_t, time);
|
||||
__GPS_SHIM_SET(long, latitude);
|
||||
__GPS_SHIM_SET(long, longitude);
|
||||
__GPS_SHIM_SET(long, altitude);
|
||||
|
|
|
@ -75,7 +75,7 @@ public:
|
|||
virtual void init(void) = 0;
|
||||
|
||||
// Properties
|
||||
long time; ///< GPS time (milliseconds from epoch)
|
||||
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
|
||||
|
|
Loading…
Reference in New Issue