mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
HAL_PX4: implement set_system_clock()
This commit is contained in:
parent
0ca82d5e3c
commit
34cde1a640
@ -89,4 +89,12 @@ enum PX4Util::safety_state PX4Util::safety_switch_state(void)
|
||||
return AP_HAL::Util::SAFETY_DISARMED;
|
||||
}
|
||||
|
||||
void PX4Util::set_system_clock(uint64_t time_utc_usec)
|
||||
{
|
||||
timespec ts;
|
||||
ts.tv_sec = time_utc_usec/1.0e6;
|
||||
ts.tv_nsec = (time_utc_usec % 1000000) * 1000;
|
||||
clock_settime(CLOCK_REALTIME, &ts);
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
|
@ -12,6 +12,11 @@ public:
|
||||
|
||||
enum safety_state safety_switch_state(void);
|
||||
|
||||
/*
|
||||
set system clock in UTC microseconds
|
||||
*/
|
||||
void set_system_clock(uint64_t time_utc_usec);
|
||||
|
||||
private:
|
||||
int _safety_handle;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user