From 9548f6ebb12f568c0c097b99baf8c4f8515c63e7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 9 Dec 2023 09:46:44 +1100 Subject: [PATCH] AP_RTC: fixed ms value from AP_RTC::get_date_and_time_utc this impacts the ViewPro mount driver --- libraries/AP_RTC/AP_RTC.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_RTC/AP_RTC.cpp b/libraries/AP_RTC/AP_RTC.cpp index d695e57420ad9..41d9f5b294470 100644 --- a/libraries/AP_RTC/AP_RTC.cpp +++ b/libraries/AP_RTC/AP_RTC.cpp @@ -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; }