mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: added set_system_clock() API
This commit is contained in:
parent
744819cec8
commit
0ca82d5e3c
|
@ -33,6 +33,11 @@ public:
|
|||
return state of safety switch, if applicable
|
||||
*/
|
||||
virtual enum safety_state safety_switch_state(void) { return SAFETY_NONE; }
|
||||
|
||||
/*
|
||||
set system clock in UTC microseconds
|
||||
*/
|
||||
virtual void set_system_clock(uint64_t time_utc_usec) {}
|
||||
};
|
||||
|
||||
#endif // __AP_HAL_UTIL_H__
|
||||
|
|
Loading…
Reference in New Issue