AP_RTC: fixed ms value from AP_RTC::get_date_and_time_utc

this impacts the ViewPro mount driver
This commit is contained in:
Andrew Tridgell 2023-12-09 09:46:44 +11:00
parent d1ad9ccfbb
commit e4a27943f5
1 changed files with 1 additions and 1 deletions

View File

@ -229,7 +229,7 @@ bool AP_RTC::get_date_and_time_utc(uint16_t& year, uint8_t& month, uint8_t& day,
hour = tm->tm_hour; /* Hours. [0-23] */
min = tm->tm_min; /* Minutes. [0-59] */
sec = tm->tm_sec; /* Seconds. [0-60] (1 leap second) */
ms = time_us / 1000U; /* milliseconds [0-999] */
ms = (time_us / 1000U) % 1000U; /* milliseconds [0-999] */
return true;
}