mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_GPS: fixed PX4 GPS driver for new upstream format
This commit is contained in:
parent
406f11423e
commit
d34e5b3f42
@ -67,12 +67,12 @@ 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_gps_usec/1000.+.5);
|
||||
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);
|
||||
|
||||
if (_gps_pos.time_gps_usec == 0) {
|
||||
if (_gps_pos.time_utc_usec == 0) {
|
||||
// This is a work-around for https://github.com/PX4/Firmware/issues/1474
|
||||
// reject position reports with invalid time, as APM adjusts it's clock after the first lock has been aquired
|
||||
state.status = AP_GPS::NO_FIX;
|
||||
|
Loading…
Reference in New Issue
Block a user