|
|
|
@ -52,30 +52,24 @@ void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type)
@@ -52,30 +52,24 @@ void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type)
|
|
|
|
|
//////////////////////////////////////
|
|
|
|
|
const uint64_t oldest_acceptable_date_us = 1640995200ULL*1000*1000; // 2022-01-01 0:00
|
|
|
|
|
|
|
|
|
|
if (type >= rtc_source_type) { |
|
|
|
|
// e.g. system-time message when we've been set by the GPS
|
|
|
|
|
if (need_prt) |
|
|
|
|
{ |
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "type{%d} >= rtc_source_type{%d}",type , (uint8_t)rtc_source_type); |
|
|
|
|
get_rtc_date(); |
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "type:%d,utc:%lld,now:%lld",type ,time_utc_usec,AP_HAL::micros64()); |
|
|
|
|
} |
|
|
|
|
if (type >= rtc_source_type && !need_prt) { |
|
|
|
|
// e.g. system-time message when we've been set by the GPS
|
|
|
|
|
|
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// check it's from an allowed sources:
|
|
|
|
|
if (!(allowed_types & (1<<type))) { |
|
|
|
|
if (need_prt) |
|
|
|
|
{ |
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "!(allowed_types{%d}& (1<<type{%d}))",(uint8_t)allowed_types,(uint8_t)type); |
|
|
|
|
} |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// don't allow old times
|
|
|
|
|
if (time_utc_usec < oldest_acceptable_date_us) { |
|
|
|
|
if (need_prt) |
|
|
|
|
{ |
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "time_utc_usec < oldest_acceptable_date_us"); |
|
|
|
|
} |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -83,12 +77,20 @@ void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type)
@@ -83,12 +77,20 @@ void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type)
|
|
|
|
|
const int64_t tmp = int64_t(time_utc_usec) - int64_t(now); |
|
|
|
|
if (tmp < rtc_shift) { |
|
|
|
|
// can't allow time to go backwards, ever
|
|
|
|
|
if (need_prt) |
|
|
|
|
static uint8_t sh_cnt; |
|
|
|
|
sh_cnt += 1; |
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "tmp-shift:%lld - %lld",tmp , rtc_shift); |
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "now-utc:%lld - %lld",now , time_utc_usec); |
|
|
|
|
if (sh_cnt > 5) |
|
|
|
|
{ |
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "tmp{%lld} < rtc_shift{%lld}",tmp , rtc_shift); |
|
|
|
|
sh_cnt = 0; |
|
|
|
|
goto Forc_Shift; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
Forc_Shift: |
|
|
|
|
WITH_SEMAPHORE(rsem); |
|
|
|
|
|
|
|
|
|
rtc_shift = tmp; |
|
|
|
@ -100,10 +102,9 @@ void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type)
@@ -100,10 +102,9 @@ void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type)
|
|
|
|
|
|
|
|
|
|
rtc_source_type = type; |
|
|
|
|
|
|
|
|
|
if (need_prt) |
|
|
|
|
{ |
|
|
|
|
|
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "type:%d,in utc:%lld,rtc_shift:%lld",type,time_utc_usec,rtc_shift); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#if HAL_GCS_ENABLED |
|
|
|
|
// update signing timestamp
|
|
|
|
|
GCS_MAVLINK::update_signing_timestamp(time_utc_usec); |
|
|
|
@ -251,7 +252,9 @@ char* AP_RTC::get_rtc_date(void)
@@ -251,7 +252,9 @@ char* AP_RTC::get_rtc_date(void)
|
|
|
|
|
min = uint8_t(localtime_tm.tm_min); |
|
|
|
|
sec = uint8_t(localtime_tm.tm_sec); |
|
|
|
|
static char buf[50]; |
|
|
|
|
snprintf(buf, sizeof(buf), "%04d%02d%02d%02d%02d%02d",year,mon,mday,hour,min,sec); |
|
|
|
|
snprintf(buf, sizeof(buf), "%04d-%02d-%02d %02d:%02d:%02d",year,mon,mday,hour,min,sec); |
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "get_rtc: %lld,%s",time_usec,buf); |
|
|
|
|
|
|
|
|
|
return buf; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|