mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
HAL_Linux: use correct datatype for time conversion
This commit is contained in:
parent
66a94f7a10
commit
d1e0f9733e
@ -98,8 +98,8 @@ void Util::set_system_clock(uint64_t time_utc_usec)
|
||||
{
|
||||
#if CONFIG_HAL_BOARD_SUBTYPE != HAL_BOARD_SUBTYPE_LINUX_NONE
|
||||
timespec ts;
|
||||
ts.tv_sec = time_utc_usec/1.0e6;
|
||||
ts.tv_nsec = (time_utc_usec % 1000000) * 1000;
|
||||
ts.tv_sec = time_utc_usec/1000000ULL;
|
||||
ts.tv_nsec = (time_utc_usec % 1000000ULL) * 1000ULL;
|
||||
clock_settime(CLOCK_REALTIME, &ts);
|
||||
#endif
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user