AP_GPS: move AP_RTC::mktime to be ap_mktime

in preparation for AP_RTC_ENABLED
This commit is contained in:
Peter Barker 2023-06-22 14:21:43 +10:00 committed by Andrew Tridgell
parent ac2fea9766
commit c89ec67333
1 changed files with 2 additions and 2 deletions

View File

@ -17,7 +17,7 @@
#include "GPS_Backend.h"
#include <AP_Logger/AP_Logger.h>
#include <time.h>
#include <AP_RTC/AP_RTC.h>
#include <AP_Common/time.h>
#include <AP_InternalError/AP_InternalError.h>
#define GPS_BACKEND_DEBUGGING 0
@ -96,7 +96,7 @@ void AP_GPS_Backend::make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
tm.tm_hour = v % 100U;
// convert from time structure to unix time
time_t unix_time = AP::rtc().mktime(&tm);
time_t unix_time = ap_mktime(&tm);
// convert to time since GPS epoch
const uint32_t unix_to_GPS_secs = 315964800UL;