mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
HAL_PX4: use correct datatype for time conversion
This commit is contained in:
parent
aa6b339252
commit
66a94f7a10
@ -99,8 +99,8 @@ enum PX4Util::safety_state PX4Util::safety_switch_state(void)
|
||||
void PX4Util::set_system_clock(uint64_t time_utc_usec)
|
||||
{
|
||||
timespec ts;
|
||||
ts.tv_sec = time_utc_usec/1.0e6f;
|
||||
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);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user