Skip to content

Commit

Permalink
AP_RTC: fixed ms value from AP_RTC::get_date_and_time_utc
Browse files Browse the repository at this point in the history
this impacts the ViewPro mount driver
  • Loading branch information
tridge committed Dec 9, 2023
1 parent d1ad9cc commit e4a2794
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AP_RTC/AP_RTC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

Expand Down

0 comments on commit e4a2794

Please sign in to comment.