diff --git a/src/drivers/gnss/septentrio/septentrio.cpp b/src/drivers/gnss/septentrio/septentrio.cpp index a5ca8a95d1..ea77df3c8b 100644 --- a/src/drivers/gnss/septentrio/septentrio.cpp +++ b/src/drivers/gnss/septentrio/septentrio.cpp @@ -1677,7 +1677,7 @@ bool SeptentrioDriver::clock_needs_update(timespec real_time) timespec rtc_system_time; px4_clock_gettime(CLOCK_REALTIME, &rtc_system_time); - int drift_time = abs(rtc_system_time.tv_sec - real_time.tv_sec); + int drift_time = abs(static_cast(rtc_system_time.tv_sec - real_time.tv_sec)); return drift_time >= k_max_allowed_clock_drift; } diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index df2c26c905..fee9b8b0f7 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -447,7 +447,7 @@ int GPS::callback(GPSCallbackType type, void *data1, int data2, void *user) px4_clock_gettime(CLOCK_REALTIME, &rtc_system_time); timespec rtc_gps_time = *(timespec *)data1; - int drift_time = abs(rtc_system_time.tv_sec - rtc_gps_time.tv_sec); + int drift_time = abs(static_cast(rtc_system_time.tv_sec - rtc_gps_time.tv_sec)); if (drift_time >= SET_CLOCK_DRIFT_TIME_S) { // as of 2021 setting the time on Nuttx temporarily pauses interrupts