mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-03 06:28:32 -04:00
AP_GPS: use AP_RTC
set the system time from a GPS if we have a 3D fix or better
This commit is contained in:
parent
721feaf40f
commit
5b41db5120
@ -671,6 +671,11 @@ void AP_GPS::update_instance(uint8_t instance)
|
||||
!AP::ahrs().have_ekf_logging()) {
|
||||
DataFlash_Class::instance()->Log_Write_GPS(instance);
|
||||
}
|
||||
|
||||
if (state[instance].status >= GPS_OK_FIX_3D) {
|
||||
const uint64_t now = time_epoch_usec(instance);
|
||||
AP::rtc().set_utc_usec(now, AP_RTC::SOURCE_GPS);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -22,6 +22,7 @@
|
||||
#include <AP_Vehicle/AP_Vehicle.h>
|
||||
#include "GPS_detect_state.h"
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <AP_RTC/AP_RTC.h>
|
||||
|
||||
/**
|
||||
maximum number of GPS instances available on this platform. If more
|
||||
@ -556,7 +557,6 @@ private:
|
||||
GPS_AUTO_CONFIG_DISABLE = 0,
|
||||
GPS_AUTO_CONFIG_ENABLE = 1
|
||||
};
|
||||
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
|
Loading…
Reference in New Issue
Block a user