14 virtual void init() = 0;
15 virtual void delay(uint16_t ms) = 0;
40 uint16_t min_time_ms);
57 uint32_t period_us) = 0;
61 virtual void reboot(
bool hold_in_bootloader) = 0;
virtual void stop_clock(uint64_t time_usec)
virtual void boost_end(void)
virtual bool in_main_thread() const =0
virtual void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms)
virtual void resume_timer_procs()=0
virtual void delay(uint16_t ms)=0
virtual void create_uavcan_thread()
virtual void call_delay_cb()
uint16_t _min_delay_cb_ms
virtual void suspend_timer_procs()=0
Common definitions and utility routines for the ArduPilot libraries.
virtual void register_timer_process(AP_HAL::MemberProc)=0
virtual void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us)=0
virtual void reboot(bool hold_in_bootloader)=0
virtual void delay_microseconds_boost(uint16_t us)
virtual void register_io_process(AP_HAL::MemberProc)=0
virtual void delay_microseconds(uint16_t us)=0
virtual void restore_interrupts(void *)
virtual void * disable_interrupts_save(void)
virtual bool in_delay_callback() const
virtual void system_initialized()=0