AP_RTC: Don't allow RTC times before 2019
This commit is contained in:
parent
ba3f95ad20
commit
ba3cfbfb54
@ -33,6 +33,8 @@ const AP_Param::GroupInfo AP_RTC::var_info[] = {
|
|||||||
|
|
||||||
void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type)
|
void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type)
|
||||||
{
|
{
|
||||||
|
const uint64_t oldest_acceptable_date = 1546300800000; // 2019-01-01 0:00
|
||||||
|
|
||||||
if (type >= rtc_source_type) {
|
if (type >= rtc_source_type) {
|
||||||
// e.g. system-time message when we've been set by the GPS
|
// e.g. system-time message when we've been set by the GPS
|
||||||
return;
|
return;
|
||||||
@ -43,6 +45,11 @@ void AP_RTC::set_utc_usec(uint64_t time_utc_usec, source_type type)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// don't allow old times
|
||||||
|
if (time_utc_usec < oldest_acceptable_date) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
const uint64_t now = AP_HAL::micros64();
|
const uint64_t now = AP_HAL::micros64();
|
||||||
const int64_t tmp = int64_t(time_utc_usec) - int64_t(now);
|
const int64_t tmp = int64_t(time_utc_usec) - int64_t(now);
|
||||||
if (tmp < rtc_shift) {
|
if (tmp < rtc_shift) {
|
||||||
|
Loading…
Reference in New Issue
Block a user