SITL: use gmtime_r() instead of gmtime()

This commit is contained in:
Andrew Tridgell 2024-02-07 12:22:53 +11:00
parent b3240ac243
commit 3d4dbd0aed
2 changed files with 4 additions and 2 deletions

View File

@ -56,7 +56,8 @@ void GPS_MSP::publish(const GPS_Data *d)
auto t = gps_time(); auto t = gps_time();
struct timeval tv; struct timeval tv;
simulation_timeval(&tv); simulation_timeval(&tv);
auto *tm = gmtime(&tv.tv_sec); struct tm tvd {};
auto *tm = gmtime_r(&tv.tv_sec, &tvd);
msp_gps.gps_week = t.week; msp_gps.gps_week = t.week;
msp_gps.ms_tow = t.ms; msp_gps.ms_tow = t.ms;

View File

@ -45,7 +45,8 @@ void GPS_NMEA::publish(const GPS_Data *d)
simulation_timeval(&tv); simulation_timeval(&tv);
tm = gmtime(&tv.tv_sec); struct tm tvd {};
tm = gmtime_r(&tv.tv_sec, &tvd);
// format time string // format time string
hal.util->snprintf(tstring, sizeof(tstring), "%02u%02u%06.3f", tm->tm_hour, tm->tm_min, tm->tm_sec + tv.tv_usec*1.0e-6); hal.util->snprintf(tstring, sizeof(tstring), "%02u%02u%06.3f", tm->tm_hour, tm->tm_min, tm->tm_sec + tv.tv_usec*1.0e-6);