mirror of https://github.com/ArduPilot/ardupilot
AP_MSP: use gmtime_r() instead of gmtime()
using gmtime_r makes gmtime thread safe
This commit is contained in:
parent
3cb3e6feda
commit
fca0aa3d02
|
@ -1023,7 +1023,8 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_rtc(sbuf_t *dst)
|
|||
#if AP_RTC_ENABLED
|
||||
if (AP::rtc().get_utc_usec(time_usec)) { // may fail, leaving time_unix at 0
|
||||
const time_t time_sec = time_usec / 1000000;
|
||||
localtime_tm = *gmtime(&time_sec);
|
||||
struct tm tmd {};
|
||||
localtime_tm = *gmtime_r(&time_sec, &tmd);
|
||||
}
|
||||
#endif
|
||||
const struct PACKED {
|
||||
|
|
Loading…
Reference in New Issue