mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RTC: move AP_RTC::mktime to be ap_mktime
in preparation for AP_RTC_ENABLED
This commit is contained in:
parent
c89ec67333
commit
84e4a45dc3
@ -3,7 +3,7 @@
|
|||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <time.h>
|
#include <AP_Common/time.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
@ -209,7 +209,7 @@ uint32_t AP_RTC::get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms
|
|||||||
/*
|
/*
|
||||||
mktime replacement from Samba
|
mktime replacement from Samba
|
||||||
*/
|
*/
|
||||||
time_t AP_RTC::mktime(const struct tm *t)
|
time_t ap_mktime(const struct tm *t)
|
||||||
{
|
{
|
||||||
time_t epoch = 0;
|
time_t epoch = 0;
|
||||||
int n;
|
int n;
|
||||||
|
@ -44,9 +44,6 @@ public:
|
|||||||
|
|
||||||
uint32_t get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms);
|
uint32_t get_time_utc(int32_t hour, int32_t min, int32_t sec, int32_t ms);
|
||||||
|
|
||||||
// replacement for mktime()
|
|
||||||
static time_t mktime(const struct tm *t);
|
|
||||||
|
|
||||||
// get singleton instance
|
// get singleton instance
|
||||||
static AP_RTC *get_singleton() {
|
static AP_RTC *get_singleton() {
|
||||||
return _singleton;
|
return _singleton;
|
||||||
|
Loading…
Reference in New Issue
Block a user