APM:Libraries
Scheduler.h
Go to the documentation of this file.
1 #pragma once
2 
3 //#pragma GCC optimize ("O2")
4 
5 #include <AP_HAL/AP_HAL.h>
6 
7 
9 #include "handler.h"
10 #include "Config.h"
11 
12 #include "Semaphores.h"
13 #include "GPIO.h"
14 
15 #include <delay.h>
16 #include <systick.h>
17 #include <boards.h>
18 #include <timer.h>
19 //#include <setjmp.h>
20 
21 #define F4Light_SCHEDULER_MAX_IO_PROCS 10
22 
23 
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
27 
28 #define SHED_FREQ 10000 // timer's freq in Hz
29 #define TIMER_PERIOD 100 // task timeslice period in uS
30 
31 
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
37 
38 #if 1
39  #define EnterCriticalSection __set_BASEPRI(SVC_INT_PRIORITY << (8 - __NVIC_PRIO_BITS))
40  #define LeaveCriticalSection __set_BASEPRI(0)
41 #else
42  #define EnterCriticalSection noInterrupts()
43  #define LeaveCriticalSection interrupts()
44 #endif
45 
46 
47 /*
48  * Task run-time structure (Task control block AKA TCB)
49  */
50 struct task_t {
51  const uint8_t* sp; // Task stack pointer, should be first to access from context switcher
52  task_t* next; // Next task (double linked list)
53  task_t* prev; // Previous task
54  Handler handle; // loop() in Revo_handler - to allow to change task, called via revo_call_handler
55  const uint8_t* stack; // Task stack bottom
56  uint8_t id; // id of task
57  uint8_t priority; // base priority of task
58  uint8_t curr_prio; // current priority of task, usually higher than priority
59  bool active; // task still not ended
60  bool f_yield; // task gives its quant voluntary (to not call it again)
61  uint32_t ttw; // time to wait - for delays and IO
62  uint32_t t_yield; // time when task loose control
63  uint32_t period; // if set then task will start on time basis
64  uint32_t time_start; // start time of task (for periodic tasks)
65  F4Light::Semaphore *sem; // task should start after owning this semaphore
66  F4Light::Semaphore *sem_wait; // task is waiting this semaphore
67  uint32_t sem_time; // max time to wait semaphore
68  uint32_t sem_start_wait; // time when waiting starts (can use t_yield but stays for clarity)
69 #if defined(MTASK_PROF)
70  uint32_t start; // microseconds of timeslice start
71  uint32_t in_isr; // time in ISR when task runs
72  uint32_t def_ttw; // default TTW - not as hard as period
73  uint8_t sw_type; // type of task switch
74  uint64_t time; // full time
75  uint32_t max_time; // maximal execution time of task - to show
76  uint32_t count; // call count to calc mean
77  uint32_t work_time; // max time of full task
78  uint32_t sem_max_wait; // max time of semaphore waiting
79  uint32_t quants; // count of ticks
80  uint32_t quants_time; // sum of quatn's times
81  uint32_t t_paused; // time task was paused on IO
82  uint32_t count_paused; // count task was paused on IO
83  uint32_t max_paused; // max time task was paused on IO
84  uint32_t max_c_paused; // count task was paused on IO
85  uint32_t stack_free; // free stack
86 #endif
87  uint32_t guard; // stack guard to check TCB corruption
88 };
89 
90 extern "C" {
91  extern unsigned _estack; // defined by link script
92  extern uint32_t us_ticks;
93  extern void *_sdata;
94  extern void *_edata;
95  extern void *_sccm; // start of CCM
96  extern void *_eccm; // end of CCM vars
97 
98  void revo_call_handler(Handler hh, uint32_t arg); // universal caller for all type handlers - memberProc and Proc
99 
100  extern voidFuncPtr boardEmergencyHandler; // will be called on any fault or panic() before halt
101  void PendSV_Handler();
102  void SVC_Handler();
103  void getNextTask();
104 
105  void switchContext();
106  void __do_context_switch();
107  void hal_try_kill_task_or_reboot(uint8_t n);
108  void hal_go_next_task();
109  void hal_stop_multitask();
110 
111  extern task_t *s_running; // running task
112  extern task_t *next_task; // task to run next
113 
114  extern caddr_t stack_bottom; // for SBRK check
115 
116  bool hal_is_armed();
117 
118 // publish to low-level functions
119  void hal_yield(uint16_t ttw);
120  void hal_delay(uint16_t t);
121  void hal_delay_microseconds(uint16_t t);
122  uint32_t hal_micros();
123  void hal_isr_time(uint32_t t);
124 
125 // task management for USB MSC mode
126  void hal_set_task_active(void * handle);
127  void hal_context_switch_isr();
128  void * hal_register_task(voidFuncPtr task, uint32_t stack);
129  void hal_set_task_priority(void * handle, uint8_t prio);
130 
131  void enqueue_flash_erase(uint32_t from, uint32_t to);
132 }
133 
134 
135 #define RAMEND ((size_t)&_estack)
136 
137 
138 
139 #ifdef SHED_DEBUG
140 typedef struct RevoSchedLog {
141  uint32_t start;
142  uint32_t end;
143  uint32_t ttw;
144  uint32_t time_start;
145  uint32_t quant;
146  uint32_t in_isr;
147  task_t *want_tail;
148  uint8_t task_id;
149  uint8_t prio;
150  uint8_t active;
151  uint8_t sw_type;
152 } revo_sched_log;
153 
154 #define SHED_DEBUG_SIZE 512
155 #endif
156 
159  IO_ONCE = 1,
160 };
161 
162 typedef struct REVO_IO {
165 } Revo_IO;
166 
168 public:
169 
170  typedef struct IO_COMPLETION {
172  bool request;
173 #ifdef SHED_PROF
174  uint64_t time;
175  uint32_t count;
176  uint32_t max_time;
177 #endif
178  } IO_Completion;
179 
180 
181 
182  Scheduler();
183  void init();
184  inline void delay(uint16_t ms) { _delay(ms); } // uses internal static methods
185  inline void delay_microseconds(uint16_t us) { _delay_microseconds(us); }
186  inline void delay_microseconds_boost(uint16_t us) override { _delay_microseconds_boost(us); }
187 
188  inline uint32_t millis() { return AP_HAL::millis(); }
189  inline uint32_t micros() { return _micros(); }
190 
191  inline void register_timer_process(AP_HAL::MemberProc proc) { _register_timer_process(proc, 1000); }
192  inline void suspend_timer_procs(){} // nothing to do in multitask
193  inline void resume_timer_procs() {}
194 
195  void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms) override;
196  static void _register_io_process(Handler h, Revo_IO_Flags flags);
197  void register_io_process(AP_HAL::MemberProc proc) { Revo_handler h = { .mp=proc }; _register_io_process(h.h, IO_PERIODIC); }
198 
199 
200  static inline void _register_timer_process(AP_HAL::MemberProc proc, uint32_t period) {
201  Revo_handler r = { .mp=proc };
202 
203  _register_timer_task(period, r.h, NULL);
204  }
205 
206  inline bool in_timerprocess() { return false; } // we don't calls anything in ISR
207 
208  void inline register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us) { _failsafe = failsafe; }
209 
210  void system_initialized();
211 
212  static void _reboot(bool hold_in_bootloader);
213  void reboot(bool hold_in_bootloader);
214 
215  inline bool in_main_thread() const override { return _in_main_thread(); }
216 
217 // drivers are not the best place for its own sheduler so let do it here
218  static inline AP_HAL::Device::PeriodicHandle register_timer_task(uint32_t period_us, AP_HAL::Device::PeriodicCb proc, F4Light::Semaphore *sem) {
219  Revo_handler r = { .pcb=proc };
220  return _register_timer_task(period_us, r.h, sem);
221  }
222 
223  static void _delay(uint16_t ms);
224  static void _delay_microseconds(uint16_t us);
225  static void _delay_microseconds_boost(uint16_t us);
226 
227  static void _delay_us_ny(uint16_t us); // no yield delay
228 
229  static inline uint32_t _millis() { return systick_uptime(); } //systick_uptime returns 64-bit time
230  static inline uint64_t _millis64() { return systick_uptime(); }
231 
232  static inline uint32_t _micros() { return timer_get_count32(TIMER5); }
233  static uint64_t _micros64();
234 
235 
236  static bool adjust_timer_task(AP_HAL::Device::PeriodicHandle h, uint32_t period_us);
237  static bool unregister_timer_task(AP_HAL::Device::PeriodicHandle h);
238  void loop(); // to add ability to print out scheduler's stats in main thread
239 
240  static inline bool in_interrupt(){ return (SCB->ICSR & SCB_ICSR_VECTACTIVE_Msk) /* || (__get_BASEPRI()) */; }
241 
242 
243 //{ this functions do a preemptive multitask and inspired by Arduino-Scheduler (Mikael Patel), and scmrtos
244 
253  static inline bool adjust_stack(size_t stackSize) { s_top = stackSize; return true; }
254 
264  static void * _start_task(Handler h, size_t stackSize);
265 
266  static inline void * start_task(voidFuncPtr taskLoop, size_t stackSize = DEFAULT_STACK_SIZE){
267  Revo_handler r = { .vp=taskLoop };
268  return _start_task(r.h, stackSize);
269  }
270  static inline void * start_task(AP_HAL::MemberProc proc, size_t stackSize = DEFAULT_STACK_SIZE){
271  Revo_handler r = { .mp=proc };
272  return _start_task(r.h, stackSize);
273  }
274  // not used - tasks are never stopped
275  static void stop_task(void * h);
276 
277 
278 // functions to alter task's properties
279 //[ this functions called only at task start
280  static void set_task_period(void *h, uint32_t period); // task will be auto-activated by this period
281 
282  static inline void set_task_priority(void *h, uint8_t prio){ // priority is a relative speed of task
283  task_t *task = (task_t *)h;
284 
285  task->curr_prio= prio;
286  task->priority = prio;
287  }
288 
289  // task wants to run only with this semaphore owned
290  static inline void set_task_semaphore(void *h, F4Light::Semaphore *sem){ // taskLoop function will be called owning this semaphore
291  task_t *task = (task_t *)h;
292 
293  task->sem = sem;
294  }
295 //]
296 
297 
298 // this functions are atomic so don't need to disable interrupts
299  static inline void *get_current_task() { // get task handler or 0 if called from ISR
300  if(in_interrupt()) return NULL;
301  return s_running;
302  }
303  static inline void *get_current_task_isr() { // get current task handler even if called from ISR
304  return s_running;
305  }
306  static inline void set_task_active(void *h) { // tasks are created in stopped state
307  task_t * task = (task_t*)h;
308  task->active=true;
309 }
310 
311  // do context switch after return from interrupt
313 
314 
315 #if defined(MTASK_PROF)
316  static void inline task_pause(uint32_t t) { // called from task when it starts transfer
317  s_running->ttw=t;
318  s_running->sem_start_wait=_micros();
320  }
321  static void inline task_resume(void *h) { // called from IO_Complete ISR to resume task
322 #if defined(USE_MPU)
323  mpu_disable(); // we need access to write
324 #endif
325  task_t * task = (task_t*)h;
326  task->ttw=0;
327  task->active=true;
328  _forced_task = task; // force it. Thus we exclude loop to select task
329  context_switch_isr();
330  uint32_t dt= _micros() - task->sem_start_wait;
331  task->t_paused += dt;
332  }
333 #else
334  static void inline task_pause(uint16_t t) { s_running->ttw=t; } // called from task when it starts IO transfer
335  static void inline task_resume(void *h) { // called from IO_Complete ISR to resume task, and will get 1st quant 100%
336 #if defined(USE_MPU)
337  mpu_disable(); // we need access to write
338 #endif
339  task_t * task = (task_t*)h; // called from ISR so don't need disabling interrupts when writes to TCB
340  task->ttw=0;
341  task->active=true;
342  _forced_task = task; // force it, to not spent time for search by priority
343  context_switch_isr();
344  }
345 #endif
346 //]
347 
348 /*
349  task scheduler. Gives task ready to run with highest priority
350 */
351  static task_t *get_next_task();
352 
353 /*
354  * finish current tick and schedule new task excluding this
355  */
356  static void yield(uint16_t ttw=0); // optional time to wait
357 
362  static size_t task_stack();
363 
364  // check from what task it called
365  static inline bool _in_main_thread() { return s_running == &s_main; }
366 
367  // resume task that called delay_boost()
368  static void resume_boost(){
369  if(boost_task) {
370  task_t *task = (task_t *) boost_task;
371  boost_task=NULL;
372 
373 
374  if(task->ttw){ // task now in wait
375 #if defined(USE_MPU)
376  mpu_disable(); // we need access to write
377 #endif
378  uint32_t now = _micros();
379  uint32_t timeFromLast = now - task->t_yield; // time since that moment
380  if(task->ttw<=100 || timeFromLast > task->ttw*3/2){ // gone 2/3 of time?
381  task->ttw=0; // stop waiting
382  task->active=true;
383  _forced_task = task; // force it
384  }
385  } else {
386  _forced_task = task; // just force it
387  }
388  }
389  }
390 
391  static inline void plan_context_switch(){
392  need_switch_task = true; // require context switch
393  SCB->ICSR = SCB_ICSR_PENDSVSET_Msk; // PENDSVSET
394  }
395 
396  static void SVC_Handler(uint32_t * svc_args); // many functions called via SVC for hardware serialization
397 
398  static void _try_kill_task_or_reboot(uint8_t n); // exception occures in armed state - try to kill current task
399  static void _go_next_task();
400  static void _stop_multitask();
401 
402  static volatile bool need_switch_task; // should be public for access from C code
403 //}
404 
405 
406 //{ IO completion routines, allows to move out time consuming parts from ISR
407  #define MAX_IO_COMPLETION 8
408 
410 
411  static uint8_t register_io_completion(Handler handle);
412 
413  static inline uint8_t register_io_completion(ioc_proc cb) {
414  Revo_handler r = { .vp=cb };
415  return register_io_completion(r.h);
416  }
417  static inline uint8_t register_io_completion(AP_HAL::MemberProc proc) {
418  Revo_handler r = { .mp=proc };
419  return register_io_completion(r.h);
420  }
421 
422  static inline void do_io_completion(uint8_t id){ // schedule selected IO completion
423  if(id) {
424  io_completion[id-1].request = true;
426  }
427  }
428 
429  static void exec_io_completion();
430 
431  static volatile bool need_io_completion;
432 //}
433 
434 
435  // helpers
436  static inline Handler get_handler(AP_HAL::MemberProc proc){
437  Revo_handler h = { .mp = proc };
438  return h.h;
439  }
440  static inline Handler get_handler(AP_HAL::Proc proc){
441  Revo_handler h = { .hp = proc };
442  return h.h;
443  }
444 
445  static inline void setEmergencyHandler(voidFuncPtr handler) { boardEmergencyHandler = handler; }
446 
447 
448 #ifdef MPU_DEBUG
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) {
453  MPU_count=count;
454  MPU_Time=time;
455  }
456  }
457 #endif
458 
459  static inline void arming_state_changed(bool v){ if(!v && on_disarm_handler) revo_call_handler(on_disarm_handler, 0); }
460  static inline void register_on_disarm(Handler h){ on_disarm_handler=h; }
461 
462  static void start_stats_task(); // it interferes with CONNECT_COM and CONNECT_ESC so should be started last
463 
464 protected:
465 
466 //{ multitask
467  // executor for task's handler, never called but used when task context formed
468  static void do_task(task_t * task);
469 
470  // gves first deleted task or NULL - not used because tasks are never finished
471  static task_t* get_empty_task();
472 /*
473  * Initiate a task with the given functions and stack. When control
474  * is yield to the task then the loop function is repeatedly called.
475  * @param[in] h task handler (may be NULL)
476  * @param[in] stack top reference.
477 */
478  static void *init_task(uint64_t h, const uint8_t* stack);
479 
480  static uint32_t fill_task(task_t &tp); // prepares task's TCB
481  static void enqueue_task(task_t &tp); // add new task to run queue
482  static void dequeue_task(task_t &tp); // remove task from run queue
483 
484  // plan context switch
485  static void switch_task();
486  static void _switch_task();
487 
488  static task_t s_main; // main task TCB
489  static size_t s_top; // Task stack allocation top.
490  static uint16_t task_n; // counter of tasks
491 
492  static task_t *_idle_task; // remember TCB of idle task
493  static task_t *_forced_task; // task activated from ISR so should be called without prioritization
494  static void *boost_task; // task that called delay_boost()
495 
496  static void check_stack(uint32_t sp);
497 
498 #define await(cond) while(!(cond)) yield()
499 
500 //} end of multitask
501 
502 private:
503  static AP_HAL::Device::PeriodicHandle _register_timer_task(uint32_t period_us, Handler proc, F4Light::Semaphore *sem);
504 
505  static void * _delay_cb_handle;
506  static bool _initialized;
507 
508  // ISR functions
509  static void _timer_isr_event(uint32_t v /*TIM_TypeDef *tim */);
510  static void _timer5_ovf(uint32_t v /*TIM_TypeDef *tim */ );
511  static void _tail_timer_event(uint32_t v /*TIM_TypeDef *tim */);
512  static void _ioc_timer_event(uint32_t v /*TIM_TypeDef *tim */);
513  static void _delay_timer_event(uint32_t v /*TIM_TypeDef *tim */);
514 
515  static void _run_timer_procs(bool called_from_isr);
516 
517  static uint32_t timer5_ovf_cnt; // high part of 64-bit time
518 
519  static AP_HAL::Proc _failsafe; // periodically called from ISR
520 
521  static Revo_IO _io_proc[F4Light_SCHEDULER_MAX_IO_PROCS]; // low priority tasks for IO thread
522  static void _run_io(void);
523  static uint8_t _num_io_proc;
524  static bool _in_io_proc;
525 
527 
528  static void _print_stats();
529 
530  static uint32_t lowest_stack;
531 
532  static struct IO_COMPLETION io_completion[MAX_IO_COMPLETION];
533  static uint8_t num_io_completion;
534 
535 
536 #ifdef SHED_PROF
537  static uint64_t shed_time;
538  static uint64_t task_time;
539  static bool flag_10s;
540 
541  static uint64_t delay_time;
542  static uint64_t delay_int_time;
543  static uint32_t max_loop_time;
544 
545  static void _set_10s_flag();
546  static uint64_t ioc_time;
547  static uint64_t sleep_time;
548  static uint32_t max_delay_err;
549 
550 
551  static uint32_t tick_micros; // max exec time
552  static uint32_t tick_count; // number of calls
553  static uint64_t tick_fulltime; // full consumed time to calc mean
554 
555 #endif
556 
557 #ifdef MTASK_PROF
558  static uint32_t max_wfe_time;
559  static uint32_t tsched_count;
560  static uint32_t tsched_sw_count;
561  static uint32_t tsched_count_y;
562  static uint32_t tsched_sw_count_y;
563  static uint32_t tsched_count_t;
564  static uint32_t tsched_sw_count_t;
565 
566 
567  #ifdef SHED_DEBUG
568  static revo_sched_log logbuf[SHED_DEBUG_SIZE];
569  static uint16_t sched_log_ptr;
570  #endif
571 #endif
572 
573 
574 
575 
576 #ifdef MPU_DEBUG
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;
581 #endif
582 
583 };
584 
585 void revo_call_handler(Handler h, uint32_t arg);
586 
587 
void(* voidFuncPtr)(void)
Definition: hal_types.h:16
#define TIMER5
Definition: timer.h:613
task_t * prev
Definition: Scheduler.h:53
static Handler get_handler(AP_HAL::MemberProc proc)
Definition: Scheduler.h:436
bool active
Definition: Scheduler.h:59
uint32_t max_time
Definition: Scheduler.h:75
uint32_t start
Definition: Scheduler.h:70
AP_HAL::MemberProc mp
Definition: handler.h:18
void PendSV_Handler()
Definition: Scheduler.cpp:1280
void hal_delay(uint16_t t)
Definition: Scheduler.cpp:1431
static void context_switch_isr()
Definition: Scheduler.h:312
bool in_timerprocess()
Definition: Scheduler.h:206
Handler h
Definition: handler.h:20
static void mpu_disable()
Definition: mpu.h:116
static uint32_t tsched_count_y
Definition: Scheduler.h:561
void hal_go_next_task()
Definition: Scheduler.cpp:1448
static bool adjust_stack(size_t stackSize)
Definition: Scheduler.h:253
uint64_t time
Definition: Scheduler.h:74
bool f_yield
Definition: Scheduler.h:60
static uint32_t tsched_sw_count_t
Definition: Scheduler.h:564
static Handler get_handler(AP_HAL::Proc proc)
Definition: Scheduler.h:440
void delay_microseconds_boost(uint16_t us) override
Definition: Scheduler.h:186
static task_t s_main
Definition: Scheduler.h:488
uint32_t stack_free
Definition: Scheduler.h:85
static uint32_t tsched_sw_count
Definition: Scheduler.h:560
static bool _initialized
Definition: Scheduler.h:506
static AP_HAL::Proc _failsafe
Definition: Scheduler.h:519
static void set_task_semaphore(void *h, F4Light::Semaphore *sem)
Definition: Scheduler.h:290
void suspend_timer_procs()
Definition: Scheduler.h:192
static uint64_t systick_uptime(void)
Returns the system uptime, in milliseconds.
Definition: systick.h:44
void hal_set_task_priority(void *handle, uint8_t prio)
Definition: Scheduler.cpp:1440
static void set_task_priority(void *h, uint8_t prio)
Definition: Scheduler.h:282
uint32_t quants_time
Definition: Scheduler.h:80
uint32_t hal_micros()
Definition: Scheduler.cpp:1434
static uint32_t tick_micros
Definition: Scheduler.h:551
void * hal_register_task(voidFuncPtr task, uint32_t stack)
Definition: Scheduler.cpp:1441
static uint64_t delay_time
Definition: Scheduler.h:541
static uint8_t num_io_completion
Definition: Scheduler.h:533
void switchContext()
uint32_t max_paused
Definition: Scheduler.h:83
uint32_t ttw
Definition: Scheduler.h:61
static void * get_current_task()
Definition: Scheduler.h:299
static void task_resume(void *h)
Definition: Scheduler.h:321
void hal_delay_microseconds(uint16_t t)
Definition: Scheduler.cpp:1432
static uint8_t register_io_completion(AP_HAL::MemberProc proc)
Definition: Scheduler.h:417
uint32_t def_ttw
Definition: Scheduler.h:72
Handler h
Definition: Scheduler.h:163
uint32_t t_yield
Definition: Scheduler.h:62
void(* Proc)(void)
void * _sccm
static bool in_interrupt()
Definition: Scheduler.h:240
static void arming_state_changed(bool v)
Definition: Scheduler.h:459
static void * boost_task
Definition: Scheduler.h:494
uint32_t sem_start_wait
Definition: Scheduler.h:68
uint32_t micros()
Definition: Scheduler.h:189
void * _edata
static uint32_t tsched_count
Definition: Scheduler.h:559
static uint64_t delay_int_time
Definition: Scheduler.h:542
#define DEFAULT_STACK_SIZE
Definition: Scheduler.h:34
uint8_t id
Definition: Scheduler.h:56
static void register_on_disarm(Handler h)
Definition: Scheduler.h:460
void revo_call_handler(Handler hh, uint32_t arg)
Definition: Scheduler.cpp:1420
timer interface.
uint32_t work_time
Definition: Scheduler.h:77
static void * start_task(AP_HAL::MemberProc proc, size_t stackSize=DEFAULT_STACK_SIZE)
Definition: Scheduler.h:270
static void set_task_active(void *h)
Definition: Scheduler.h:306
uint32_t in_isr
Definition: Scheduler.h:71
struct REVO_IO Revo_IO
static uint32_t max_wfe_time
Definition: Scheduler.h:558
static uint32_t timer5_ovf_cnt
Definition: Scheduler.h:517
static void plan_context_switch()
Definition: Scheduler.h:391
uint8_t curr_prio
Definition: Scheduler.h:58
uint32_t sem_time
Definition: Scheduler.h:67
static void _register_timer_process(AP_HAL::MemberProc proc, uint32_t period)
Definition: Scheduler.h:200
void * _eccm
uint32_t guard
Definition: Scheduler.h:87
uint32_t time_start
Definition: Scheduler.h:64
static size_t s_top
Definition: Scheduler.h:489
task_t * s_running
static uint32_t max_delay_err
Definition: Scheduler.h:548
void yield(uint32_t us)
Definition: system.cpp:99
uint32_t count
Definition: Scheduler.h:76
uint32_t max_c_paused
Definition: Scheduler.h:84
uint32_t t_paused
Definition: Scheduler.h:81
static Handler on_disarm_handler
Definition: Scheduler.h:526
static uint8_t _num_io_proc
Definition: Scheduler.h:523
voidFuncPtr ioc_proc
Definition: Scheduler.h:409
#define TIMER13
Definition: timer.h:621
static uint32_t _millis()
Definition: Scheduler.h:229
void delay_microseconds(uint16_t us)
Definition: Scheduler.h:185
static uint64_t _millis64()
Definition: Scheduler.h:230
static AP_HAL::Device::PeriodicHandle register_timer_task(uint32_t period_us, AP_HAL::Device::PeriodicCb proc, F4Light::Semaphore *sem)
Definition: Scheduler.h:218
bool in_main_thread() const override
Definition: Scheduler.h:215
void hal_set_task_active(void *handle)
Definition: Scheduler.cpp:1438
uint32_t quants
Definition: Scheduler.h:79
void * PeriodicHandle
Definition: Device.h:42
uint32_t count_paused
Definition: Scheduler.h:82
uint32_t millis()
Definition: system.cpp:157
void loop()
Definition: AC_PID_test.cpp:34
static uint32_t lowest_stack
Definition: Scheduler.h:530
void hal_yield(uint16_t ttw)
Definition: Scheduler.cpp:1430
F4Light::Semaphore * sem_wait
Definition: Scheduler.h:66
bool hal_is_armed()
Definition: Scheduler.cpp:1446
void * _sdata
uint32_t sem_max_wait
Definition: Scheduler.h:78
F4Light::Semaphore * sem
Definition: Scheduler.h:65
static uint8_t register_io_completion(ioc_proc cb)
Definition: Scheduler.h:413
static uint16_t task_n
Definition: Scheduler.h:490
static void do_io_completion(uint8_t id)
Definition: Scheduler.h:422
float v
Definition: Printf.cpp:15
static bool _in_io_proc
Definition: Scheduler.h:524
uint8_t priority
Definition: Scheduler.h:57
const uint8_t * stack
Definition: Scheduler.h:55
static uint32_t tsched_count_t
Definition: Scheduler.h:563
Delay implementation.
static bool _in_main_thread()
Definition: Scheduler.h:365
uint8_t sw_type
Definition: Scheduler.h:73
void hal_context_switch_isr()
Definition: Scheduler.cpp:1439
void register_timer_process(AP_HAL::MemberProc proc)
Definition: Scheduler.h:191
#define NULL
Definition: hal_types.h:59
voidFuncPtr boardEmergencyHandler
static uint64_t shed_time
Definition: Scheduler.h:537
void hal_isr_time(uint32_t t)
Definition: Scheduler.cpp:1435
caddr_t stack_bottom
Definition: syscalls.c:74
Board-specific pin information.
task_t * next_task
static uint32_t _micros()
Definition: Scheduler.h:232
Revo_IO_Flags
Definition: Scheduler.h:157
static uint64_t task_time
Definition: Scheduler.h:538
static void * get_current_task_isr()
Definition: Scheduler.h:303
static void setEmergencyHandler(voidFuncPtr handler)
Definition: Scheduler.h:445
void SVC_Handler()
Definition: Scheduler.cpp:1293
static uint32_t tsched_sw_count_y
Definition: Scheduler.h:562
static uint64_t sleep_time
Definition: Scheduler.h:547
static uint64_t tick_fulltime
Definition: Scheduler.h:553
static uint32_t tick_count
Definition: Scheduler.h:552
Handler handle
Definition: Scheduler.h:54
void init()
Generic board initialization function.
Definition: system.cpp:136
static task_t * _forced_task
Definition: Scheduler.h:493
void delay(uint16_t ms)
Definition: Scheduler.h:184
AP_HAL::Device::PeriodicCb pcb
Definition: handler.h:17
static uint32_t max_loop_time
Definition: Scheduler.h:543
void getNextTask()
void resume_timer_procs()
Definition: Scheduler.h:193
unsigned _estack
void register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us)
Definition: Scheduler.h:208
voidFuncPtr vp
Definition: handler.h:14
const uint8_t * sp
Definition: Scheduler.h:51
uint64_t Handler
Definition: hal_types.h:19
void enqueue_flash_erase(uint32_t from, uint32_t to)
static void task_pause(uint32_t t)
Definition: Scheduler.h:316
void register_io_process(AP_HAL::MemberProc proc)
Definition: Scheduler.h:197
static uint64_t ioc_time
Definition: Scheduler.h:546
uint32_t millis()
Definition: Scheduler.h:188
uint32_t us_ticks
Definition: stopwatch.c:10
static void resume_boost()
Definition: Scheduler.h:368
task_t * next
Definition: Scheduler.h:52
uint32_t period
Definition: Scheduler.h:63
static volatile bool need_io_completion
Definition: Scheduler.h:431
static bool flag_10s
Definition: Scheduler.h:539
void hal_stop_multitask()
Definition: Scheduler.cpp:1449
static void * _delay_cb_handle
Definition: Scheduler.h:505
#define TIMER14
Definition: timer.h:622
void hal_try_kill_task_or_reboot(uint8_t n)
Definition: Scheduler.cpp:1447
static INLINE uint32_t timer_get_count32(const timer_dev *dev)
Definition: timer.h:706
Revo_IO_Flags flags
Definition: Scheduler.h:164
AP_HAL::Proc hp
Definition: handler.h:16
static task_t * _idle_task
Definition: Scheduler.h:492
#define MAX_IO_COMPLETION
Definition: Scheduler.h:407
void __do_context_switch()
static void * start_task(voidFuncPtr taskLoop, size_t stackSize=DEFAULT_STACK_SIZE)
Definition: Scheduler.h:266
#define F4Light_SCHEDULER_MAX_IO_PROCS
Definition: Scheduler.h:21
static volatile bool need_switch_task
Definition: Scheduler.h:402
static void timer_generate_update(const timer_dev *dev)
Generate an update event for the given timer.
Definition: timer.h:807