mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: fixed GPS time in HIL
account for 10 year difference in epoch between unix time and GPS time
This commit is contained in:
parent
effccacf46
commit
cd50fe82b6
|
@ -393,8 +393,9 @@ AP_GPS::setHIL(uint8_t instance, GPS_Status _status, uint64_t time_epoch_ms,
|
|||
istate.num_sats = _num_sats;
|
||||
istate.have_vertical_velocity = _have_vertical_velocity;
|
||||
istate.last_gps_time_ms = tnow;
|
||||
istate.time_week = time_epoch_ms / (86400*7*(uint64_t)1000);
|
||||
istate.time_week_ms = time_epoch_ms - istate.time_week*(86400*7*(uint64_t)1000);
|
||||
uint64_t gps_time_ms = time_epoch_ms - (17000ULL*86400ULL + 52*10*7000ULL*86400ULL - 15000ULL);
|
||||
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);
|
||||
timing[instance].last_message_time_ms = tnow;
|
||||
timing[instance].last_fix_time_ms = tnow;
|
||||
_type[instance].set(GPS_TYPE_HIL);
|
||||
|
|
Loading…
Reference in New Issue