APM:Libraries
timer.c
Go to the documentation of this file.
1 /******************************************************************************
2  * The MIT License
3 
4 (c) 2017 night_ghost@ykoctpa.ru
5 
6 based on:
7 
8  *
9  * Copyright (c) 2011 LeafLabs, LLC.
10  *
11  * Permission is hereby granted, free of charge, to any person
12  * obtaining a copy of this software and associated documentation
13  * files (the "Software"), to deal in the Software without
14  * restriction, including without limitation the rights to use, copy,
15  * modify, merge, publish, distribute, sublicense, and/or sell copies
16  * of the Software, and to permit persons to whom the Software is
17  * furnished to do so, subject to the following conditions:
18  *
19  * The above copyright notice and this permission notice shall be
20  * included in all copies or substantial portions of the Software.
21  *
22  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
23  * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
24  * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
25  * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
26  * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
27  * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
28  * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
29  * SOFTWARE.
30  *****************************************************************************/
31 
32 #pragma GCC optimize ("O2")
33 
40 #include "timer.h"
41 #include "dma.h"
42 #include <string.h>
43 #include "nvic.h"
44 
45 /* Just like the corresponding DIER bits:
46  * [0] = Update handler;
47  * [1,2,3,4] = capture/compare 1,2,3,4 handlers, respectively;
48  * [5] = COM;
49  * [6] = TRG;
50  * [7] = BRK. */
51 #define NR_ADV_HANDLERS 8
52 /* Update, capture/compare 1,2,3,4; <junk>; trigger. */
53 #define NR_GEN_HANDLERS 7
54 /* Update only. */
55 #define NR_BAS_HANDLERS 1
56 
57 
58 static Handler tim1_handlers[NR_ADV_HANDLERS] IN_CCM;
59 static Handler tim2_handlers[NR_GEN_HANDLERS] IN_CCM;
60 static Handler tim3_handlers[NR_GEN_HANDLERS] IN_CCM;
61 static Handler tim4_handlers[NR_GEN_HANDLERS] IN_CCM;
62 static Handler tim5_handlers[NR_GEN_HANDLERS] IN_CCM;
63 static Handler tim6_handlers[NR_BAS_HANDLERS] IN_CCM;
64 static Handler tim7_handlers[NR_BAS_HANDLERS] IN_CCM;
65 static Handler tim8_handlers[NR_ADV_HANDLERS] IN_CCM;
66 static Handler tim9_handlers[NR_GEN_HANDLERS] IN_CCM;
67 static Handler tim10_handlers[NR_GEN_HANDLERS] IN_CCM;
68 static Handler tim11_handlers[NR_GEN_HANDLERS] IN_CCM;
69 static Handler tim12_handlers[NR_GEN_HANDLERS] IN_CCM;
70 static Handler tim13_handlers[NR_GEN_HANDLERS] IN_CCM;
71 static Handler tim14_handlers[NR_GEN_HANDLERS] IN_CCM;
72 
73 static timerState timer_state[14] IN_CCM;
74 
75 const timer_dev timers[] = {
76  {
78  .regs = TIM1,
79  .clk = RCC_APB2Periph_TIM1,
80  .handlers = tim1_handlers,
81  .af = GPIO_AF_TIM1,
82  .type = TIMER_ADVANCED,
83  .n_handlers = NR_ADV_HANDLERS,
84  .bus = 1,
85  .id = 1,
86  .state = &timer_state[0],
87  .ch_dma = { // dma per channel: stream, channel
88  { DMA2_STREAM1, 6 },
89  { DMA2_STREAM2, 6 },
90  { DMA2_STREAM6, 6 },
91  { DMA2_STREAM4, 6 },
92  },
93  },
94 
95  {
96  .regs = TIM2,
97  .clk = RCC_APB1Periph_TIM2,
98  .handlers = tim2_handlers,
99  .af = GPIO_AF_TIM2,
100  .type = TIMER_GENERAL,
101  .n_handlers = NR_GEN_HANDLERS,
102  .bus = 0,
103  .id = 2,
104  .state = &timer_state[1],
105  .ch_dma = { // dma per channel: stream, channel
106  { DMA1_STREAM5, 3 },
107  { DMA1_STREAM6, 3 },
108  { DMA1_STREAM1, 3 },
109  { DMA1_STREAM7, 6 },
110  },
111 
112  },
113 
114  {
115  .regs = TIM3,
116  .clk = RCC_APB1Periph_TIM3,
117  .handlers = tim3_handlers,
118  .af = GPIO_AF_TIM3,
119  .type = TIMER_GENERAL,
120  .n_handlers = NR_GEN_HANDLERS,
121  .bus = 0,
122  .id = 3,
123  .state = &timer_state[2],
124  .ch_dma = { // dma per channel: stream, channel
125  { DMA1_STREAM4, 5 },
126  { DMA1_STREAM5, 5 },
127  { DMA1_STREAM7, 5 },
128  { DMA1_STREAM2, 5 },
129  },
130 
131  },
132 
133  {
134  .regs = TIM4,
135  .clk = RCC_APB1Periph_TIM4,
136  .handlers = tim4_handlers,
137  .af = GPIO_AF_TIM4,
138  .type = TIMER_GENERAL,
139  .n_handlers = NR_GEN_HANDLERS,
140  .bus = 0,
141  .id = 4,
142  .state = &timer_state[3],
143  .ch_dma = { // dma per channel: stream, channel
144  { DMA1_STREAM0, 2 },
145  { DMA1_STREAM3, 2 },
146  { DMA1_STREAM7, 2 },
147  { -1, -1 },
148  },
149 
150  },
151 
152  {
153  .regs = TIM5,
154  .clk = RCC_APB1Periph_TIM5,
155  .handlers = tim5_handlers,
156  .af = GPIO_AF_TIM5,
157  .type = TIMER_GENERAL,
158  .n_handlers = NR_GEN_HANDLERS,
159  .bus = 0,
160  .id = 5,
161  .state = &timer_state[4],
162  .ch_dma = { // dma per channel: stream, channel
163  { DMA1_STREAM2, 6 },
164  { DMA1_STREAM4, 6 },
165  { DMA1_STREAM0, 6 },
166  { DMA1_STREAM1, 6 },
167  },
168  },
169 
170  {
171  .regs = TIM6,
172  .clk = RCC_APB1Periph_TIM6,
173  .handlers = tim6_handlers,
174  .af = 0,
175  .type = TIMER_BASIC,
176  .n_handlers = NR_BAS_HANDLERS,
177  .bus = 0,
178  .id = 6,
179  .state = &timer_state[5],
180  },
181 
182  {
183  .regs = TIM7,
184  .clk = RCC_APB1Periph_TIM7,
185  .handlers = tim7_handlers,
186  .af = 0,
187  .type = TIMER_BASIC,
188  .n_handlers = NR_BAS_HANDLERS,
189  .bus = 0,
190  .id = 7,
191  .state = &timer_state[6],
192  },
193 
194  {
195  .regs = TIM8,
196  .clk = RCC_APB2Periph_TIM8,
197  .handlers = tim8_handlers,
198  .af = GPIO_AF_TIM8,
199  .type = TIMER_ADVANCED,
200  .n_handlers = NR_ADV_HANDLERS,
201  .bus = 1,
202  .id = 8,
203  .state = &timer_state[7],
204  .ch_dma = { // dma per channel: stream, channel
205  { DMA2_STREAM2, 7 },
206  { DMA2_STREAM3, 7 },
207  { DMA2_STREAM4, 7 },
208  { DMA2_STREAM7, 7 },
209  },
210  },
211 
212 // another timers don't has DMA
213 
214  {
215  .regs = TIM9,
216  .clk = RCC_APB2Periph_TIM9,
217  .handlers = tim9_handlers,
218  .af = GPIO_AF_TIM9,
219  .type = TIMER_GENERAL,
220  .n_handlers = NR_GEN_HANDLERS,
221  .bus = 1,
222  .id = 9,
223  .state = &timer_state[8],
224  },
225 
226  {
227  .regs = TIM10,
228  .clk = RCC_APB2Periph_TIM10,
229  .handlers = tim10_handlers,
230  .af = GPIO_AF_TIM10,
231  .type = TIMER_GENERAL,
232  .n_handlers = NR_GEN_HANDLERS,
233  .bus = 1,
234  .id = 10,
235  .state = &timer_state[9],
236  },
237 
238  {
239  .regs = TIM11,
240  .clk = RCC_APB2Periph_TIM11,
241  .handlers = tim11_handlers,
242  .af = GPIO_AF_TIM11,
243  .type = TIMER_GENERAL,
244  .n_handlers = NR_GEN_HANDLERS,
245  .bus = 1,
246  .id = 11,
247  .state = &timer_state[10],
248  },
249 
250  {
251  .regs = TIM12,
252  .clk = RCC_APB1Periph_TIM12,
253  .handlers = tim12_handlers,
254  .af = GPIO_AF_TIM12,
255  .type = TIMER_GENERAL,
256  .n_handlers = NR_GEN_HANDLERS,
257  .bus = 0,
258  .id = 12,
259  .state = &timer_state[11],
260  },
261 
262  {
263  .regs = TIM13,
264  .clk = RCC_APB1Periph_TIM13,
265  .handlers = tim13_handlers,
266  .af = GPIO_AF_TIM13,
267  .type = TIMER_GENERAL,
268  .n_handlers = NR_GEN_HANDLERS,
269  .bus = 0,
270  .id = 13,
271  .state = &timer_state[12],
272  },
273 
274  {
275  .regs = TIM14,
276  .clk = RCC_APB1Periph_TIM14,
277  .handlers = tim14_handlers,
278  .af = GPIO_AF_TIM14,
279  .type = TIMER_GENERAL,
280  .n_handlers = NR_GEN_HANDLERS,
281  .bus = 0,
282  .id = 14,
283  .state = &timer_state[13],
284  }
285 };
286 
287 
288 /*
289  * Convenience routines
290  */
291 
292 static void disable_channel(const timer_dev *dev, uint8_t channel);
293 static void pwm_mode(const timer_dev *dev, uint8_t channel);
294 static void output_compare_mode(const timer_dev *dev, uint8_t channel);
295 
296 static inline void enable_irq(const timer_dev *dev, uint8_t interrupt, uint8_t priority);
297 
298 
303 void timer_init(const timer_dev *dev) {
304 
305  if(dev->bus)
306  RCC_APB2PeriphClockCmd(dev->clk, ENABLE);
307  else
308  RCC_APB1PeriphClockCmd(dev->clk, ENABLE);
309 
310 }
311 
316 void timer_reset(const timer_dev *dev) {
317  memset(dev->handlers, 0, dev->n_handlers * sizeof(Handler));
318  memset(dev->state, 0, sizeof(*dev->state));
319 
320  if(dev->bus) {
321  RCC_APB2PeriphClockCmd(dev->clk, ENABLE);
322  RCC_APB2PeriphResetCmd(dev->clk, ENABLE);
323  RCC_APB2PeriphResetCmd(dev->clk, DISABLE);
324  } else {
325  RCC_APB1PeriphClockCmd(dev->clk, ENABLE);
326  RCC_APB1PeriphResetCmd(dev->clk, ENABLE);
327  RCC_APB1PeriphResetCmd(dev->clk, DISABLE);
328  }
329 
330 }
331 
340 void timer_disable(const timer_dev *dev) {
341  dev->regs->CR1 = 0;
342  dev->regs->DIER = 0;
343 
344  switch (dev->type) {
345  case TIMER_ADVANCED:
346  case TIMER_GENERAL:
347  (dev->regs)->CCER = 0;
348  break;
349  case TIMER_BASIC:
350  break;
351  }
352 }
353 
354 
355 // initial configuration - set required frequency (in kHz) and period (in ticks)
356 // returns real timers freq
357 uint32_t configTimeBase(const timer_dev *dev, uint16_t period, uint16_t khz)
358 {
359  TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
360  TIM_TypeDef *tim = dev->regs;
361 
362  timer_init(dev); // turn it on
363 
364  timer_pause(dev);
365 
366  dev->regs->CR1 = TIMER_CR1_ARPE;
367  dev->regs->PSC = 1;
368  dev->regs->SR = 0;
369  dev->regs->DIER = 0;
370  dev->regs->EGR = TIMER_EGR_UG;
371 
372  TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
373 
374  TIM_TimeBaseStructure.TIM_Period = (period - 1) & get_timer_mask(dev); // AKA TIMx_ARR
375  uint32_t freq = (uint32_t)khz * 1000;
376  uint16_t prescaler;
377  uint32_t tf; // timer's frequency
378 
379  if (tim == TIM1 || tim == TIM8 || tim == TIM9 || tim == TIM10 || tim == TIM11) { // 168MHz
380  tf = SystemCoreClock;
381  } else { // 84 MHz
382  tf = SystemCoreClock / 2;
383  }
384 
385  prescaler = ((tf + freq/4) / freq) - 1; // ==41 for 2MHz
386 
387  TIM_TimeBaseStructure.TIM_Prescaler = prescaler;
388  freq = tf / prescaler; // real timer's frequency
389 
390  dev->state->freq = freq; // store
391 
392  TIM_TimeBaseStructure.TIM_ClockDivision = 0;
393  TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
394  TIM_TimeBaseInit(tim, &TIM_TimeBaseStructure);
395 
396  switch (dev->type) {
397  case TIMER_ADVANCED:
398  dev->regs->BDTR = TIMER_BDTR_MOE | TIMER_BDTR_LOCK_OFF; // break and dead-time register, enable output
399  // fall-through
400  case TIMER_GENERAL:
401  case TIMER_BASIC:
402  break;
403  }
404 
405  timer_set_count(dev,0);
406 
407  dev->state->freq_scale = (float)freq / (khz * 1000); // remember ratio for correction
408 
409  return freq;
410 }
411 
412 
413 static void disable_channel(const timer_dev *dev, timer_Channel channel) {
414  timer_detach_interrupt(dev, channel);
415  timer_cc_disable(dev, channel);
416 }
417 
418 static void pwm_mode(const timer_dev *dev, timer_Channel channel) {
419  timer_disable_irq(dev, channel);
421  timer_cc_enable(dev, channel);
422 }
423 
424 static void output_compare_mode(const timer_dev *dev, timer_Channel channel) {
426  timer_cc_enable(dev, channel);
427 }
428 
429 
430 
442 void timer_set_mode(const timer_dev *dev, timer_Channel channel, timer_mode mode) {
443  assert_param(channel > 0 && channel <= 4);
444 
445  /* TODO decide about the basic timers */
446  assert_param(dev->type != TIMER_BASIC);
447  if (!dev || dev->type == TIMER_BASIC)
448  return;
449 
450  switch (mode) {
451  case TIMER_DISABLED:
452  disable_channel(dev, channel);
453  break;
454  case TIMER_PWM:
455  pwm_mode(dev, channel);
456  break;
458  output_compare_mode(dev, channel);
459  break;
460  }
461 }
462 
463 
468 void timer_foreach(void (*fn)(const timer_dev*)) {
469  uint8_t i;
470  for(i=0; i<(sizeof(timers)/sizeof(timer_dev)); i++){
471  fn(&timers[i]);
472  }
473 }
474 
485 void timer_attach_interrupt(const timer_dev *dev, timer_interrupt_id interrupt, Handler handler, uint8_t priority) {
486  if(interrupt>=dev->n_handlers) return;
487 
488  dev->handlers[interrupt] = handler;
489  timer_enable_irq(dev, interrupt);
490  enable_irq(dev, interrupt, priority);
491 }
492 
493 // attach all timer's interrupts to one handler - for PWM/PPM input
494 void timer_attach_all_interrupts(const timer_dev *dev, Handler handler) {
495  uint16_t i;
496  for(i=0; i < dev->n_handlers; i++) {
497  dev->handlers[i] = handler;
498  }
499  // enabling by caller
500 }
501 
502 
513  timer_disable_irq(dev, interrupt);
514  if(interrupt>=dev->n_handlers) return;
515  dev->handlers[interrupt] = 0;
516 }
517 
518 /*
519  * IRQ handlers
520  */
521 
522 static inline void dispatch_adv_brk(const timer_dev *dev);
523 static inline void dispatch_adv_up(const timer_dev *dev);
524 static inline void dispatch_adv_trg_com(const timer_dev *dev);
525 static inline void dispatch_adv_cc(const timer_dev *dev);
526 static inline void dispatch_general(const timer_dev *dev);
527 static inline void dispatch_general_h(const timer_dev *dev);
528 static inline void dispatch_basic(const timer_dev *dev);
529 
530 void TIM1_BRK_TIM9_IRQHandler(void);
531 void TIM1_UP_TIM10_IRQHandler(void);
533 void TIM1_CC_IRQHandler(void);
534 void TIM2_IRQHandler(void);
535 void TIM3_IRQHandler(void);
536 void TIM4_IRQHandler(void);
537 void TIM5_IRQHandler(void);
538 void TIM6_DAC_IRQHandler(void);
539 void TIM7_IRQHandler(void);
540 void TIM8_BRK_TIM12_IRQHandler(void);
541 void TIM8_CC_IRQHandler(void);
542 void TIM8_UP_TIM13_IRQHandler(void);
544 
545 
546 
547 
548 
550 {
553 
554 }
555 
559 }
560 
564 
565 }
566 
567 void TIM1_CC_IRQHandler(void) {
569 }
570 
571 void TIM2_IRQHandler(void) {
573 }
574 
575 void TIM3_IRQHandler(void) {
577 }
578 
579 void TIM4_IRQHandler(void) {
581 }
582 
583 void TIM5_IRQHandler(void) {
585 }
586 
589 }
590 
591 void TIM7_IRQHandler(void) {
593 }
594 
595 // used in PWM
596 void TIM8_BRK_TIM12_IRQHandler(void) { // used in PWM tim12
599 }
600 
601 void TIM8_CC_IRQHandler(void) { // used in PWM tim8
603 }
604 
605 
606 void TIM8_UP_TIM13_IRQHandler(void) { // not conflicts with PWM
609 
610 }
611 
615 
616 }
617 
618 
619 /* Note: the following dispatch routines make use of the fact that
620  * DIER interrupt enable bits and SR interrupt flags have common bit
621  * positions. Thus, ANDing DIER and SR lets us check if an interrupt
622  * is enabled and if it has occurred simultaneously.
623  */
624 
625 static INLINE void dispatch_single_irq(const timer_dev *dev,
626  timer_interrupt_id iid,
627  uint32_t irq_mask) {
628 
629  uint32_t dsr = dev->regs->DIER & dev->regs->SR & irq_mask;
630  if (dsr) {
631 
632  Handler handler = (dev->handlers)[iid];
633  if (handler) {
634  revo_call_handler(handler, (uint32_t)dev->regs);
635  }
636 
637  dev->regs->SR &= ~dsr; // reset IRQ inspite of installed handler! @NG
638 
639  }
640 }
641 
642 /* For dispatch routines which service multiple interrupts. */
643 static INLINE void handle_irq(const timer_dev *dev, uint32_t dier_sr, uint32_t irq_mask, uint32_t iid) {
644  if (dier_sr & irq_mask) {
645  Handler handler = (dev->handlers)[iid];
646  if (handler) {
647  revo_call_handler(handler, (uint32_t)dev->regs);
648  }
649  }
650 }
651 
652 static inline void dispatch_adv_brk(const timer_dev *dev) {
653 #ifdef ISR_PERF
654  uint32_t t=stopwatch_getticks();
655 #endif
657 #ifdef ISR_PERF
658  t = stopwatch_getticks() - t;
659  isr_time += t;
660  if(t>max_isr_time) max_isr_time=t;
661 #endif
662 }
663 
664 static inline void dispatch_adv_up(const timer_dev *dev) {
665 #ifdef ISR_PERF
666  uint32_t t=stopwatch_getticks();
667 #endif
669 #ifdef ISR_PERF
670  t = stopwatch_getticks() - t;
671  isr_time += t;
672  if(t>max_isr_time) max_isr_time=t;
673 #endif
674 }
675 
676 static inline void dispatch_adv_trg_com(const timer_dev *dev) {
677 #ifdef ISR_PERF
678  uint32_t t=stopwatch_getticks();
679 #endif
680 
681  uint32_t dsr = dev->regs->DIER & dev->regs->SR;
682  /* Logical OR of SR interrupt flags we end up
683  * handling. We clear these. User handlers
684  * must clear overcapture flags, to avoid
685  * wasting time in output mode. */
686 
689 
690  dev->regs->SR &= ~dsr; // handled ALL enabled interrupts! AFTER ISR itself!
691 
692 #ifdef ISR_PERF
693  t = stopwatch_getticks() - t;
694  isr_time += t;
695  if(t>max_isr_time) max_isr_time=t;
696 #endif
697 }
698 
699 static inline void dispatch_adv_cc(const timer_dev *dev) {
700 #ifdef ISR_PERF
701  uint32_t t=stopwatch_getticks();
702 #endif
703 
704  uint32_t dsr = dev->regs->DIER & dev->regs->SR;
705 
710 
711  dev->regs->SR &= ~dsr; // handled ALL enabled interrupts! AFTER ISR itself!
712 
713 #ifdef ISR_PERF
714  t = stopwatch_getticks() - t;
715  isr_time += t;
716  if(t>max_isr_time) max_isr_time=t;
717 #endif
718 }
719 
720 static inline void dispatch_general(const timer_dev *dev) {
721 #ifdef ISR_PERF
722  uint32_t t=stopwatch_getticks();
723 #endif
724 
725  uint32_t dsr = dev->regs->DIER & dev->regs->SR;
726 
727 
734 
735  dev->regs->SR &= ~dsr; // handled ALL enabled interrupts! AFTER ISR itself!
736 
737 #ifdef ISR_PERF
738  t = stopwatch_getticks() - t;
739  isr_time += t;
740  if(t>max_isr_time) max_isr_time=t;
741 #endif
742 
743 }
744 
745 static inline void dispatch_general_h(const timer_dev *dev) {
746 #ifdef ISR_PERF
747  uint32_t t=stopwatch_getticks();
748 #endif
749 
750  uint32_t dsr = dev->regs->DIER & dev->regs->SR;
751 
756 
757  dev->regs->SR &= ~dsr; // handled ALL enabled interrupts! AFTER ISR itself!
758 
759 #ifdef ISR_PERF
760  t = stopwatch_getticks() - t;
761  isr_time += t;
762  if(t>max_isr_time) max_isr_time=t;
763 #endif
764 
765 }
766 
767 
768 // don't count time of basic timer because it used only as timer scheduler's interrupt
769 static inline void dispatch_basic(const timer_dev *dev) {
771 }
772 
773 /*
774  * Utilities
775  */
776 
777 static void enable_advanced_irq(const timer_dev *dev, timer_interrupt_id id, uint8_t priority);
778 
779 #define PRIO_DISABLE_FLAG 0x80
780 
781 static inline void enable_irq(const timer_dev *dev, timer_interrupt_id iid, uint8_t priority) {
782 
783  IRQn_Type irq;
784 
785  switch(dev->id){
786  case 1: /* 1 - advanced */ enable_advanced_irq(dev, iid, priority); return;
787  case 2: irq=TIM2_IRQn; break;
788  case 3: irq=TIM3_IRQn; break;
789  case 4: irq=TIM4_IRQn; break;
790  case 5: irq=TIM5_IRQn; break;
791  case 6: irq=TIM6_DAC_IRQn; break;
792  case 7: irq=TIM7_IRQn; break;
793  case 8: /* 8 - advanced */ enable_advanced_irq(dev, iid, priority); return;
794  case 9: irq=TIM1_BRK_TIM9_IRQn; break;
795  case 10: irq=TIM1_UP_TIM10_IRQn; break;
796  case 11: irq=TIM1_TRG_COM_TIM11_IRQn; break;
797  case 12: irq=TIM8_BRK_TIM12_IRQn; break;
798  case 13: irq=TIM8_UP_TIM13_IRQn; break;
799  case 14: irq=TIM8_TRG_COM_TIM14_IRQn; break;
800 
801  default: return;
802  }
803 
804  if(priority & PRIO_DISABLE_FLAG){
805  NVIC_DisableIRQ(irq);
806  }else {
807  enable_nvic_irq(irq, priority);
808  }
809 
810 }
811 
812 static void enable_advanced_irq(const timer_dev *dev, timer_interrupt_id id, uint8_t priority) {
813  uint8_t is_timer1 = (dev->id == 1);
814 
815  IRQn_Type irq=0;
816 
817  switch (id) {
819  irq = is_timer1 ? TIM1_UP_TIM10_IRQn : TIM8_UP_TIM13_IRQn;
820  break;
821  case TIMER_CC1_INTERRUPT:
822  case TIMER_CC2_INTERRUPT:
823  case TIMER_CC3_INTERRUPT:
824  case TIMER_CC4_INTERRUPT:
825  irq = is_timer1 ? TIM1_CC_IRQn : TIM8_CC_IRQn;
826  break;
827  case TIMER_COM_INTERRUPT:
828  case TIMER_TRG_INTERRUPT:
829  irq = is_timer1 ? TIM1_TRG_COM_TIM11_IRQn : TIM8_TRG_COM_TIM14_IRQn;
830  break;
832  irq = is_timer1 ? TIM1_BRK_TIM9_IRQn : TIM8_BRK_TIM12_IRQn;
833  break;
834  }
835  if(!irq) return;
836  if(priority & PRIO_DISABLE_FLAG){
837  NVIC_DisableIRQ(irq);
838  }else {
839  NVIC_EnableIRQ(irq);
840  NVIC_SetPriority(irq,priority);
841  }
842 }
843 
844 
845 void timer_enable_NVICirq(const timer_dev *dev, uint8_t interrupt, uint8_t priority) {
846  enable_irq(dev,interrupt, priority);
847 }
848 
849 
850 void timer_disable_NVICirq(const timer_dev *dev, uint8_t interrupt){
851  enable_irq(dev,interrupt, PRIO_DISABLE_FLAG);
852 }
#define TIMER5
Definition: timer.h:613
static uint32_t stopwatch_getticks()
Definition: stopwatch.h:33
uint32_t clk
Definition: timer.h:576
static void enable_irq(const timer_dev *dev, uint8_t interrupt, uint8_t priority)
static void timer_cc_enable(const timer_dev *dev, timer_Channel channel)
Enable a timer channel&#39;s capture/compare signal.
Definition: timer.h:858
static void timer_cc_disable(const timer_dev *dev, timer_Channel channel)
Disable a timer channel&#39;s output compare or input capture signal.
Definition: timer.h:891
uint32_t SystemCoreClock
void timer_set_mode(const timer_dev *dev, timer_Channel channel, timer_mode mode)
Definition: timer.c:442
void TIM4_IRQHandler(void)
Definition: timer.c:579
#define TIMER_EGR_UG
Definition: timer.h:241
const timer_dev timers[]
Definition: timer.c:75
static void pwm_mode(const timer_dev *dev, uint8_t channel)
static void dispatch_adv_cc(const timer_dev *dev)
Definition: timer.c:699
#define TIMER8
Definition: timer.h:616
void timer_reset(const timer_dev *dev)
Definition: timer.c:316
void TIM3_IRQHandler(void)
Definition: timer.c:575
#define TIMER2
Definition: timer.h:610
#define assert_param(expr)
void TIM8_CC_IRQHandler(void)
Definition: timer.c:601
Handler * handlers
Definition: timer.h:577
static INLINE uint32_t get_timer_mask(const timer_dev *dev)
Definition: timer.h:651
uint8_t n_handlers
Definition: timer.h:583
void timer_enable_NVICirq(const timer_dev *dev, uint8_t interrupt, uint8_t priority)
Definition: timer.c:845
static INLINE void timer_pause(const timer_dev *dev)
Stop a timer&#39;s counter from changing.
Definition: timer.h:679
#define TIMER_SR_BIF
Definition: timer.h:218
static void output_compare_mode(const timer_dev *dev, uint8_t channel)
timer interface.
void TIM1_TRG_COM_TIM11_IRQHandler(void)
Definition: timer.c:561
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
uint32_t freq
Definition: timer.h:563
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
#define TIMER_BDTR_MOE
Definition: timer.h:356
#define TIMER_BDTR_LOCK_OFF
Definition: timer.h:363
void TIM5_IRQHandler(void)
Definition: timer.c:583
#define NR_BAS_HANDLERS
Definition: timer.c:55
#define TIMER4
Definition: timer.h:612
#define TIMER_SR_TIF
Definition: timer.h:219
uint8_t bus
Definition: timer.h:584
#define TIMER3
Definition: timer.h:611
timer_Channel
Definition: timer.h:441
static INLINE void dispatch_single_irq(const timer_dev *dev, timer_interrupt_id iid, uint32_t irq_mask)
Definition: timer.c:625
#define NR_ADV_HANDLERS
Definition: timer.c:51
#define TIMER13
Definition: timer.h:621
timer_interrupt_id
Timer interrupt number.
Definition: timer.h:479
#define TIMER1
Definition: timer.h:609
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
void TIM2_IRQHandler(void)
Definition: timer.c:571
void timer_detach_interrupt(const timer_dev *dev, timer_interrupt_id interrupt)
Detach a timer interrupt.
Definition: timer.c:512
static void dispatch_adv_up(const timer_dev *dev)
Definition: timer.c:664
static Handler tim1_handlers [NR_ADV_HANDLERS] IN_CCM
Definition: timer.c:58
void TIM1_BRK_TIM9_IRQHandler(void)
Definition: timer.c:549
#define TIMER_SR_UIF
Definition: timer.h:225
#define TIMER_SR_CC3IF
Definition: timer.h:222
#define NR_GEN_HANDLERS
Definition: timer.c:53
void enable_nvic_irq(uint8_t irq, uint8_t prio)
Definition: nvic.c:8
#define TIMER_SR_CC4IF
Definition: timer.h:221
#define PRIO_DISABLE_FLAG
Definition: timer.c:779
static void dispatch_adv_trg_com(const timer_dev *dev)
Definition: timer.c:676
void TIM6_DAC_IRQHandler(void)
Definition: timer.c:587
#define TIMER12
Definition: timer.h:620
#define INLINE
Definition: hal_types.h:79
void timer_attach_all_interrupts(const timer_dev *dev, Handler handler)
Definition: timer.c:494
static void dispatch_basic(const timer_dev *dev)
Definition: timer.c:769
static void timer_oc_set_mode(const timer_dev *dev, timer_Channel _channel, timer_oc_mode mode, uint8_t flags)
Configure a channel&#39;s output compare mode.
Definition: timer.h:1065
void TIM8_BRK_TIM12_IRQHandler(void)
Definition: timer.c:596
#define TIMER6
Definition: timer.h:614
static void dispatch_general_h(const timer_dev *dev)
Definition: timer.c:745
float freq_scale
Definition: timer.h:564
#define TIMER10
Definition: timer.h:618
void timer_init(const timer_dev *dev)
Definition: timer.c:303
#define TIMER9
Definition: timer.h:617
#define BOARD_PWM_MODE
Definition: timer.h:45
static void timer_enable_irq(const timer_dev *dev, timer_interrupt_id interrupt)
Enable a timer interrupt.
Definition: timer.h:1125
static void timer_disable_irq(const timer_dev *dev, timer_interrupt_id interrupt)
Disable a timer interrupt.
Definition: timer.h:1138
#define TIMER_CR1_ARPE
Definition: timer.h:90
void TIM1_UP_TIM10_IRQHandler(void)
Definition: timer.c:556
static void dispatch_adv_brk(const timer_dev *dev)
Definition: timer.c:652
void TIM7_IRQHandler(void)
Definition: timer.c:591
static void disable_channel(const timer_dev *dev, uint8_t channel)
#define TIMER_SR_CC2IF
Definition: timer.h:223
void TIM8_TRG_COM_TIM14_IRQHandler(void)
Definition: timer.c:612
#define TIMER11
Definition: timer.h:619
timerState * state
Definition: timer.h:578
TIM_TypeDef * regs
Definition: timer.h:575
uint8_t id
Definition: timer.h:585
#define TIMER_SR_COMIF
Definition: timer.h:220
uint32_t configTimeBase(const timer_dev *dev, uint16_t period, uint16_t khz)
Definition: timer.c:357
void TIM8_UP_TIM13_IRQHandler(void)
Definition: timer.c:606
#define TIMER7
Definition: timer.h:615
void timer_disable_NVICirq(const timer_dev *dev, uint8_t interrupt)
Definition: timer.c:850
uint64_t Handler
Definition: hal_types.h:19
static INLINE void handle_irq(const timer_dev *dev, uint32_t dier_sr, uint32_t irq_mask, uint32_t iid)
Definition: timer.c:643
static void dispatch_general(const timer_dev *dev)
Definition: timer.c:720
static void enable_advanced_irq(const timer_dev *dev, timer_interrupt_id id, uint8_t priority)
Definition: timer.c:812
void TIM1_CC_IRQHandler(void)
Definition: timer.c:567
timer_type type
Definition: timer.h:582
void revo_call_handler(Handler h, uint32_t arg)
Definition: Scheduler.cpp:1420
#define TIMER_SR_CC1IF
Definition: timer.h:224
#define TIMER14
Definition: timer.h:622
timer_mode
Definition: timer.h:421
void timer_foreach(void(*fn)(const timer_dev *))
Call a function on timer devices.
Definition: timer.c:468
void timer_disable(const timer_dev *dev)
Disable a timer.
Definition: timer.c:340