mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS_PX4: fixed GPS epoch calculations
This commit is contained in:
parent
5ccd3dfec8
commit
cc4fafc3e4
@ -39,9 +39,9 @@ AP_GPS_PX4::AP_GPS_PX4(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriv
|
||||
}
|
||||
|
||||
|
||||
#define MS_PER_WEEK 7*24*3600*1000LL
|
||||
#define DELTA_POSIX_GPS_EPOCH 315964800LL*1000LL
|
||||
#define LEAP_MS_GPS_2014 16*1000LL
|
||||
const uint64_t MS_PER_WEEK = ((uint64_t)7)*24*3600*1000;
|
||||
const uint64_t DELTA_POSIX_GPS_EPOCH = ((uint64_t)3657)*24*3600*1000;
|
||||
const uint64_t LEAP_MS_GPS_2016 = ((uint64_t)17)*1000;
|
||||
|
||||
// update internal state if new GPS information is available
|
||||
bool
|
||||
@ -68,10 +68,10 @@ AP_GPS_PX4::read(void)
|
||||
|
||||
// convert epoch timestamp back to gps epoch - evil hack until we get the genuine
|
||||
// raw week information (or APM switches to Posix epoch ;-) )
|
||||
uint64_t epoch_ms = uint64_t(_gps_pos.time_utc_usec/1000.+.5);
|
||||
uint64_t gps_ms = epoch_ms - DELTA_POSIX_GPS_EPOCH + LEAP_MS_GPS_2014;
|
||||
state.time_week = uint16_t(gps_ms / uint64_t(MS_PER_WEEK));
|
||||
state.time_week_ms = uint32_t(gps_ms - uint64_t(state.time_week)*MS_PER_WEEK);
|
||||
uint64_t epoch_ms = _gps_pos.time_utc_usec/1000;
|
||||
uint64_t gps_ms = epoch_ms - DELTA_POSIX_GPS_EPOCH + LEAP_MS_GPS_2016;
|
||||
state.time_week = (uint16_t)(gps_ms / MS_PER_WEEK);
|
||||
state.time_week_ms = (uint32_t)(gps_ms - (state.time_week)*MS_PER_WEEK);
|
||||
|
||||
if (_gps_pos.time_utc_usec == 0) {
|
||||
// This is a work-around for https://github.com/PX4/Firmware/issues/1474
|
||||
|
Loading…
Reference in New Issue
Block a user