AP_NMEA_Output: use gmtime_r() instead of gmtime()

using gmtime_r makes gmtime thread safe
This commit is contained in:
Andrew Tridgell 2024-02-07 09:32:49 +11:00
parent fca0aa3d02
commit 476587adf1
1 changed files with 2 additions and 1 deletions

View File

@ -108,7 +108,8 @@ void AP_NMEA_Output::update()
// not completely accurate, our time includes leap seconds and time_t should be without
const time_t time_sec = time_usec / 1000000;
struct tm* tm = gmtime(&time_sec);
struct tm tmd {};
struct tm* tm = gmtime_r(&time_sec, &tmd);
// format time string
char tstring[10];