21 #define F4Light_SCHEDULER_MAX_IO_PROCS 10 24 #define MAIN_PRIORITY 100 // priority for main task 25 #define DRIVER_PRIORITY 98 // priority for drivers, speed of main will be 1/4 of this 26 #define IO_PRIORITY 115 // main task has 100 so IO tasks will use 1/16 of CPU 28 #define SHED_FREQ 10000 // timer's freq in Hz 29 #define TIMER_PERIOD 100 // task timeslice period in uS 32 #define MAIN_STACK_SIZE 4096U+1024U // measured use of stack is only 1.5K - but it grows up to 3K when using FatFs, also this includes 1K stack for ISR 33 #define IO_STACK_SIZE 4096U // IO_tasks stack size - io_thread can do work with filesystem, stack overflows if 2K 34 #define DEFAULT_STACK_SIZE 1024U // Default tasks stack size 35 #define SMALL_TASK_STACK 1024U // small stack for sensors 36 #define STACK_MAX 65536U 39 #define EnterCriticalSection __set_BASEPRI(SVC_INT_PRIORITY << (8 - __NVIC_PRIO_BITS)) 40 #define LeaveCriticalSection __set_BASEPRI(0) 42 #define EnterCriticalSection noInterrupts() 43 #define LeaveCriticalSection interrupts() 69 #if defined(MTASK_PROF) 135 #define RAMEND ((size_t)&_estack) 140 typedef struct RevoSchedLog {
154 #define SHED_DEBUG_SIZE 512 184 inline void delay(uint16_t ms) { _delay(ms); }
189 inline uint32_t
micros() {
return _micros(); }
195 void register_delay_callback(
AP_HAL::Proc, uint16_t min_time_ms)
override;
203 _register_timer_task(period, r.
h,
NULL);
210 void system_initialized();
212 static void _reboot(
bool hold_in_bootloader);
213 void reboot(
bool hold_in_bootloader);
220 return _register_timer_task(period_us, r.
h, sem);
223 static void _delay(uint16_t ms);
224 static void _delay_microseconds(uint16_t us);
225 static void _delay_microseconds_boost(uint16_t us);
227 static void _delay_us_ny(uint16_t us);
233 static uint64_t _micros64();
240 static inline bool in_interrupt(){
return (SCB->ICSR & SCB_ICSR_VECTACTIVE_Msk) ; }
253 static inline bool adjust_stack(
size_t stackSize) { s_top = stackSize;
return true; }
264 static void * _start_task(
Handler h,
size_t stackSize);
268 return _start_task(r.
h, stackSize);
272 return _start_task(r.
h, stackSize);
275 static void stop_task(
void * h);
280 static void set_task_period(
void *h, uint32_t
period);
300 if(in_interrupt())
return NULL;
315 #if defined(MTASK_PROF) 329 context_switch_isr();
334 static void inline task_pause(uint16_t t) {
s_running->
ttw=t; }
335 static void inline task_resume(
void *h) {
343 context_switch_isr();
351 static task_t *get_next_task();
362 static size_t task_stack();
378 uint32_t now = _micros();
379 uint32_t timeFromLast = now - task->
t_yield;
380 if(task->
ttw<=100 || timeFromLast > task->
ttw*3/2){
392 need_switch_task =
true;
393 SCB->ICSR = SCB_ICSR_PENDSVSET_Msk;
398 static void _try_kill_task_or_reboot(uint8_t n);
399 static void _go_next_task();
400 static void _stop_multitask();
407 #define MAX_IO_COMPLETION 8 415 return register_io_completion(r.
h);
419 return register_io_completion(r.
h);
424 io_completion[
id-1].request =
true;
429 static void exec_io_completion();
449 static inline void MPU_buffer_overflow(){ MPU_overflow_cnt++; }
450 static inline void MPU_restarted() { MPU_restart_cnt++; }
451 static inline void MPU_stats(uint16_t
count, uint32_t
time) {
452 if(count>MPU_count) {
462 static void start_stats_task();
468 static void do_task(
task_t * task);
471 static task_t* get_empty_task();
478 static void *init_task(uint64_t h,
const uint8_t*
stack);
480 static uint32_t fill_task(
task_t &tp);
481 static void enqueue_task(
task_t &tp);
482 static void dequeue_task(
task_t &tp);
485 static void switch_task();
486 static void _switch_task();
496 static void check_stack(uint32_t
sp);
498 #define await(cond) while(!(cond)) yield() 509 static void _timer_isr_event(uint32_t
v );
510 static void _timer5_ovf(uint32_t
v );
511 static void _tail_timer_event(uint32_t
v );
512 static void _ioc_timer_event(uint32_t
v );
513 static void _delay_timer_event(uint32_t
v );
515 static void _run_timer_procs(
bool called_from_isr);
522 static void _run_io(
void);
528 static void _print_stats();
545 static void _set_10s_flag();
568 static revo_sched_log logbuf[SHED_DEBUG_SIZE];
569 static uint16_t sched_log_ptr;
577 static uint32_t MPU_overflow_cnt;
578 static uint32_t MPU_restart_cnt;
579 static uint32_t MPU_count;
580 static uint32_t MPU_Time;
void(* voidFuncPtr)(void)
static Handler get_handler(AP_HAL::MemberProc proc)
void hal_delay(uint16_t t)
static void context_switch_isr()
static void mpu_disable()
static uint32_t tsched_count_y
static bool adjust_stack(size_t stackSize)
static uint32_t tsched_sw_count_t
static Handler get_handler(AP_HAL::Proc proc)
void delay_microseconds_boost(uint16_t us) override
static uint32_t tsched_sw_count
static AP_HAL::Proc _failsafe
static void set_task_semaphore(void *h, F4Light::Semaphore *sem)
void suspend_timer_procs()
static uint64_t systick_uptime(void)
Returns the system uptime, in milliseconds.
void hal_set_task_priority(void *handle, uint8_t prio)
static void set_task_priority(void *h, uint8_t prio)
static uint32_t tick_micros
void * hal_register_task(voidFuncPtr task, uint32_t stack)
static uint64_t delay_time
static uint8_t num_io_completion
static void * get_current_task()
static void task_resume(void *h)
void hal_delay_microseconds(uint16_t t)
static uint8_t register_io_completion(AP_HAL::MemberProc proc)
static bool in_interrupt()
static void arming_state_changed(bool v)
static uint32_t tsched_count
static uint64_t delay_int_time
#define DEFAULT_STACK_SIZE
static void register_on_disarm(Handler h)
void revo_call_handler(Handler hh, uint32_t arg)
static void * start_task(AP_HAL::MemberProc proc, size_t stackSize=DEFAULT_STACK_SIZE)
static void set_task_active(void *h)
static uint32_t max_wfe_time
static uint32_t timer5_ovf_cnt
static void plan_context_switch()
static void _register_timer_process(AP_HAL::MemberProc proc, uint32_t period)
static uint32_t max_delay_err
static Handler on_disarm_handler
static uint8_t _num_io_proc
static uint32_t _millis()
void delay_microseconds(uint16_t us)
static uint64_t _millis64()
static AP_HAL::Device::PeriodicHandle register_timer_task(uint32_t period_us, AP_HAL::Device::PeriodicCb proc, F4Light::Semaphore *sem)
bool in_main_thread() const override
void hal_set_task_active(void *handle)
static uint32_t lowest_stack
void hal_yield(uint16_t ttw)
F4Light::Semaphore * sem_wait
static uint8_t register_io_completion(ioc_proc cb)
static void do_io_completion(uint8_t id)
static uint32_t tsched_count_t
static bool _in_main_thread()
void hal_context_switch_isr()
void register_timer_process(AP_HAL::MemberProc proc)
voidFuncPtr boardEmergencyHandler
static uint64_t shed_time
void hal_isr_time(uint32_t t)
Board-specific pin information.
static uint32_t _micros()
static uint64_t task_time
static void * get_current_task_isr()
static void setEmergencyHandler(voidFuncPtr handler)
static uint32_t tsched_sw_count_y
static uint64_t sleep_time
static uint64_t tick_fulltime
static uint32_t tick_count
void init()
Generic board initialization function.
static task_t * _forced_task
AP_HAL::Device::PeriodicCb pcb
static uint32_t max_loop_time
void resume_timer_procs()
void register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
void enqueue_flash_erase(uint32_t from, uint32_t to)
static void task_pause(uint32_t t)
void register_io_process(AP_HAL::MemberProc proc)
static void resume_boost()
static volatile bool need_io_completion
void hal_stop_multitask()
static void * _delay_cb_handle
void hal_try_kill_task_or_reboot(uint8_t n)
static INLINE uint32_t timer_get_count32(const timer_dev *dev)
static task_t * _idle_task
#define MAX_IO_COMPLETION
void __do_context_switch()
static void * start_task(voidFuncPtr taskLoop, size_t stackSize=DEFAULT_STACK_SIZE)
#define F4Light_SCHEDULER_MAX_IO_PROCS
static volatile bool need_switch_task
static void timer_generate_update(const timer_dev *dev)
Generate an update event for the given timer.