APM:Libraries
Scheduler.cpp
Go to the documentation of this file.
1 /*
2 (c) 2017 night_ghost@ykoctpa.ru
3 */
4 
5 #pragma GCC optimize ("O2")
6 
7 
8 #include "Scheduler.h"
9 
10 #include <stdio.h>
12 
13 
14 #include "Semaphores.h"
15 #include "I2CDevice.h"
16 
17 #include <timer.h>
18 
19 
20 #include <AP_Notify/AP_Notify.h>
21 #include <AP_Math/AP_Math.h>
23 
24 #include "RCInput.h"
25 #include <systick.h>
26 #include "GPIO.h"
27 #include <usb.h>
28 
29 
30 using namespace F4Light;
31 extern const AP_HAL::HAL& hal;
32 
33 
35 
38 
40 
42 
44 
47 
49 
50 static void loc_ret(){}
51 
52 #define STACK_GUARD 0x60a4d51aL
53 
54 // Reference running task
57 // Main task and run queue
58 task_t Scheduler::s_main = { 0 }; // NOT in CCM to can't be corrupted by stack
59 uint16_t Scheduler::task_n=0;
60 
61 
62 struct Scheduler::IO_COMPLETION Scheduler::io_completion[MAX_IO_COMPLETION] IN_CCM;
63 
65 
66 
67 // Initial top stack for task allocation
68 size_t Scheduler::s_top IN_CCM; // = MAIN_STACK_SIZE; - CCM not initialized!
69 
70 
71 #ifdef SHED_PROF
72 uint64_t Scheduler::shed_time = 0;
73 bool Scheduler::flag_10s = false;
74 uint64_t Scheduler::task_time IN_CCM = 0;
75 uint64_t Scheduler::delay_time IN_CCM = 0;
78 uint64_t Scheduler::ioc_time IN_CCM =0;
79 uint64_t Scheduler::sleep_time IN_CCM =0;
80 uint32_t Scheduler::max_delay_err=0;
81 
82 uint32_t Scheduler::tick_micros IN_CCM; // max exec time
83 uint32_t Scheduler::tick_count IN_CCM; // number of calls
84 uint64_t Scheduler::tick_fulltime IN_CCM; // full consumed time to calc mean
85 #endif
86 
87 
88 #ifdef MTASK_PROF
89  uint32_t Scheduler::max_wfe_time IN_CCM =0;
96  #ifdef SHED_DEBUG
97  revo_sched_log Scheduler::logbuf[SHED_DEBUG_SIZE] IN_CCM;
98  uint16_t Scheduler::sched_log_ptr;
99  #endif
100 
101 uint32_t Scheduler::lowest_stack = (uint32_t)-1;
102 #endif
103 
104 
106 #ifdef MPU_DEBUG
107 uint32_t Scheduler::MPU_overflow_cnt IN_CCM;
108 uint32_t Scheduler::MPU_restart_cnt IN_CCM;
109 uint32_t Scheduler::MPU_count IN_CCM;
110 uint32_t Scheduler::MPU_Time IN_CCM;
111 #endif
112 volatile bool Scheduler::need_switch_task IN_CCM;
114 
115 
117 {
118 
119  s_running = &s_main; // CCM don't initialized! - Reference running task
120  next_task = &s_main;
121  s_top = MAIN_STACK_SIZE; // Initial top stack for task allocation
122 
123 // init main task
124  memset(&s_main, 0, sizeof(s_main));
125 
126  Revo_handler h = { .vp=loc_ret }; // fake handler to not 0
127 
128  s_main.next = &s_main; // linked list
129  s_main.prev = &s_main;
130  s_main.priority = MAIN_PRIORITY; // base priority
131  s_main.active = true; // not paused
132  s_main.handle = h.h; // to not 0
133  s_main.guard = STACK_GUARD; // to check corruption of TCB by stack overflow
134 
135 #ifdef MTASK_PROF
136  s_main.stack_free = (uint32_t) -1;
137 #endif
138 
139  _forced_task = NULL;
140 }
141 
142 
143 // to do when nothing to do
144 static void idle_task(){
145  while(1){
146  __WFE();
147  // see RM090 12.2.3
148  TIMER6->regs->SR &= TIMER_SR_UIF; // reset pending bit
149  NVIC_ClearPendingIRQ(TIM6_DAC_IRQn); // timer6 as event generator - reset IRQ
150 
151  Scheduler::yield(0);
152  }
153 }
154 
156 {
157  if(in_interrupt()){ // some interrupt caused restart at ISR level
158  AP_HAL::panic("HAL initialization on ISR level=0x%x", (uint8_t)(SCB->ICSR & SCB_ICSR_VECTACTIVE_Msk));
159  }
160  memset(_io_proc, 0, sizeof(_io_proc) );
161  memset(io_completion, 0, sizeof(io_completion) );
162 
163 
164  // The PendSV exception is always enabled so disable interrupts
165  // to prevent it from occurring while being configured
166  noInterrupts();
167 
168  NVIC_SetPriority(PendSV_IRQn, PENDSV_INT_PRIORITY); // lowest priority so all IRQs can't be switced
169  NVIC_SetPriority(SVCall_IRQn, SVC_INT_PRIORITY); // priority 14 - the same as Timer7 ISR
170  NVIC_SetPriority(SysTick_IRQn, SYSTICK_INT_PRIORITY); // priority 5 - less thah fast device IO ISRs but higher than USB
171 
172 
173  // Ensure the effect of the priority change occurs before
174  // clearing PRIMASK to ensure that future PendSV exceptions
175  // are taken at the new priority
176  asm volatile("dsb \n");
177  asm volatile("isb \n");
178 
179  interrupts();
180 
181 
182  CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); //we don't need deep sleep
183  SET_BIT( SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); //we need Event on each interrupt
184 
185 /*[ DEBUG
186  SCnSCB->ACTLR |= SCnSCB_ACTLR_DISDEFWBUF_Msk; // disable imprecise exceptions
187 //]*/
188 
189  timer_foreach(timer_reset); // timer_reset(dev) moved out from configTimeBase so reset by hands
190 
191 
192  {// timeslice timer, not SYSTICK because we need to restart it by hands
193  uint32_t period = (2000000UL / SHED_FREQ) - 1;
194  // dev period freq, kHz
195  configTimeBase(TIMER7, period, 2000); //2MHz 0.5us ticks
196  Revo_handler h = { .isr = _timer_isr_event };
197  timer_attach_interrupt(TIMER7, TIMER_UPDATE_INTERRUPT, h.h , SVC_INT_PRIORITY); // almost lowest priority, higher than Pend_SW to schedule task switch
198  TIMER7->regs->CR1 |= TIMER_CR1_URS; // interrupt only by overflow, not by update
200  }
201 
202  {// timer5 - 32-bit general timer, unused for other needs
203  // so we can read micros32() directly from its counter and micros64() from counter and overflows
204  configTimeBase(TIMER5, 0, 1000); //1MHz 1us ticks
205  timer_set_count(TIMER5,(1000000/SHED_FREQ)/2); // to not interfere with TIMER7
206  Revo_handler h = { .isr = _timer5_ovf };
209  }
210 
211  { // only Timer6 from spare timers has personal NVIC line - TIM6_DAC_IRQn
212  uint32_t freq = configTimeBase(TIMER6, 0, 20000); // 20MHz - we here don't know real freq so can't set period
213  timer_set_reload(TIMER6, freq / 1000000); // period to generate 1uS requests
214  timer_enable_irq(TIMER6, TIMER_UPDATE_INTERRUPT); // enable interrupt requests from timer but not enable them in NVIC - will be events
216  }
217 
218  { // timer to generate more precise delays via quant termination
219  // dev period freq, kHz
220  configTimeBase(TIMER14, 0, 1000); //1MHz 1us ticks
222  timer_attach_interrupt(TIMER14, TIMER_UPDATE_INTERRUPT, h.h , SVC_INT_PRIORITY); // priority 14 - the same as Timer7 and SVC
223  TIMER14->regs->CR1 &= ~(TIMER_CR1_ARPE | TIMER_CR1_URS); // not buffered preload, interrupt by overflow or by UG set
224  }
225 
226 
227  { // timer to generate interrupt for driver's IO_Completion
228  // dev period freq, kHz
229  configTimeBase(TIMER13, 0, 1000); //1MHz 1us ticks
230  Revo_handler h = { .isr = _ioc_timer_event };
232  TIMER13->regs->CR1 &= ~(TIMER_CR1_ARPE | TIMER_CR1_URS); // not buffered preload, interrupt by overflow or by UG set
233  }
234 
235  void *task = _start_task((uint32_t)idle_task, 256); // only for one context
236  set_task_priority(task, 255); // lowest possible, to fill delay()
237  _idle_task=(task_t *)task;
238  set_task_active(task); // tasks are created paused so run it
239 }
240 
241 
242 
243 // it can't be started on init() because should be stopped in later_init()
245 #ifdef DEBUG_BUILD
246 // show stats output each 10 seconds
247  Revo_handler h = { .vp = _set_10s_flag };
248  void *task = _register_timer_task(10000000, h.h, NULL);
249  set_task_priority(task, IO_PRIORITY+1); // lower than IO_thread
250 #endif
251 
252 // task list is filled. so now we can do a trick -
253 // dequeue_task(_idle_task); // exclude idle task from task queue, it will be used by direct link.
254  // its own .next still shows to next task so no problems will. This works but...
255 
256 }
257 
258 void Scheduler::_delay(uint16_t ms)
259 {
260  uint32_t start = _micros();
261 #ifdef SHED_PROF
262  uint32_t t=start;
263 #endif
264 
265  uint32_t dt = ms * 1000;
266  uint32_t now;
267 
268  while((now=_micros()) - start < dt) {
269  if (hal.scheduler->_min_delay_cb_ms <= ms) { // MAVlink callback uses 5ms
270  hal.scheduler->call_delay_cb();
271  yield(1000 - (_micros() - now)); // to not stop MAVlink callback
272  } else {
273  yield(dt); // for full time
274  }
275  }
276 
277 
278 #ifdef SHED_PROF
279  uint32_t us=_micros()-t;
280  delay_time +=us;
281 
282 #endif
283 }
284 
285 // also see resume_boost()
286 // this used from InertialSensor only
289 
290 #ifdef SHED_PROF
291  uint32_t t = _micros();
292 #endif
293 
294  yield(us); // yield raises priority by 6 so task will be high-priority for 1st time
295 
296 #ifdef SHED_PROF
297  uint32_t r_us=_micros()-t; // real time
298  delay_time +=r_us;
299 #endif
301 }
302 
303 #define NO_YIELD_TIME 8 // uS
304 
306 {
307 
308 #ifdef SHED_PROF
309  uint32_t t = _micros();
310 #endif
311 
312  uint16_t no_yield_t; // guard time for main process
313  no_yield_t=NO_YIELD_TIME;
314 
315  if(us > no_yield_t){
316  yield(us);
317 
318  #ifdef SHED_PROF
319  uint32_t r_us=_micros()-t; // real time
320  delay_time +=r_us;
321  #endif
322 
323  }else{
324  _delay_us_ny(us);
325  }
326 
327 }
328 
329 void Scheduler::_delay_us_ny(uint16_t us){ // precise no yield delay
330  uint32_t rtime = stopwatch_getticks(); // get start ticks first
331 
332  uint32_t dt = us_ticks * us; // delay time in ticks
333 
334  while ((stopwatch_getticks() - rtime) < dt) {
335  // __WFE(); -- not helps very much
336  }
337 
338 #ifdef SHED_PROF
339  delay_time +=us;
340 
341 #endif
342 
343 }
344 
345 void Scheduler::register_delay_callback(AP_HAL::Proc proc, uint16_t min_time_ms)
346 {
347  static bool init_done=false;
348  if(!init_done){ // small hack to load HAL parameters in needed time
349 
350  ((HAL_F4Light&) hal).lateInit();
351 
352  init_done=true;
353  }
354 
356 
357 
358 /*
359 1 - it should run in delay() only
360 2 - it should be removed after init done
361  if(proc) {
362  _delay_cb_handle = start_task(proc);
363  } else {
364  stop_task(_delay_cb_handle);
365  }
366 */
367 }
368 
369 
371 {
372  if (_in_io_proc) {
373  return;
374  }
375  _in_io_proc = true;
376 
377  // now call the IO based drivers. TODO: per-task stats
378  for (int i = 0; i < _num_io_proc; i++) {
379  if (_io_proc[i].h) {
380  revo_call_handler(_io_proc[i].h,0);
381  if(_io_proc[i].flags == IO_ONCE){
382  _io_proc[i].h = 0;
383  }
384  }
385  }
386 
387  _in_io_proc = false;
388 }
389 
390 
392 {
394 
395  if(_num_io_proc==0){
396  void *task = start_task(_run_io, IO_STACK_SIZE);
397  set_task_period(task, 1000);
399  }
400 
401  uint8_t i;
402  for(i=0; i<_num_io_proc; i++){ // find free slots
403  if(_io_proc[i].h == 0) { // found
404  _io_proc[i].h = h;
405  _io_proc[i].flags = flags;
406  return;
407  }
408  }
409 
410  i=_num_io_proc++;
411  _io_proc[i].h = h;
412  _io_proc[i].flags = flags;
413 }
414 
415 
416 #ifdef MTASK_PROF
417 void Scheduler::check_stack(uint32_t sp) { // check for stack usage
418 
419 // uint32_t * stack = (uint32_t *)sp;
420 
421  // Stack frame contains:
422  // r0, r1, r2, r3, r12, r14, the return address and xPSR
423  // - Stacked R0 = stack[0]
424  // - Stacked R1 = stack[1]
425  // - Stacked R2 = stack[2]
426  // - Stacked R3 = stack[3]
427  // - Stacked R12 = stack[4]
428  // - Stacked LR = stack[5]
429  // - Stacked PC = stack[6]
430  // - Stacked xPSR= stack[7]
431 
432  if(ADDRESS_IN_CCM(sp)){
433  if(sp<lowest_stack){ lowest_stack=sp; }
434  }
435 }
436 #endif
437 
438 
439 void Scheduler::_run_timer_procs(bool called_from_isr) {
440 
441  // and the failsafe, if one is setted
442  if (_failsafe) {
443  static uint32_t last_failsafe=0;
444  uint32_t t=_millis();
445  if(t-last_failsafe>10){
446  last_failsafe = t+50; // 50ms = 20Hz
447  _failsafe();
448  }
449  }
450 
451 }
452 
453 void Scheduler::_timer_isr_event(uint32_t v /* TIM_TypeDef *tim */) {
454 #ifdef MTASK_PROF
455  uint32_t sp;
456  // Get stack pointer
457  asm volatile ("MRS %0, PSP\n\t" : "=rm" (sp));
458 
459  check_stack(sp);
460 #endif
461  static uint32_t last_timer_procs=0;
462 
463  uint32_t now = _micros();
464 
465  if(now - last_timer_procs >= 1000) {
466  last_timer_procs = now;
467  _run_timer_procs(true);
468  }
469 
470 
471 #ifndef MTASK_PROF
472  _switch_task();
473 #else
474 
475  if(task_n==0 || need_switch_task) return; // if there no tasks or already planned
476 
478  tsched_count++;
479 
480  if(next_task != s_running) { // if we should switch task
481  s_running->sw_type=0;
482  tsched_sw_count++;
483  plan_context_switch(); // plan context switch after return from ISR
484  }
485 #endif
486 }
487 
488 void Scheduler::_timer5_ovf(uint32_t v /* TIM_TypeDef *tim */) {
489  timer5_ovf_cnt++;
490 }
491 
493 #pragma pack(push, 1)
494  union {
495  uint64_t t;
496  uint32_t w[2];
497  } now;
498 #pragma pack(pop)
499 
500  noInterrupts();
501  now.w[0] = _micros();
502  now.w[1] = timer5_ovf_cnt;
503  interrupts();
504  return now.t;
505 }
506 
507 
509 {
510 #ifndef I_KNOW_WHAT_I_DO
511  if (_initialized) {
512  AP_HAL::panic("PANIC: scheduler::system_initialized called more than once");
513  }
514 #endif
515  _initialized = true;
516 
517  board_set_rtc_register(0,RTC_SIGNATURE_REG); // clear bootloader flag after init done
518 }
519 
520 
521 void Scheduler::_reboot(bool hold_in_bootloader) {
522 
523  if(hold_in_bootloader) {
524 #if 1
525  if(is_bare_metal() || hal_param_helper->_boot_dfu) { // bare metal build without bootloader of parameter set
526 
528 
529  } else
530 #endif
532  }
533 
534  _delay(100);
535 
536  NVIC_SystemReset();
537 
538  _delay(1000);
539 }
540 
541 
542 void Scheduler::reboot(bool hold_in_bootloader) {
543 
544  hal.console->println("GOING DOWN FOR A REBOOT\r\n");
545  _reboot(hold_in_bootloader);
546 }
547 
548 
549 
550 #ifdef DEBUG_BUILD
551 
552 extern "C" {
553  extern void *__brkval;
554  extern void *__brkval_ccm;
555 }
556 
557 
559  static int cnt=0;
560 
561  if(flag_10s) {
562  flag_10s=false;
563 
564 #if defined(USE_MPU)
565  mpu_disable(); // we need access to all tasks
566 #endif
567 
568 
569  uint32_t t=_millis();
570  const int Kf=100;
571 
572  switch(cnt++) {
573 
574  case 0:{
575 #ifdef SHED_PROF
576  float eff= (task_time)/(float)(task_time+shed_time);
577 
578  static float shed_eff=0;
579 
580  if(is_zero(shed_eff)) shed_eff = eff;
581  else shed_eff = shed_eff*(1 - 1/Kf) + eff*(1/Kf);
582 
583  printf("\nSched stats: uptime %lds\n %% of full time: %5.2f Efficiency %5.3f max loop time %ld\n", t/1000, (task_time/10.0)/t /* in percent*/ , shed_eff, max_loop_time);
584  printf("delay times: in main %5.2f including in timer %5.2f", (delay_time/10.0)/t, (delay_int_time/10.0)/t);
585  max_loop_time=0;
586 
587 #ifdef ISR_PROF
588  printf("\nISR time %5.2f max %5.2f", (isr_time/10.0/(float)us_ticks)/t, max_isr_time/(float)us_ticks );
589  max_isr_time=0;
590 #endif
591 #ifdef MPU_DEBUG
592  printf("MPU overflows: %ld restarts %ld max samples %ld time %ld\n", MPU_overflow_cnt, MPU_restart_cnt, MPU_count, MPU_Time); MPU_overflow_cnt=0; MPU_restart_cnt=0; MPU_count=0; MPU_Time=0;
593 #endif
594 
595  printf("\nPPM max buffer size: %d\n", RCInput::max_num_pulses); RCInput::max_num_pulses=0;
596 #endif
597 
598  } break;
599 
600  case 1:{
601 #ifdef SHED_PROF
602 #endif
603 
604  }break;
605 
606  case 2:{
607 #ifdef MTASK_PROF
608  task_t* ptr = &s_main;
609 
611  printf("\nsched time: by timer %5.2f%% sw %5.2f%% in yield %5.2f%% sw %5.2f%% in tails %5.2f%% sw %5.2f%%\n", 100.0*tsched_count/fc, 100.0 * tsched_sw_count/tsched_count, 100.0*tsched_count_y/fc,100.0 * tsched_sw_count_y/tsched_count_y, 100.0*tsched_count_t/fc, 100.0 * tsched_sw_count_t/tsched_count_t);
612 
613  do {
614  printf("task %d (0x%015llx) time: %7.2f%% mean %8.1fuS max %5lduS full %7lduS wait sem. %6lduS free stack 0x%lx\n",
615  ptr->id, ptr->handle, 100.0 * ptr->time/1000.0 / t,
616  (float)ptr->time / ptr->count,
617  ptr->max_time,
618  ptr->work_time, ptr->sem_max_wait, ptr->stack_free);
619 
620  ptr->max_time=0; // reset times
621  ptr->work_time=0;
622  ptr->sem_max_wait=0;
623  ptr->quants=0;
624  ptr->quants_time=0;
625  ptr->max_paused=0;
626 
627  ptr = ptr->next;
628  } while(ptr != &s_main);
629 #endif
630  }break;
631 
632  case 3: {
633  uint8_t n = I2CDevice::get_dev_count();
634  printf("\nI2C stats\n");
635 
636  for(uint8_t i=0; i<n; i++){
638  if(d){
639  printf("bus %d addr %x errors %ld last error=%d state=%d\n",d->get_bus(), d->get_addr(), d->get_error_count(), d->get_last_error(), d->get_last_error_state());
640  }
641  }
642  }break;
643 
644  case 4: {
645  uint32_t heap_ptr = (uint32_t)__brkval; // upper bound of sbrk()
646  uint32_t bottom = (uint32_t)&_sdata;
647 
648  // 48K after boot 72K while logging on
649  printf("\nMemory used: static %ldk full %ldk\n",((uint32_t)&_edata-bottom+1023)/1024, (heap_ptr-bottom+1023)/1024);
650  printf("Free stack: %ldk\n",(lowest_stack - (uint32_t)&_eccm)/1024);
651  printf("CCM use: %ldk\n",((uint32_t)__brkval_ccm - (uint32_t)&_sccm)/1024);
652 
653  } break;
654 
655  case 5: {
656  printf("\nIO completion %7.3f%%\n", ioc_time/1000.0/t*100);
657  uint64_t iot=0;
658  for(uint8_t i=0; i<num_io_completion; i++){
659  struct IO_COMPLETION &io = io_completion[i];
660 
661  if(io.handler) {
662  if(io.count){
663  printf("task %llx time %7.3f%% mean %7.3fuS max %lduS\n", io.handler, 100.0 * io.time / t / 1000, (float)io.time/io.count, io.max_time);
664  io.max_time=0;
665  iot+=io.time;
666  }
667  }
668  }
669  if(ioc_time)
670  printf("IO completion effectiveness=%7.3f%%\n", 100.0 * iot/ioc_time);
671 
672  }break;
673 
674  case 6:
675  default:
676  cnt=0;
677  break;
678  }
679  }
680 }
681 
683  flag_10s=true;
684  _print_stats();
685 }
686 #endif
687 
688 /*
689 [ common implementation of all Device.PeriodicCallback;
690 */
691 
693 
694  // all drivers will runs at individual IO tasks
695  void *task = _start_task(proc, SMALL_TASK_STACK);
696  if(task){
698  set_task_semaphore(task, sem);
699  set_task_period(task, period_us); // setting of period allows task to run
700  }
701  return (AP_HAL::Device::PeriodicHandle)task;
702 }
703 
704 
705 
706 
708 {
709  #pragma GCC diagnostic push
710  #pragma GCC diagnostic ignored "-Wcast-align" // yes I know
711 
712  task_t *p = (task_t *)h;
713  #pragma GCC diagnostic pop
714  p->period = period_us;
715  return true;
716 }
717 
719 {
720  #pragma GCC diagnostic push
721  #pragma GCC diagnostic ignored "-Wcast-align"
722  task_t *p = (task_t *)h;
723  #pragma GCC diagnostic pop
724 
725  noInterrupts(); // 64-bits should be
726  p->handle=0L;
727  interrupts();
728  return true;
729 }
730 // ]
731 
732 
733 //[ -------- preemptive multitasking --------
734 
735 
736 #if 0 // once started tasks are never ended
737 
739  task_t* ptr = &s_main;
740 
741  do {
742  if(ptr->handler == NULL) return ptr;
743 
744  ptr = ptr->next;
745  } while(ptr != &s_main);
746 
747  return NULL;
748 }
749 
750 #endif
751 
752 void Scheduler::stop_task(void *h){
753  if(h) {
754  task_t *tp = (task_t *)h ;
755  noInterrupts();
756  tp->handle = 0;
757  interrupts();
758  }
759 }
760 
761 
762 // task's executor, which calls user's function having semaphore
764  while(1){
765  uint32_t t=0;
766  if(task->handle && task->active) { // Task Switch occures asyncronously so we should wait until task becomes active again
767  task->time_start=_micros();
768  if(task->sem) {// if task requires a semaphore - block on it
769  if(!task->sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
770  yield(0); // can't be
771  continue;
772  }
773  revo_call_handler(task->handle, task->id);
774  task->sem->give(); // give semaphore when task finished
775  } else {
776  revo_call_handler(task->handle, task->id);
777  }
778 #ifdef MTASK_PROF
779  t = _micros()-task->time_start; // execution time
780  if(t > task->work_time) task->work_time=t;
781  if(task->t_paused > task->max_paused) {
782  task->max_paused = task->t_paused;
783  }
784  if(task->count_paused>task->max_c_paused) {
785  task->max_c_paused = task->count_paused;
786  }
787  task->count_paused=0;
788  task->t_paused=0;
789 #endif
790  task->active=false; // turn off active, to know when task is started again. last! or can never give semaphore
791  task->curr_prio = task->priority - 6; // just activated task will have a highest priority for one quant
792  }
793  yield(0); // give up quant remainder
794  } // endless loop
795 }
796 
797 void Scheduler::enqueue_task(task_t &tp) { // add new task to run queue, starting main task
798  tp.next = &s_main; // prepare for insert task into linked list
799  tp.prev = s_main.prev;
800  tp.id = ++task_n; // counter - new task is created
801 
802  noInterrupts(); // we will break linked list so do it in critical section
803  s_main.prev->next = &tp;
804  s_main.prev = &tp;
805  interrupts(); // now TCB is ready to task scheduler
806 }
807 
808 void Scheduler::dequeue_task(task_t &tp) { // remove task from run queue
809  noInterrupts(); // we will break linked list so do it in critical section
810  tp.prev->next = tp.next;
811  tp.next->prev = tp.prev;
812  interrupts(); // done
813 }
814 
815 
816 // Create task descriptor
818  memset(&tp,0,sizeof(tp));
819 
820  // fill required fields
821  tp.priority = MAIN_PRIORITY; // default priority equal to main task
822  tp.curr_prio = MAIN_PRIORITY; // current priority the same
823 #ifdef MTASK_PROF
824  tp.start=_micros();
825  tp.stack_free = (uint32_t) -1;
826 #endif
827  tp.guard = STACK_GUARD;
828 
829  return (uint32_t)&tp;
830 }
831 
832 // create task descriptor and context
833 void * Scheduler::init_task(Handler handler, const uint8_t* stack){
834 #pragma GCC diagnostic push
835 #pragma GCC diagnostic ignored "-Wcast-align" // yes I know
836 
837 // task_t *task = (task_t *)((uint32_t)(stack-sizeof(task_t)) & 0xFFFFFFFCUL); // control block below memory top, 4-byte alignment
838  task_t *task = (task_t *)((uint32_t)(stack-sizeof(task_t)) & 0xFFFFFFE0UL); // control block below memory top, 32-byte alignment for MMU page
839 #pragma GCC diagnostic pop
840 
841  fill_task(*task); // fill task descriptor
842  task->stack = stack;
843 
844  /*
845  * ARM Architecture Procedure Call Standard [AAPCS] requires 8-byte stack alignment.
846  * This means that we must get top of stack aligned _after_ context "pushing", at
847  * interrupt entry.
848  */
849  uint32_t *sp =(uint32_t *) (((uint32_t)task - 4) & 0xFFFFFFF8UL); // below TCB
850 
851 // HW frame
852  *(--sp) = 0x01000000UL; // xPSR
853  // 61000000
854  *(--sp) = ((uint32_t)do_task); // PC Entry Point - task executor
855  *(--sp) = ((uint32_t)do_task)|1; // LR the same, with thumb bit set
856  sp -= 4; // emulate "push R12,R3,R2,R1"
857  *(--sp) = (uint32_t)task; // emulate "push r0"
858 // SW frame, context saved as "STMDB R0!, {R4-R11, LR}"
859  *(--sp) = 0xFFFFFFFDUL; // emulate "push lr" =exc_return: Return to Thread mode, floating-point context inactive, execution uses PSP after return.
860 #if 0
861  asm volatile (
862  "MOV R0, %0 \n\t"
863  "STMDB R0!, {R4-R11}\n\t" : "+rm" (sp) ); // push real registers - they can be global register variables
864  "MOV %0,R0 \n\t"
865 #else
866  sp -= 8; // emulate "push R4-R11"
867 #endif
868  task->sp=(uint8_t *)sp; // set stack pointer of task
869 
870  // task is not active so we need not to disable interrupts
871  task->handle = handler; // save handler to TCB
872 
873  return (void *)task;
874 }
875 
876 
877 
878 // create a paused task
879 void * NOINLINE Scheduler::_start_task(Handler handle, size_t stackSize)
880 {
881  // Check called from main task
882  if (!_in_main_thread() ) return NULL;
883 
884  if(in_interrupt()) {
885  AP_HAL::panic("start_task called from ISR 0x%x", (uint8_t)(SCB->ICSR & SCB_ICSR_VECTACTIVE_Msk));
886  }
887 
888 #if defined(USE_MPU)
889  mpu_disable(); // we need access to new tasks TCB which can be overlapped by guard page
890 #endif
891 
892  // Adjust stack size with size of task context
893  stackSize += sizeof(task_t)+8; // for alignment
894 
895  if (s_main.stack == NULL) { // first call, initialize all task subsystem
896  s_main.stack = (const uint8_t*)RAMEND - s_top; // remember bottom of stack of main task on first call
897  }
898 
899  const uint8_t *sp=(const uint8_t*)s_main.prev->stack; // top of stack for new task
900 
901  task_t *task=(task_t *) init_task(handle, sp); // give stack top as parameter, will correct later
902  sp-= stackSize; // calc stack bottom
903  task->stack = sp; // correct to bottom of stack
904  stack_bottom = (caddr_t)sp; // and remember for memory allocator
905  s_top += stackSize; // adjust used size at stack top
906 
907  enqueue_task(*task); // task is ready, now we can add new task to run queue
908  // task will not be executed because .active==0
909 
910  return (void *)task; // return address of task descriptor as task handle
911 }
912 
913 // task should run periodically, period in uS. this will be high-priority task
914 void Scheduler::set_task_period(void *h, uint32_t period){
915  task_t *task = (task_t *)h;
916 
917  task->active = false; // will be first started after 'period'
918  task->time_start = _micros();
919  task->period = period;
920 }
921 
922 
923 #ifdef SHED_DEBUG
924 static uint16_t next_log_ptr(uint16_t sched_log_ptr){
925  uint16_t lp = sched_log_ptr+ 1;
926  if(lp >= SHED_DEBUG_SIZE) lp=0;
927  return lp;
928 }
929 #endif
930 
931 // exception occures in armed state - try to kill current task, or reboot if this is main task
933  task_t *me = s_running; // current task
934  uint8_t tmp = task_n;
935 
936  if(tmp==0 || me->id == 0) { // no tasks yet or in main task
937  board_set_rtc_register(FORCE_APP_RTC_SIGNATURE, RTC_SIGNATURE_REG); // force bootloader to not wait
938  _reboot(false);
939  }
940  stop_task(me); // exclude task from planning
941  task_n = 0; // printf() can call yield while we now between live and death
942 
943  printf("\nTaks %d killed by exception %d!\n",me->id, n);
944 
945  task_n = tmp;
947 }
948 
951 
952  while(1);
953 }
954 
956  task_n = 0;
957 }
958 
959 
960 // this function called only from SVC Level ISRs so there is no need to be reentrant
962  task_t *me = s_running; // current task
963  task_t *task=_idle_task; // task to switch to, idle_task by default
964 
965 
966  uint32_t timeFromLast=0;
967  uint32_t remains = 0;
968 
969  uint32_t partial_quant=(uint32_t)-1;
970  task_t *want_tail = NULL;
971 
972  uint32_t now = _micros();
973  me->t_yield = now;
974 
975 #if defined(USE_MPU)
976  mpu_disable(); // we need access to all tasks
977 #endif
978 
979  { // isolate dt
980 #if defined(MTASK_PROF)
981  uint32_t dt = now - me->start; // time in task
982  if(dt >= me->in_isr) dt -= me->in_isr; // minus time in interrupts
983  else dt=0;
984 
985  me->time+=dt; // calculate sum
986  me->quants_time+=dt;
987 #endif
988 
989 
990 #ifdef MTASK_PROF
991  if(dt > me->max_time) {
992  me->max_time = dt; // maximum to show
993  }
994 
995  #ifdef SHED_DEBUG
996  {
997  revo_sched_log &lp = logbuf[sched_log_ptr];
998  lp.end = now;
999  lp.task_id=me->id;
1000  lp.ttw = me->ttw;
1001  lp.in_isr = me->in_isr;
1002  lp.sw_type=me->sw_type;
1003  sched_log_ptr = next_log_ptr(sched_log_ptr);
1004  ZeroIt(logbuf[sched_log_ptr]); // clear next
1005  }
1006  #endif
1007 #endif
1008  }
1009 
1010  if(_forced_task) {
1011  task = _forced_task;
1012  _forced_task = NULL;
1013  } else {
1014 
1015  task_t *ptr = me; // starting from current task
1016  bool was_yield=false;
1017 
1018  while(true) { // lets try to find task to switch to
1019  ptr = ptr->next; // Next task in run queue will continue
1020 
1021 #if !defined(USE_MPU) || 1
1022  if(ptr->guard != STACK_GUARD){ // check for TCB is not damaged
1023  printf("PANIC: stack guard spoiled in process %d (from %d)\n", task->id, me->id);
1024  dequeue_task(*ptr); // исключить задачу из планирования
1025  goto skip_task; // skip this tasks
1026  }
1027 #endif
1028 
1029  if(!ptr->handle) goto skip_task; // skip finished tasks
1030 
1031  if(ptr->f_yield) { // task wants to give one quant
1032  ptr->f_yield = false;
1033  was_yield = true;
1034  goto skip_task; // skip this tasks
1035  }
1036 
1037 
1038  if(ptr->sem_wait) { // task want a semaphore
1039  if(ptr->sem_wait->is_taken()) { // task blocked on semaphore
1040  task_t *own =(task_t *)ptr->sem_wait->get_owner();
1041  if(own != ptr) { // owner is another task?
1042  uint32_t dt = now - ptr->sem_start_wait; // time since start waiting
1043  if(ptr->sem_time == HAL_SEMAPHORE_BLOCK_FOREVER || dt < ptr->sem_time) {
1044  if(own->curr_prio > ptr->curr_prio) {
1045  own->curr_prio=ptr->curr_prio;
1046  }
1047  goto skip_task;
1048  }
1049  }
1050  }
1051  ptr->sem_wait=NULL; // clear semaphore after release
1052 #ifdef MTASK_PROF
1053  uint32_t st=now-ptr->sem_start_wait;
1054  if(st>ptr->sem_max_wait) ptr->sem_max_wait=st; // time of semaphore waiting
1055 #endif
1056  }
1057 
1058 
1059  if(!ptr->active){ // non-active, is it periodic?
1060  if(ptr->period){
1061  timeFromLast = now - ptr->time_start; // time from last run
1062  if( timeFromLast < ptr->period) { // is less than task's period?
1063  remains = ptr->period - timeFromLast;
1064  if(remains>4) {
1065  if(remains<partial_quant && ptr->curr_prio <= want_tail->curr_prio) { // exclude low-prio tasks
1066  partial_quant=remains; // minimal time remains to next task
1067  want_tail = ptr;
1068  }
1069  goto skip_task;
1070  }// else execute task slightly before
1071  }
1072  } else { // non-active non-periodic tasks with manual activation
1073  goto skip_task; // should be skipped
1074  }
1075  ptr->active=true; // selected task to run, even if it will lose quant by priority
1076 
1077  } else { // обычный тайм слайс
1078 
1079  if(ptr->ttw){// task wants to wait
1080  timeFromLast = now - ptr->t_yield; // time since that moment
1081  if(timeFromLast < ptr->ttw){ // still less than ttw ?
1082  remains = ptr->ttw - timeFromLast; // remaining time to wait
1083  if(remains>4) { // context switch time
1084  if(remains<partial_quant && ptr->curr_prio <= want_tail->curr_prio) {
1085  partial_quant=remains;
1086  want_tail = ptr;
1087  }
1088  goto skip_task;
1089  }// else execute task slightly before
1090  }
1091  }
1092  }
1093 
1094 
1095  if(ptr->curr_prio <= task->curr_prio){ // select the most priority task, round-robin for equal priorities
1096  // task loose tick
1097  if(task->priority != 255) { // not for idle task
1098  if(task->curr_prio>1) task->curr_prio--; // increase priority if task loose tick
1099 // as a result of the rising priority of the waiting task, we do not completely stop the low priority tasks, but only slow them down
1100 // execution, forcing to skip the number of ticks equal to the priority difference. As a result, the low priority task is performed at a lower speed,
1101 // which can be adjusted by changing the priority difference
1102  }
1103  task = ptr; // winner
1104  } else { // ptr loose a chance - increase priority
1105  if(ptr->priority != 255) { // not for idle task
1106  if(ptr->curr_prio>1) ptr->curr_prio--;
1107  }
1108  }
1109 
1110 skip_task:
1111  // we should do this check after EACH task so can't use "continue" which skips ALL loop.
1112  // And we can't move this to begin of loop because then interrupted task does not participate in the comparison of priorities
1113  if(ptr == me) { // 'me' is the task that works now, so full loop - now we have most-priority task so let it run!
1114  if(was_yield && task == _idle_task) { // task wants to yield() but there is no other tasks
1115  was_yield=false; // reset flag and loop again
1116  } else {
1117  break; // task found
1118  }
1119  }
1120  }
1121  }
1122 
1123  // task to run is selected
1124 
1125  #ifdef SHED_DEBUG
1126  revo_sched_log &lp = logbuf[sched_log_ptr];
1127  lp.start = now;
1128  lp.task_id=task->id;
1129  lp.prio = task->curr_prio;
1130  lp.active = task->active;
1131  lp.time_start = task->time_start;
1132  lp.quant = partial_quant;
1133  lp.want_tail = want_tail;
1134  ZeroIt(logbuf[next_log_ptr(sched_log_ptr)]); // clear next
1135  #endif
1136 
1137  task->curr_prio=task->priority; // reset current priority to default value
1138  task->ttw=0; // time to wait is over
1139 #if defined(MTASK_PROF)
1140  task->start = now; // task startup time
1141  task->in_isr=0; // reset ISR time
1142  task->count++; // full count
1143  task->quants++; // one-start count
1144 
1145  uint32_t sz = s_running->sp - s_running->stack;
1146  if(sz< s_running->stack_free) s_running->stack_free = sz;
1147 
1148 #endif
1149 
1150  if(want_tail && want_tail->curr_prio <= task->curr_prio) { // we have a high-prio task that want to be started next in the middle of tick
1151  if(partial_quant < TIMER_PERIOD-10) { // if time less than tick
1153  timer_set_reload(TIMER14, partial_quant+2); // +2 to guarantee
1155  }
1156  }
1157 
1158  return task;
1159 }
1160 
1161 
1162 
1163 /*
1164  interrupt to reduce timeslice quant
1165 */
1166 void Scheduler::_tail_timer_event(uint32_t v /*TIM_TypeDef *tim */){
1167  timer_pause(TIMER14); // stop tail timer
1168  timer_generate_update(TIMER7); // tick is over
1169 #ifndef MTASK_PROF
1170  _switch_task();
1171 #else
1172 
1173  if(need_switch_task || task_n==0) return; // already scheduled context switch
1174 
1176 
1177  tsched_count_t++;
1178 
1179  if(next_task != s_running) { // if we should switch task
1180  s_running->sw_type=1;
1183  }
1184 #endif
1185 }
1186 
1187 
1188 void Scheduler::yield(uint16_t ttw) // time to wait
1189 {
1190  if(task_n==0 || in_interrupt()) { // SVC causes HardFault if in interrupt so just nothing to do
1191  #ifdef USE_WFE
1192  if(ttw) {__WFE(); }
1193  #endif
1194  return;
1195  }
1196 
1197 // if yield() called with a time, then task don't want to run all this time so exclude it from time sliceing
1198  if(ttw) { // ttw cleared on sleep exit so always 0 if not set specially
1199  s_running->ttw=ttw; // if switching tasks occurs between writing and calling svc, we just add an extra tick
1200  }
1201  asm volatile("svc 0");
1202 }
1203 
1204 
1210  unsigned char marker;
1211  return (&marker - s_running->stack);
1212 }
1213 
1214 
1215 
1216 
1217 
1218 // register IO completion routine
1220 
1222  io_completion[num_io_completion].handler=handler; // no need to disable interrupts because we increment counter later
1224  return ++num_io_completion;
1225  }
1226  return 0;
1227 }
1228 
1229 void Scheduler::_ioc_timer_event(uint32_t v){ // isr at low priority to do all IO completion routines
1230  bool do_it = false;
1231 
1232 #ifdef SHED_PROF
1233  uint32_t full_t=_micros();
1234 #endif
1235 
1236  do {
1237  do_it = false;
1238  for(uint8_t i=0; i<num_io_completion; i++){
1239  IO_Completion &io = io_completion[i];
1240 
1241  if(io.request) {
1242  io.request=false; // ASAP - it can be set again in interrupt.
1243  // we don't need to disable interrupts because all drivers has own queue and can survive a skipping of one request
1244  if(io.handler){
1245  do_it=true;
1246 
1247 #ifdef SHED_PROF
1248  uint32_t t = _micros();
1249 #endif
1250  revo_call_handler(io.handler,i); // call it
1251 #ifdef SHED_PROF
1252  t = _micros() - t;
1253  io.time += t;
1254  io.count++;
1255  if(t>io.max_time) io.max_time=t;
1256 #endif
1257  }
1258  }
1259  }
1260  } while(do_it);
1261 
1262 #ifdef SHED_PROF
1263  full_t=_micros() - full_t;
1264  ioc_time += full_t;
1265 #endif
1266 
1267 #ifdef MTASK_PROF
1268 // To exclude the interruption time from the task's time, which it interrupted
1269  s_running->in_isr += full_t;
1270 #endif
1271 
1272 }
1273 
1274 #pragma GCC optimize ("O2") // should ALWAYS be -O2 for tail recursion optimization in PendSV_Handler
1275 
1276 /* how to configure and schedule a PendSV exception
1277 from http://infocenter.arm.com/help/index.jsp?topic=/com.arm.doc.dui0395b/CIHJHFJD.html
1278 */
1279 
1282 #if defined(USE_MPU)
1283  // set the guard page for the next task
1285  (uint32_t)(next_task->stack) & ~31, // end of stack in the guard page
1287 
1288  mpu_enable(MPU_CTRL_PRIVDEFENA); // enable default memory map
1289 #endif
1291 }
1292 
1294  uint32_t * svc_args;
1295 
1296 // SVC can't be used from any interrupt so this is only for reliability
1297  asm volatile (
1298  "TST lr, #4 \n"
1299  "ite eq \n"
1300  "MRSEQ %0, MSP \n"
1301  "MRSNE %0, PSP \n"
1302  : "=rm" (svc_args) );
1303 
1304  Scheduler::SVC_Handler(svc_args);
1305 }
1306 
1307 
1308 // svc executes on same priority as Timer7 ISR so there is no need to prevent interrupts
1309 void Scheduler::SVC_Handler(uint32_t * svc_args){
1310  // * Stack contains: * r0, r1, r2, r3, r12, r14, the return address and xPSR
1311  unsigned int svc_number = ((char *)svc_args[6])[-2];
1312 
1313  bool ret;
1314  switch(svc_number) {
1315  case 0: // Handle SVC 00 - yield()
1316  timer_generate_update(TIMER7); // tick is over
1318 
1319  if(s_running->priority!=255){ // not for idle task or low-priority tasks
1320  if(s_running->priority<IO_PRIORITY && s_running->ttw){ // the task voluntarily gave up its quant and wants delay, so that at the end of the delay it will have the high priority
1322  } else {
1323  s_running->f_yield = true; // to guarantee that quant will not return even if there is no high priority tasks
1324  }
1325  }
1326  switch_task();
1327  break;
1328 
1329  case 1:{ // Handle SVC 01 - semaphore give(semaphore) returns bool
1330  Semaphore * sem = (F4Light::Semaphore *)svc_args[0];
1331  bool v=sem->is_waiting();
1332  svc_args[0] = sem->svc_give();
1333  if(v) switch_task(); // switch context to waiting task if any
1334  }
1335  break;
1336 
1337  case 2:{ // Handle SVC 02 - semaphore take(semaphore, time) returns bool
1338  Semaphore * sem = (F4Light::Semaphore *)svc_args[0];
1339  uint32_t timeout_ms = svc_args[1];
1340  svc_args[0] = ret = sem->svc_take(timeout_ms);
1341  if(!ret) { // if failed - switch context to pause waiting task
1342  task_t *own = (task_t *)sem->get_owner();
1343  task_t *curr_task = s_running;
1344  curr_task->sem_wait = sem; // semaphore
1345  curr_task->sem_start_wait = _micros(); // time when waiting starts
1346  if(timeout_ms == HAL_SEMAPHORE_BLOCK_FOREVER){
1347  curr_task->sem_time = timeout_ms;
1348  } else {
1349  curr_task->sem_time = timeout_ms*1000; // time to wait semaphore
1350  }
1351  //Increase the priority of the semaphore's owner up to the priority of the current task
1352  if(own->priority >= curr_task->priority) own->curr_prio = curr_task->priority-1;
1353  switch_task();
1354  }
1355  }
1356  break;
1357 
1358  case 3:{ // Handle SVC 03 - semaphore take_nonblocking(semaphore) returns bool
1359  Semaphore * sem = (F4Light::Semaphore *)svc_args[0];
1360  svc_args[0] = ret = sem->svc_take_nonblocking();
1361  if(!ret) { // if failed - switch context to give tick to semaphore's owner
1362  task_t *own = (task_t *)sem->get_owner();
1363  task_t *curr_task = s_running;
1364  //Increase the priority of the semaphore's owner up to the priority of the current task
1365  if(own->priority >= curr_task->priority) own->curr_prio = curr_task->priority-1;
1366 
1367  switch_task();
1368  }
1369  }
1370  break;
1371 
1372  case 4: // whats more we can do via SVC?
1373 
1374  default: // Unknown SVC - just ignore
1375  break;
1376  }
1377 }
1378 
1379 // prepare task switch and plan it if needed. This function called only on ISR level 14
1381  timer_pause(TIMER14); // we will recalculate scheduling
1382  timer_generate_update(TIMER7); // tick is over
1383  _switch_task();
1384 }
1385 
1387  if(need_switch_task || task_n==0) return; // already scheduled context switch
1388 
1389  next_task = get_next_task(); // 2.5uS mean full time
1390 
1391 #ifdef MTASK_PROF
1392  tsched_count_y++;
1393 #endif
1394 
1395  if(next_task != s_running) { // if we should switch task
1396 #ifdef MTASK_PROF
1397  s_running->sw_type=2;
1399 #endif
1401  }
1402 #ifdef MTASK_PROF
1403  else if(next_task == _idle_task){ // the same idle task
1404  tsched_count_y--; // don't count loops in idle task
1405  }
1406 #endif
1407 }
1408 
1410 /*
1411 union Revo_handler { // blood, bowels, assembler :) transform functors into a unified view for calling from C
1412  voidFuncPtr vp;
1413  AP_HAL::MemberProc mp; this is C not C ++, so we can not declare the support of functors explicitly, and are forced to pass
1414  uint64_t h; // treat as handle <-- as 64-bit integer
1415  uint32_t w[2]; // words, to check. if this is a functor then the high is the address of the flash and the lower one is the address in RAM.
1416  if this is a function pointer then lower word is an address in flash and high is 0
1417 };
1418 */
1419 
1420 void revo_call_handler(uint64_t hh, uint32_t arg){
1421  Revo_handler h = { .h = hh };
1422 
1423  if(ADDRESS_IN_FLASH(h.w[0])){
1424  (h.isr)(arg);
1425  } else if(ADDRESS_IN_FLASH(h.w[1])) {
1426  (h.mpa)(arg);
1427  }
1428 }
1429 
1430 void hal_yield(uint16_t ttw){ Scheduler::yield(ttw); }
1431 void hal_delay(uint16_t t){ Scheduler::_delay(t); }
1433 
1434 uint32_t hal_micros() { return Scheduler::_micros(); }
1435 void hal_isr_time(uint32_t t) { s_running->in_isr += t; }
1436 
1437 // task management for USB and another C code
1440 void hal_set_task_priority(void * h, uint8_t prio) {Scheduler::set_task_priority(h, prio); }
1441 void * hal_register_task(voidFuncPtr task, uint32_t stack) {
1442  Revo_handler r = { .vp=task };
1443  return Scheduler::_start_task(r.h, stack);
1444 }
1445 
1446 bool hal_is_armed() { return hal.util->get_soft_armed(); }
void hal_go_next_task()
Definition: Scheduler.cpp:1448
bool svc_take_nonblocking()
Definition: Semaphores.cpp:112
void revo_call_handler(uint64_t hh, uint32_t arg)
Definition: Scheduler.cpp:1420
void(* voidFuncPtr)(void)
Definition: hal_types.h:16
#define TIMER5
Definition: timer.h:613
#define ADDRESS_IN_CCM(a)
Definition: hal_types.h:92
static uint32_t stopwatch_getticks()
Definition: stopwatch.h:33
#define MPU_CTRL_PRIVDEFENA
Definition: mpu.h:21
task_t * prev
Definition: Scheduler.h:53
int printf(const char *fmt,...)
Definition: stdio.c:113
bool get_soft_armed() const
Definition: Util.h:15
bool active
Definition: Scheduler.h:59
uint32_t max_time
Definition: Scheduler.h:75
uint32_t start
Definition: Scheduler.h:70
uint8_t get_last_error_state()
Definition: I2CDevice.h:127
#define MPU_INT_PRIORITY
Definition: Config.h:48
static void _timer5_ovf(uint32_t v)
Definition: Scheduler.cpp:488
static void context_switch_isr()
Definition: Scheduler.h:312
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
static INLINE void noInterrupts()
Definition: exti.h:120
Handler h
Definition: handler.h:20
static void mpu_disable()
Definition: mpu.h:116
static uint32_t tsched_count_y
Definition: Scheduler.h:561
uint64_t time
Definition: Scheduler.h:74
#define STACK_GUARD
Definition: Scheduler.cpp:52
bool f_yield
Definition: Scheduler.h:60
void hal_stop_multitask()
Definition: Scheduler.cpp:1449
static void switch_task()
Definition: Scheduler.cpp:1380
#define FORCE_APP_RTC_SIGNATURE
Definition: boards.h:293
static uint32_t tsched_sw_count_t
Definition: Scheduler.h:564
#define NO_YIELD_TIME
Definition: Scheduler.cpp:303
#define MPU_RASR_SIZE_32
Definition: mpu.h:32
AP_HAL::UARTDriver * console
Definition: HAL.h:110
static size_t task_stack()
Definition: Scheduler.cpp:1209
revo_isr_handler isr
Definition: handler.h:15
static task_t s_main
Definition: Scheduler.h:488
void timer_reset(const timer_dev *dev)
Definition: timer.c:316
uint32_t stack_free
Definition: Scheduler.h:85
static INLINE void interrupts()
Definition: exti.h:106
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
caddr_t stack_bottom
Definition: syscalls.c:74
void hal_set_task_priority(void *h, 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
#define DRIVER_PRIORITY
Definition: Scheduler.h:25
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
uint32_t max_paused
Definition: Scheduler.h:83
uint32_t ttw
Definition: Scheduler.h:61
AP_HAL::Util * util
Definition: HAL.h:115
static void * get_current_task()
Definition: Scheduler.h:299
virtual void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms)
Definition: Scheduler.cpp:5
static void _run_timer_procs(bool called_from_isr)
Definition: Scheduler.cpp:439
void PendSV_Handler()
Definition: Scheduler.cpp:1280
static void enqueue_task(task_t &tp)
Definition: Scheduler.cpp:797
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
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
bool svc_take(uint32_t timeout_ms)
Definition: Semaphores.cpp:136
static void _try_kill_task_or_reboot(uint8_t n)
Definition: Scheduler.cpp:932
static void * boost_task
Definition: Scheduler.h:494
uint32_t sem_start_wait
Definition: Scheduler.h:68
void * _edata
static uint32_t tsched_count
Definition: Scheduler.h:559
static uint64_t delay_int_time
Definition: Scheduler.h:542
static void _set_10s_flag()
Definition: Scheduler.cpp:682
uint8_t id
Definition: Scheduler.h:56
static INLINE void timer_pause(const timer_dev *dev)
Stop a timer&#39;s counter from changing.
Definition: timer.h:679
static void _print_stats()
Definition: Scheduler.cpp:558
static void idle_task()
Definition: Scheduler.cpp:144
uint32_t w[2]
Definition: handler.h:21
timer interface.
uint32_t work_time
Definition: Scheduler.h:77
static INLINE void timer_set_count(const timer_dev *dev, uint16_t value)
Sets the counter value for the given timer.
Definition: timer.h:715
static void _register_io_process(Handler h, Revo_IO_Flags flags)
Definition: Scheduler.cpp:391
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static void set_task_active(void *h)
Definition: Scheduler.h:306
void timer_attach_interrupt(const timer_dev *dev, timer_interrupt_id interrupt, Handler handler, uint8_t priority)
Attach a timer interrupt.
Definition: timer.c:485
static void _switch_task()
Definition: Scheduler.cpp:1386
static void _timer_isr_event(uint32_t v)
Definition: Scheduler.cpp:453
void ZeroIt(T &value)
Definition: handler.h:5
uint32_t in_isr
Definition: Scheduler.h:71
static uint32_t max_wfe_time
Definition: Scheduler.h:558
static void _reboot(bool hold_in_bootloader)
Definition: Scheduler.cpp:521
void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms) override
Definition: Scheduler.cpp:345
static INLINE void timer_resume(const timer_dev *dev)
Start a timer&#39;s counter.
Definition: timer.h:690
void * __brkval
Definition: syscalls.c:71
#define MPU_REGION_0
Definition: mpu.h:97
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
static void check_stack(uint32_t sp)
Definition: Scheduler.cpp:417
uint32_t sem_time
Definition: Scheduler.h:67
uint32_t guard
Definition: Scheduler.h:87
void hal_try_kill_task_or_reboot(uint8_t n)
Definition: Scheduler.cpp:1447
uint32_t time_start
Definition: Scheduler.h:64
#define SHED_FREQ
Definition: Scheduler.h:28
static size_t s_top
Definition: Scheduler.h:489
task_t * s_running
static uint32_t max_delay_err
Definition: Scheduler.h:548
#define MPU_RASR_ATTR_AP_RO_RO
Definition: mpu.h:87
void system_initialized()
Definition: Scheduler.cpp:508
uint32_t count
Definition: Scheduler.h:76
static void * init_task(uint64_t h, const uint8_t *stack)
Definition: Scheduler.cpp:833
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
#define TIMER13
Definition: timer.h:621
static uint32_t _millis()
Definition: Scheduler.h:229
#define TIMER_CR1_URS
Definition: timer.h:98
#define BOOT_RTC_SIGNATURE
Definition: boards.h:291
static uint64_t _micros64()
Definition: Scheduler.cpp:492
static uint8_t get_dev_count()
Definition: I2CDevice.h:131
uint32_t hal_micros()
Definition: Scheduler.cpp:1434
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
bool hal_is_armed()
Definition: Scheduler.cpp:1446
void hal_set_task_active(void *h)
Definition: Scheduler.cpp:1438
uint32_t quants
Definition: Scheduler.h:79
static void * _start_task(Handler h, size_t stackSize)
Definition: Scheduler.cpp:879
void * PeriodicHandle
Definition: Device.h:42
#define TIMER_SR_UIF
Definition: timer.h:225
uint32_t count_paused
Definition: Scheduler.h:82
static void _delay_us_ny(uint16_t us)
Definition: Scheduler.cpp:329
static void SVC_Handler(uint32_t *svc_args)
Definition: Scheduler.cpp:1309
static void set_task_period(void *h, uint32_t period)
Definition: Scheduler.cpp:914
void println(const char *str)
Definition: BetterStream.h:34
MemberProcArg mpa
Definition: handler.h:19
static uint32_t lowest_stack
Definition: Scheduler.h:530
void hal_isr_time(uint32_t t)
Definition: Scheduler.cpp:1435
F4Light::Semaphore * sem_wait
Definition: Scheduler.h:66
void * _sdata
#define MAIN_STACK_SIZE
Definition: Scheduler.h:32
uint32_t sem_max_wait
Definition: Scheduler.h:78
virtual void call_delay_cb()
Definition: Scheduler.cpp:12
F4Light::Semaphore * sem
Definition: Scheduler.h:65
static uint16_t task_n
Definition: Scheduler.h:490
float v
Definition: Printf.cpp:15
static bool _in_io_proc
Definition: Scheduler.h:524
uint8_t priority
Definition: Scheduler.h:57
#define RAMEND
Definition: Scheduler.h:135
#define TIMER6
Definition: timer.h:614
const uint8_t * stack
Definition: Scheduler.h:55
static uint32_t tsched_count_t
Definition: Scheduler.h:563
static void yield(uint16_t ttw=0)
Definition: Scheduler.cpp:1188
static bool _in_main_thread()
Definition: Scheduler.h:365
uint8_t sw_type
Definition: Scheduler.h:73
uint16_t _min_delay_cb_ms
Definition: Scheduler.h:88
static uint16_t max_num_pulses
Definition: RCInput.h:51
#define MAIN_PRIORITY
Definition: Scheduler.h:24
void hal_context_switch_isr()
Definition: Scheduler.cpp:1439
#define NULL
Definition: hal_types.h:59
uint32_t us_ticks
Definition: stopwatch.c:10
static uint64_t shed_time
Definition: Scheduler.h:537
static bool adjust_timer_task(AP_HAL::Device::PeriodicHandle h, uint32_t period_us)
Definition: Scheduler.cpp:707
static void _run_io(void)
Definition: Scheduler.cpp:370
static void timer_enable_irq(const timer_dev *dev, timer_interrupt_id interrupt)
Enable a timer interrupt.
Definition: timer.h:1125
static void _delay_microseconds_boost(uint16_t us)
Definition: Scheduler.cpp:287
void * get_owner()
Definition: Semaphores.h:43
task_t * next_task
static struct IO_COMPLETION io_completion[MAX_IO_COMPLETION]
Definition: Scheduler.h:532
caddr_t _eccm
static void mpu_enable(uint32_t ctrl)
Definition: mpu.h:111
static uint32_t _micros()
Definition: Scheduler.h:232
Revo_IO_Flags
Definition: Scheduler.h:157
static Revo_IO _io_proc[F4Light_SCHEDULER_MAX_IO_PROCS]
Definition: Scheduler.h:521
static uint64_t task_time
Definition: Scheduler.h:538
void hal_yield(uint16_t ttw)
Definition: Scheduler.cpp:1430
#define TIMER_CR1_ARPE
Definition: timer.h:90
static bool unregister_timer_task(AP_HAL::Device::PeriodicHandle h)
Definition: Scheduler.cpp:718
static F4Light::I2CDevice * get_device(uint8_t i)
Definition: I2CDevice.h:132
#define SMALL_TASK_STACK
Definition: Scheduler.h:35
bool take(uint32_t timeout_ms)
Definition: Semaphores.cpp:45
void hal_delay(uint16_t t)
Definition: Scheduler.cpp:1431
#define IOC_INT_PRIORITY
Definition: Config.h:51
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 void _delay(uint16_t ms)
Definition: Scheduler.cpp:258
static void do_task(task_t *task)
Definition: Scheduler.cpp:763
uint32_t get_error_count()
Definition: I2CDevice.h:125
static uint32_t tick_count
Definition: Scheduler.h:552
Handler handle
Definition: Scheduler.h:54
static task_t * _forced_task
Definition: Scheduler.h:493
AP_HAL::Proc Scheduler::_failsafe IN_CCM
Definition: Scheduler.cpp:34
#define NOINLINE
Definition: AP_Common.h:37
void board_set_rtc_register(uint32_t sig, uint16_t reg)
Definition: boards.cpp:141
uint32_t configTimeBase(const timer_dev *dev, uint16_t period, uint16_t khz)
Definition: timer.c:357
static task_t * get_empty_task()
static void dequeue_task(task_t &tp)
Definition: Scheduler.cpp:808
static uint32_t max_loop_time
Definition: Scheduler.h:543
#define DFU_RTC_SIGNATURE
Definition: boards.h:292
#define TIMER7
Definition: timer.h:615
static void loc_ret()
Definition: Scheduler.cpp:50
static void mpu_configure_region(uint8_t region, uint32_t addr, uint32_t attribs)
Definition: mpu.h:122
voidFuncPtr vp
Definition: handler.h:14
const uint8_t * sp
Definition: Scheduler.h:51
static AP_HAL::Device::PeriodicHandle _register_timer_task(uint32_t period_us, Handler proc, F4Light::Semaphore *sem)
Definition: Scheduler.cpp:692
uint64_t Handler
Definition: hal_types.h:19
static void _stop_multitask()
Definition: Scheduler.cpp:955
static uint64_t ioc_time
Definition: Scheduler.h:546
static INLINE void timer_set_reload(const timer_dev *dev, uint32_t arr)
Set a timer&#39;s reload value.
Definition: timer.h:763
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define RTC_SIGNATURE_REG
Definition: boards.h:312
static void _delay_microseconds(uint16_t us)
Definition: Scheduler.cpp:305
task_t * next
Definition: Scheduler.h:52
#define MPU_RASR_ATTR_NON_CACHEABLE
Definition: mpu.h:93
uint32_t period
Definition: Scheduler.h:63
#define SVC_INT_PRIORITY
Definition: Config.h:53
#define SYSTICK_INT_PRIORITY
Definition: Config.h:44
uint8_t get_bus()
Definition: I2CDevice.h:128
#define PENDSV_INT_PRIORITY
Definition: Config.h:54
static bool flag_10s
Definition: Scheduler.h:539
static void _go_next_task()
Definition: Scheduler.cpp:949
uint8_t get_last_error()
Definition: I2CDevice.h:126
static void * _delay_cb_handle
Definition: Scheduler.h:505
uint8_t get_addr()
Definition: I2CDevice.h:129
#define TIMER14
Definition: timer.h:622
Revo_IO_Flags flags
Definition: Scheduler.h:164
void timer_foreach(void(*fn)(const timer_dev *))
Call a function on timer devices.
Definition: timer.c:468
static task_t * get_next_task()
Definition: Scheduler.cpp:961
static bool is_bare_metal()
Definition: boards.h:149
static task_t * _idle_task
Definition: Scheduler.h:492
static uint32_t fill_task(task_t &tp)
Definition: Scheduler.cpp:817
void * __brkval_ccm
Definition: syscalls.c:72
static void stop_task(void *h)
Definition: Scheduler.cpp:752
void hal_delay_microseconds(uint16_t t)
Definition: Scheduler.cpp:1432
#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
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
#define IO_PRIORITY
Definition: Scheduler.h:26
static void _ioc_timer_event(uint32_t v)
Definition: Scheduler.cpp:1229
void reboot(bool hold_in_bootloader)
Definition: Scheduler.cpp:542
static void _tail_timer_event(uint32_t v)
Definition: Scheduler.cpp:1166
#define TIMER_PERIOD
Definition: Scheduler.h:29
#define IO_STACK_SIZE
Definition: Scheduler.h:33
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
static uint8_t register_io_completion(Handler handle)
Definition: Scheduler.cpp:1219
static void start_stats_task()
Definition: Scheduler.cpp:244
#define ADDRESS_IN_FLASH(a)
Definition: hal_types.h:93