mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
gps: explicit type cast (#25293)
This commit is contained in:
parent
a5dbcada9f
commit
4117aa5bd3
@ -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<long>(rtc_system_time.tv_sec - real_time.tv_sec));
|
||||
|
||||
return drift_time >= k_max_allowed_clock_drift;
|
||||
}
|
||||
|
||||
@ -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<long>(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
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user