mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_VRBRAIN: use common methods for setting time
This commit is contained in:
parent
3bdbe3b63c
commit
89d532b557
|
@ -96,14 +96,6 @@ enum VRBRAINUtil::safety_state VRBRAINUtil::safety_switch_state(void)
|
|||
return AP_HAL::Util::SAFETY_DISARMED;
|
||||
}
|
||||
|
||||
void VRBRAINUtil::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 VRBRAIN system identifer - board type and serial number
|
||||
*/
|
||||
|
|
|
@ -34,11 +34,6 @@ public:
|
|||
|
||||
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)
|
||||
*/
|
||||
|
|
Loading…
Reference in New Issue