2012-08-23 15:36:13 -03:00
|
|
|
|
|
|
|
#ifndef __AP_HAL_SCHEDULER_H__
|
|
|
|
#define __AP_HAL_SCHEDULER_H__
|
|
|
|
|
2012-09-05 20:54:21 -03:00
|
|
|
#include <stdint.h>
|
2015-10-22 12:03:11 -03:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_Progmem/AP_Progmem.h>
|
2012-09-05 20:54:21 -03:00
|
|
|
|
2015-10-22 12:03:11 -03:00
|
|
|
#include "AP_HAL_Boards.h"
|
|
|
|
#include "AP_HAL_Namespace.h"
|
|
|
|
|
|
|
|
|
2012-08-23 15:36:13 -03:00
|
|
|
class AP_HAL::Scheduler {
|
|
|
|
public:
|
2012-09-06 15:20:12 -03:00
|
|
|
Scheduler() {}
|
2012-09-07 20:07:16 -03:00
|
|
|
virtual void init(void* implspecific) = 0;
|
2012-12-19 22:16:10 -04:00
|
|
|
virtual void delay(uint16_t ms) = 0;
|
2012-09-05 20:54:21 -03:00
|
|
|
virtual uint32_t millis() = 0;
|
|
|
|
virtual uint32_t micros() = 0;
|
2014-08-19 18:55:19 -03:00
|
|
|
virtual uint64_t millis64() = 0;
|
|
|
|
virtual uint64_t micros64() = 0;
|
2015-02-15 20:52:37 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
delay for the given number of microseconds. This needs to be as
|
|
|
|
accurate as possible - preferably within 100 microseconds.
|
|
|
|
*/
|
2012-09-05 20:54:21 -03:00
|
|
|
virtual void delay_microseconds(uint16_t us) = 0;
|
2015-02-15 20:52:37 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
delay for the given number of microseconds. On supported
|
|
|
|
platforms this boosts the priority of the main thread for a
|
|
|
|
short time when the time completes. The aim is to ensure the
|
|
|
|
main thread runs at a higher priority than drivers for the start
|
|
|
|
of each loop
|
|
|
|
*/
|
|
|
|
virtual void delay_microseconds_boost(uint16_t us) { delay_microseconds(us); }
|
|
|
|
|
2012-10-26 22:02:52 -03:00
|
|
|
virtual void register_delay_callback(AP_HAL::Proc,
|
2013-09-28 03:23:34 -03:00
|
|
|
uint16_t min_time_ms) = 0;
|
2013-01-03 21:31:43 -04:00
|
|
|
|
2013-04-17 08:33:50 -03:00
|
|
|
// register a high priority timer task
|
2013-09-30 04:00:26 -03:00
|
|
|
virtual void register_timer_process(AP_HAL::MemberProc) = 0;
|
2013-04-17 08:33:50 -03:00
|
|
|
|
|
|
|
// register a low priority IO task
|
2013-09-30 04:00:26 -03:00
|
|
|
virtual void register_io_process(AP_HAL::MemberProc) = 0;
|
2013-04-17 08:33:50 -03:00
|
|
|
|
|
|
|
// suspend and resume both timer and IO processes
|
2012-09-07 20:07:16 -03:00
|
|
|
virtual void suspend_timer_procs() = 0;
|
|
|
|
virtual void resume_timer_procs() = 0;
|
2013-01-10 17:50:11 -04:00
|
|
|
|
|
|
|
virtual bool in_timerprocess() = 0;
|
2013-01-03 21:31:43 -04:00
|
|
|
|
2013-09-30 04:00:26 -03:00
|
|
|
virtual void register_timer_failsafe(AP_HAL::Proc,
|
2013-09-28 03:23:34 -03:00
|
|
|
uint32_t period_us) = 0;
|
2012-12-04 19:52:27 -04:00
|
|
|
|
2013-01-10 17:50:11 -04:00
|
|
|
virtual bool system_initializing() = 0;
|
|
|
|
virtual void system_initialized() = 0;
|
|
|
|
|
2015-10-22 12:48:16 -03:00
|
|
|
virtual void panic(const prog_char_t *errormsg, ...) NORETURN = 0;
|
2013-09-03 22:58:13 -03:00
|
|
|
virtual void reboot(bool hold_in_bootloader) = 0;
|
2013-10-12 04:22:57 -03:00
|
|
|
|
|
|
|
/**
|
|
|
|
optional function to set timer speed in Hz
|
|
|
|
*/
|
|
|
|
virtual void set_timer_speed(uint16_t speed_hz) {}
|
2013-12-29 18:31:18 -04:00
|
|
|
|
|
|
|
/**
|
2014-02-26 04:33:39 -04:00
|
|
|
optional function to stop clock at a given time, used by log replay
|
2013-12-29 18:31:18 -04:00
|
|
|
*/
|
2014-02-26 04:33:39 -04:00
|
|
|
virtual void stop_clock(uint64_t time_usec) {}
|
2012-08-23 15:36:13 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
#endif // __AP_HAL_SCHEDULER_H__
|
|
|
|
|