mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Mount: Xacti integrates get-date-and-time return of ms
This commit is contained in:
parent
b5cbefc43a
commit
471f528233
@ -389,9 +389,9 @@ void AP_Mount_Xacti::handle_gnss_status_req(AP_DroneCAN* ap_dronecan, const Cana
|
|||||||
}
|
}
|
||||||
|
|
||||||
// get date and time
|
// get date and time
|
||||||
uint16_t year;
|
uint16_t year, ms;
|
||||||
uint8_t month, day, hour, min, sec;
|
uint8_t month, day, hour, min, sec;
|
||||||
if (!AP::rtc().get_date_and_time_utc(year, month, day, hour, min, sec)) {
|
if (!AP::rtc().get_date_and_time_utc(year, month, day, hour, min, sec, ms)) {
|
||||||
year = month = day = hour = min = sec = 0;
|
year = month = day = hour = min = sec = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user