AP_GPS: Update the number of leapseconds

This commit is contained in:
Michael du Breuil 2017-01-10 02:58:42 -07:00 committed by Francisco Ferreira
parent cb1f7ba4bb
commit c696137a42
3 changed files with 6 additions and 3 deletions

View File

@ -590,7 +590,7 @@ AP_GPS::setHIL(uint8_t instance, GPS_Status _status, uint64_t time_epoch_ms,
istate.hdop = hdop; istate.hdop = hdop;
istate.num_sats = _num_sats; istate.num_sats = _num_sats;
istate.last_gps_time_ms = tnow; istate.last_gps_time_ms = tnow;
uint64_t gps_time_ms = time_epoch_ms - (17000ULL*86400ULL + 52*10*7000ULL*86400ULL - 15000ULL); uint64_t gps_time_ms = time_epoch_ms - (17000ULL*86400ULL + 52*10*7000ULL*86400ULL - GPS_LEAPSECONDS_MILLIS);
istate.time_week = gps_time_ms / (86400*7*(uint64_t)1000); istate.time_week = gps_time_ms / (86400*7*(uint64_t)1000);
istate.time_week_ms = gps_time_ms - istate.time_week*(86400*7*(uint64_t)1000); istate.time_week_ms = gps_time_ms - istate.time_week*(86400*7*(uint64_t)1000);
timing[instance].last_message_time_ms = tnow; timing[instance].last_message_time_ms = tnow;

View File

@ -31,6 +31,9 @@
#define GPS_MAX_INSTANCES 2 #define GPS_MAX_INSTANCES 2
#define GPS_RTK_INJECT_TO_ALL 127 #define GPS_RTK_INJECT_TO_ALL 127
// the number of GPS leap seconds
#define GPS_LEAPSECONDS_MILLIS 18000ULL
class DataFlash_Class; class DataFlash_Class;
class AP_GPS_Backend; class AP_GPS_Backend;

View File

@ -64,7 +64,7 @@ int16_t AP_GPS_Backend::swap_int16(int16_t v) const
uint64_t AP_GPS::time_epoch_convert(uint16_t gps_week, uint32_t gps_ms) uint64_t AP_GPS::time_epoch_convert(uint16_t gps_week, uint32_t gps_ms)
{ {
const uint64_t ms_per_week = 7000ULL*86400ULL; const uint64_t ms_per_week = 7000ULL*86400ULL;
const uint64_t unix_offset = 17000ULL*86400ULL + 52*10*7000ULL*86400ULL - 15000ULL; const uint64_t unix_offset = 17000ULL*86400ULL + 52*10*7000ULL*86400ULL - GPS_LEAPSECONDS_MILLIS;
uint64_t fix_time_ms = unix_offset + gps_week*ms_per_week + gps_ms; uint64_t fix_time_ms = unix_offset + gps_week*ms_per_week + gps_ms;
return fix_time_ms; return fix_time_ms;
} }
@ -110,7 +110,7 @@ void AP_GPS_Backend::make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
} }
// get time in seconds since unix epoch // get time in seconds since unix epoch
uint32_t ret = (year/4) - 15 + 367*rmon/12 + day; uint32_t ret = (year/4) - (GPS_LEAPSECONDS_MILLIS / 1000UL) + 367*rmon/12 + day;
ret += year*365 + 10501; ret += year*365 + 10501;
ret = ret*24 + hour; ret = ret*24 + hour;
ret = ret*60 + min; ret = ret*60 + min;