mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
HAL_VRBRAIN: use correct datatype for time conversion
This commit is contained in:
parent
d1e0f9733e
commit
caf8dce75c
@ -95,8 +95,8 @@ enum VRBRAINUtil::safety_state VRBRAINUtil::safety_switch_state(void)
|
|||||||
void VRBRAINUtil::set_system_clock(uint64_t time_utc_usec)
|
void VRBRAINUtil::set_system_clock(uint64_t time_utc_usec)
|
||||||
{
|
{
|
||||||
timespec ts;
|
timespec ts;
|
||||||
ts.tv_sec = time_utc_usec/1.0e6f;
|
ts.tv_sec = time_utc_usec/1000000ULL;
|
||||||
ts.tv_nsec = (time_utc_usec % 1000000) * 1000;
|
ts.tv_nsec = (time_utc_usec % 1000000ULL) * 1000UL;
|
||||||
clock_settime(CLOCK_REALTIME, &ts);
|
clock_settime(CLOCK_REALTIME, &ts);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user