mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_HAL_PX4: use common methods for setting time
This commit is contained in:
parent
c9dbdd7a5c
commit
3bdbe3b63c
@ -96,14 +96,6 @@ enum PX4Util::safety_state PX4Util::safety_switch_state(void)
|
|||||||
return AP_HAL::Util::SAFETY_DISARMED;
|
return AP_HAL::Util::SAFETY_DISARMED;
|
||||||
}
|
}
|
||||||
|
|
||||||
void PX4Util::set_system_clock(uint64_t time_utc_usec)
|
|
||||||
{
|
|
||||||
timespec ts;
|
|
||||||
ts.tv_sec = time_utc_usec/1000000ULL;
|
|
||||||
ts.tv_nsec = (time_utc_usec % 1000000ULL) * 1000ULL;
|
|
||||||
clock_settime(CLOCK_REALTIME, &ts);
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
display PX4 system identifer - board type and serial number
|
display PX4 system identifer - board type and serial number
|
||||||
*/
|
*/
|
||||||
|
@ -34,11 +34,6 @@ public:
|
|||||||
|
|
||||||
enum safety_state safety_switch_state(void);
|
enum safety_state safety_switch_state(void);
|
||||||
|
|
||||||
/*
|
|
||||||
set system clock in UTC microseconds
|
|
||||||
*/
|
|
||||||
void set_system_clock(uint64_t time_utc_usec);
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
get system identifier (STM32 serial number)
|
get system identifier (STM32 serial number)
|
||||||
*/
|
*/
|
||||||
|
Loading…
Reference in New Issue
Block a user