mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RTC: fixed ms value from AP_RTC::get_date_and_time_utc
this impacts the ViewPro mount driver
This commit is contained in:
parent
d1ad9ccfbb
commit
e4a27943f5
@ -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] */
|
hour = tm->tm_hour; /* Hours. [0-23] */
|
||||||
min = tm->tm_min; /* Minutes. [0-59] */
|
min = tm->tm_min; /* Minutes. [0-59] */
|
||||||
sec = tm->tm_sec; /* Seconds. [0-60] (1 leap second) */
|
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;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user