Refactor missing prototypes 2 (#14170)
[betaflight.git] / src / platform / AT32 / timer_at32bsp.c
blobf76a41715220249b4f96dd8f93991d788fe8c599
1 /*
2 * This file is part of Betaflight.
4 * Betaflight is free software. You can redistribute this software
5 * and/or modify this software under the terms of the GNU General
6 * Public License as published by the Free Software Foundation,
7 * either version 3 of the License, or (at your option) any later
8 * version.
10 * Betaflight is distributed in the hope that it will be useful,
11 * but WITHOUT ANY WARRANTY; without even the implied warranty of
12 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
14 * See the GNU General Public License for more details.
16 * You should have received a copy of the GNU General Public
17 * License along with this software.
19 * If not, see <http://www.gnu.org/licenses/>.
22 #include <stdbool.h>
23 #include <stdint.h>
24 #include <string.h>
25 #include <math.h>
27 #include "platform.h"
29 #ifdef USE_TIMER
31 #include "build/atomic.h"
33 #include "common/utils.h"
35 #include "drivers/nvic.h"
37 #include "drivers/io.h"
38 #include "drivers/rcc.h"
39 #include "drivers/system.h"
40 #include "drivers/timer.h"
41 #include "drivers/timer_impl.h"
43 #define TIM_N(n) (1 << (n))
46 Groups that allow running different period (ex 50Hz servos + 400Hz throttle + etc):
47 TIM1 2 channels
48 TIM2 4 channels
49 TIM3 4 channels
50 TIM4 4 channels
53 #define USED_TIMER_COUNT BITCOUNT(USED_TIMERS)
54 #define CC_CHANNELS_PER_TIMER 4
56 #define TIM_IT_CCx(ch) (TMR_C1_INT << ((ch)-1))
58 typedef struct timerConfig_s {
59 timerOvrHandlerRec_t *updateCallback;
61 // per-channel
62 timerCCHandlerRec_t *edgeCallback[CC_CHANNELS_PER_TIMER];
63 timerOvrHandlerRec_t *overflowCallback[CC_CHANNELS_PER_TIMER];
65 // state
66 timerOvrHandlerRec_t *overflowCallbackActive; // null-terminated linked list of active overflow callbacks
67 uint32_t forcedOverflowTimerValue;
68 } timerConfig_t;
70 timerConfig_t timerConfig[USED_TIMER_COUNT];
72 typedef struct {
73 channelType_t type;
74 } timerChannelInfo_t;
76 #ifdef TIMER_CHANNEL_COUNT
77 timerChannelInfo_t timerChannelInfo[TIMER_CHANNEL_COUNT];
78 #endif
80 typedef struct {
81 uint8_t priority;
82 } timerInfo_t;
83 timerInfo_t timerInfo[USED_TIMER_COUNT];
85 // return index of timer in timer table. Lowest timer has index 0
86 #define TIMER_INDEX(i) BITCOUNT((TIM_N(i) - 1) & USED_TIMERS)
88 static uint8_t lookupTimerIndex(const tmr_type *tim)
90 #define _CASE_SHF 10 // amount we can safely shift timer address to the right. gcc will throw error if some timers overlap
91 #define _CASE_(tim, index) case ((unsigned)tim >> _CASE_SHF): return index; break
92 #define _CASE(i) _CASE_(TMR##i##_BASE, TIMER_INDEX(i))
94 // let gcc do the work, switch should be quite optimized
95 switch ((unsigned)tim >> _CASE_SHF) {
96 #if USED_TIMERS & TIM_N(1)
97 _CASE(1);
98 #endif
99 #if USED_TIMERS & TIM_N(2)
100 _CASE(2);
101 #endif
102 #if USED_TIMERS & TIM_N(3)
103 _CASE(3);
104 #endif
105 #if USED_TIMERS & TIM_N(4)
106 _CASE(4);
107 #endif
108 #if USED_TIMERS & TIM_N(5)
109 _CASE(5);
110 #endif
111 #if USED_TIMERS & TIM_N(6)
112 _CASE(6);
113 #endif
114 #if USED_TIMERS & TIM_N(7)
115 _CASE(7);
116 #endif
117 #if USED_TIMERS & TIM_N(8)
118 _CASE(8);
119 #endif
120 #if USED_TIMERS & TIM_N(9)
121 _CASE(9);
122 #endif
123 #if USED_TIMERS & TIM_N(10)
124 _CASE(10);
125 #endif
126 #if USED_TIMERS & TIM_N(11)
127 _CASE(11);
128 #endif
129 #if USED_TIMERS & TIM_N(12)
130 _CASE(12);
131 #endif
132 #if USED_TIMERS & TIM_N(13)
133 _CASE(13);
134 #endif
135 #if USED_TIMERS & TIM_N(14)
136 _CASE(14);
137 #endif
138 #if USED_TIMERS & TIM_N(15)
139 _CASE(15);
140 #endif
141 #if USED_TIMERS & TIM_N(16)
142 _CASE(16);
143 #endif
144 #if USED_TIMERS & TIM_N(17)
145 _CASE(17);
146 #endif
147 #if USED_TIMERS & TIM_N(20)
148 _CASE(20);
149 #endif
150 default: return ~1; // make sure final index is out of range
152 #undef _CASE
153 #undef _CASE_
156 tmr_type * const usedTimers[USED_TIMER_COUNT] = {
157 #define _DEF(i) TMR##i
159 #if USED_TIMERS & TIM_N(1)
160 _DEF(1),
161 #endif
162 #if USED_TIMERS & TIM_N(2)
163 _DEF(2),
164 #endif
165 #if USED_TIMERS & TIM_N(3)
166 _DEF(3),
167 #endif
168 #if USED_TIMERS & TIM_N(4)
169 _DEF(4),
170 #endif
171 #if USED_TIMERS & TIM_N(5)
172 _DEF(5),
173 #endif
174 #if USED_TIMERS & TIM_N(6)
175 _DEF(6),
176 #endif
177 #if USED_TIMERS & TIM_N(7)
178 _DEF(7),
179 #endif
180 #if USED_TIMERS & TIM_N(8)
181 _DEF(8),
182 #endif
183 #if USED_TIMERS & TIM_N(9)
184 _DEF(9),
185 #endif
186 #if USED_TIMERS & TIM_N(10)
187 _DEF(10),
188 #endif
189 #if USED_TIMERS & TIM_N(11)
190 _DEF(11),
191 #endif
192 #if USED_TIMERS & TIM_N(12)
193 _DEF(12),
194 #endif
195 #if USED_TIMERS & TIM_N(13)
196 _DEF(13),
197 #endif
198 #if USED_TIMERS & TIM_N(14)
199 _DEF(14),
200 #endif
201 #if USED_TIMERS & TIM_N(15)
202 _DEF(15),
203 #endif
204 #if USED_TIMERS & TIM_N(16)
205 _DEF(16),
206 #endif
207 #if USED_TIMERS & TIM_N(17)
208 _DEF(17),
209 #endif
210 #if USED_TIMERS & TIM_N(20)
211 _DEF(20),
212 #endif
213 #undef _DEF
216 // Map timer index to timer number (Straight copy of usedTimers array)
217 const int8_t timerNumbers[USED_TIMER_COUNT] = {
218 #define _DEF(i) i
220 #if USED_TIMERS & TIM_N(1)
221 _DEF(1),
222 #endif
223 #if USED_TIMERS & TIM_N(2)
224 _DEF(2),
225 #endif
226 #if USED_TIMERS & TIM_N(3)
227 _DEF(3),
228 #endif
229 #if USED_TIMERS & TIM_N(4)
230 _DEF(4),
231 #endif
232 #if USED_TIMERS & TIM_N(5)
233 _DEF(5),
234 #endif
235 #if USED_TIMERS & TIM_N(6)
236 _DEF(6),
237 #endif
238 #if USED_TIMERS & TIM_N(7)
239 _DEF(7),
240 #endif
241 #if USED_TIMERS & TIM_N(8)
242 _DEF(8),
243 #endif
244 #if USED_TIMERS & TIM_N(9)
245 _DEF(9),
246 #endif
247 #if USED_TIMERS & TIM_N(10)
248 _DEF(10),
249 #endif
250 #if USED_TIMERS & TIM_N(11)
251 _DEF(11),
252 #endif
253 #if USED_TIMERS & TIM_N(12)
254 _DEF(12),
255 #endif
256 #if USED_TIMERS & TIM_N(13)
257 _DEF(13),
258 #endif
259 #if USED_TIMERS & TIM_N(14)
260 _DEF(14),
261 #endif
262 #if USED_TIMERS & TIM_N(15)
263 _DEF(15),
264 #endif
265 #if USED_TIMERS & TIM_N(16)
266 _DEF(16),
267 #endif
268 #if USED_TIMERS & TIM_N(17)
269 _DEF(17),
270 #endif
271 #if USED_TIMERS & TIM_N(20)
272 _DEF(20),
273 #endif
274 #undef _DEF
277 int8_t timerGetNumberByIndex(uint8_t index)
279 if (index < USED_TIMER_COUNT) {
280 return timerNumbers[index];
281 } else {
282 return 0;
286 int8_t timerGetTIMNumber(const tmr_type *tim)
288 const uint8_t index = lookupTimerIndex(tim);
290 return timerGetNumberByIndex(index);
293 static inline uint8_t lookupChannelIndex(const uint16_t channel)
295 // return channel >> 2;
296 return channel -1 ;//at32 use 1\2\3\4 as channel num
299 uint8_t timerLookupChannelIndex(const uint16_t channel)
301 return lookupChannelIndex(channel);
304 rccPeriphTag_t timerRCC(const tmr_type *tim)
306 for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
307 if (timerDefinitions[i].TIMx == tim) {
308 return timerDefinitions[i].rcc;
311 return 0;
314 uint8_t timerInputIrq(const tmr_type *tim)
316 for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
317 if (timerDefinitions[i].TIMx == tim) {
318 return timerDefinitions[i].inputIrq;
321 return 0;
324 static void timerNVICConfigure(uint8_t irq)
326 nvic_irq_enable(irq,NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER),NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER));
329 void configTimeBase(tmr_type *tim, uint16_t period, uint32_t hz)
331 //timer, period, perscaler
332 tmr_base_init(tim,(period - 1) & 0xFFFF,(timerClock(tim) / hz) - 1);
333 //TMR_CLOCK_DIV1 = 0X00 NO DIV
334 tmr_clock_source_div_set(tim,TMR_CLOCK_DIV1);
335 //COUNT UP
336 tmr_cnt_dir_set(tim,TMR_COUNT_UP);
340 // old interface for PWM inputs. It should be replaced
341 void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, uint32_t hz)
343 configTimeBase(timerHardwarePtr->tim, period, hz);
344 tmr_counter_enable(timerHardwarePtr->tim, TRUE);
346 uint8_t irq = timerInputIrq(timerHardwarePtr->tim);
347 timerNVICConfigure(irq);
348 switch (irq) {
349 #if defined(AT32F4)
350 case TMR1_CH_IRQn:
351 timerNVICConfigure(TMR1_OVF_TMR10_IRQn);
352 break;
353 #endif
357 // allocate and configure timer channel. Timer priority is set to highest priority of its channels
358 void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority, uint8_t irq)
360 #ifndef USE_TIMER_MGMT
362 UNUSED(timHw);
363 UNUSED(type);
364 UNUSED(irqPriority);
365 UNUSED(irq);
366 return;
368 #else
370 unsigned channel = timHw - TIMER_HARDWARE;
371 if (channel >= TIMER_CHANNEL_COUNT) {
372 return;
375 timerChannelInfo[channel].type = type;
376 unsigned timer = lookupTimerIndex(timHw->tim);
377 if (timer >= USED_TIMER_COUNT)
378 return;
379 if (irqPriority < timerInfo[timer].priority) {
380 // it would be better to set priority in the end, but current startup sequence is not ready
381 configTimeBase(usedTimers[timer], 0, 1);
382 tmr_counter_enable(usedTimers[timer], TRUE);
384 nvic_irq_enable(irq, NVIC_PRIORITY_BASE(irqPriority), NVIC_PRIORITY_SUB(irqPriority));
386 timerInfo[timer].priority = irqPriority;
388 #endif
391 void timerChCCHandlerInit(timerCCHandlerRec_t *self, timerCCHandlerCallback *fn)
393 self->fn = fn;
396 void timerChOvrHandlerInit(timerOvrHandlerRec_t *self, timerOvrHandlerCallback *fn)
398 self->fn = fn;
399 self->next = NULL;
402 // update overflow callback list
403 // some synchronization mechanism is neccesary to avoid disturbing other channels (BASEPRI used now)
404 static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, const tmr_type *tim) {
405 timerOvrHandlerRec_t **chain = &cfg->overflowCallbackActive;
406 ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
408 if (cfg->updateCallback) {
409 *chain = cfg->updateCallback;
410 chain = &cfg->updateCallback->next;
413 for (int i = 0; i < CC_CHANNELS_PER_TIMER; i++)
414 if (cfg->overflowCallback[i]) {
415 *chain = cfg->overflowCallback[i];
416 chain = &cfg->overflowCallback[i]->next;
418 *chain = NULL;
420 // enable or disable IRQ
421 tmr_interrupt_enable((tmr_type *)tim, TMR_OVF_INT, cfg->overflowCallbackActive ? TRUE : FALSE);
424 // config edge and overflow callback for channel. Try to avoid per-channel overflowCallback, it is a bit expensive
425 void timerChConfigCallbacks(const timerHardware_t *timHw, timerCCHandlerRec_t *edgeCallback, timerOvrHandlerRec_t *overflowCallback)
427 uint8_t timerIndex = lookupTimerIndex(timHw->tim);
428 if (timerIndex >= USED_TIMER_COUNT) {
429 return;
432 uint8_t channelIndex = lookupChannelIndex(timHw->channel);
433 if (edgeCallback == NULL) {
434 // disable irq before changing callback to NULL
435 tmr_interrupt_enable(timHw->tim, TIM_IT_CCx(timHw->channel), FALSE);
438 // setup callback info
439 timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallback;
440 timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback;
441 // enable channel IRQ
442 if (edgeCallback) {
443 tmr_interrupt_enable(timHw->tim, TIM_IT_CCx(timHw->channel), TRUE);
446 timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim);
449 void timerConfigUpdateCallback(const tmr_type *tim, timerOvrHandlerRec_t *updateCallback)
451 uint8_t timerIndex = lookupTimerIndex(tim);
452 if (timerIndex >= USED_TIMER_COUNT) {
453 return;
455 timerConfig[timerIndex].updateCallback = updateCallback;
456 timerChConfig_UpdateOverflow(&timerConfig[timerIndex], tim);
459 // enable or disable IRQ
460 void timerChITConfig(const timerHardware_t *timHw, FunctionalState newState)
462 tmr_interrupt_enable(timHw->tim, TIM_IT_CCx(timHw->channel), newState ? TRUE : FALSE);
465 // clear Compare/Capture flag for channel
466 void timerChClearCCFlag(const timerHardware_t *timHw)
468 tmr_flag_clear(timHw->tim, TIM_IT_CCx(timHw->channel));
471 // configure timer channel GPIO mode
472 void timerChConfigGPIO(const timerHardware_t* timHw, ioConfig_t mode)
474 IOInit(IOGetByTag(timHw->tag), OWNER_TIMER, 0);
475 IOConfigGPIO(IOGetByTag(timHw->tag), mode);
478 // calculate input filter constant
479 // TODO - we should probably setup DTS to higher value to allow reasonable input filtering
480 // - notice that prescaler[0] does use DTS for sampling - the sequence won't be monotonous anymore
481 static unsigned getFilter(unsigned ticks)
483 static const unsigned ftab[16] = {
484 1*1, // fDTS !
485 1*2, 1*4, 1*8, // fCK_INT
486 2*6, 2*8, // fDTS/2
487 4*6, 4*8,
488 8*6, 8*8,
489 16*5, 16*6, 16*8,
490 32*5, 32*6, 32*8
492 for (unsigned i = 1; i < ARRAYLEN(ftab); i++)
493 if (ftab[i] > ticks)
494 return i - 1;
495 return 0x0f;
498 // Configure input capture
499 void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks)
501 tmr_input_config_type tmr_icInitStructure;
502 tmr_icInitStructure.input_channel_select = TIM_CH_TO_SELCHANNEL(timHw->channel) ;// MAPS 1234 TO 0 2 4 6
503 tmr_icInitStructure.input_polarity_select = polarityRising ?TMR_INPUT_RISING_EDGE:TMR_INPUT_FALLING_EDGE;
504 tmr_icInitStructure.input_mapped_select = TMR_CC_CHANNEL_MAPPED_DIRECT;
505 tmr_icInitStructure.input_filter_value = getFilter(inputFilterTicks);
507 tmr_input_channel_init(timHw->tim,&tmr_icInitStructure,TMR_CHANNEL_INPUT_DIV_1);
510 volatile timCCR_t* timerChCCR(const timerHardware_t *timHw)
513 if(timHw->channel == 1)
514 return (volatile timCCR_t*)(&timHw->tim->c1dt);
515 else if(timHw->channel == 2)
516 return (volatile timCCR_t*)(&timHw->tim->c2dt);
517 else if(timHw->channel == 3)
518 return (volatile timCCR_t*)(&timHw->tim->c3dt);
519 else if(timHw->channel == 4)
520 return (volatile timCCR_t*)(&timHw->tim->c4dt);
521 else
522 return (volatile timCCR_t*)((volatile char*)&timHw->tim->c1dt + (timHw->channel-1)*0x04); //for 32bit need to debug
526 static void timCCxHandler(tmr_type *tim, timerConfig_t *timerConfig)
528 uint16_t capture;
529 unsigned tim_status;
530 tim_status = tim->ists & tim->iden;
531 #if 1
532 while (tim_status) {
533 // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
534 // current order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
535 unsigned bit = __builtin_clz(tim_status);
536 unsigned mask = ~(0x80000000 >> bit);
537 tim->ists = mask;
538 tim_status &= mask;
539 switch (bit) {
540 case __builtin_clz(TMR_OVF_FLAG): {
542 if (timerConfig->forcedOverflowTimerValue != 0) {
543 capture = timerConfig->forcedOverflowTimerValue - 1;
544 timerConfig->forcedOverflowTimerValue = 0;
545 } else {
546 capture = tim->pr;
549 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
550 while (cb) {
551 cb->fn(cb, capture);
552 cb = cb->next;
554 break;
556 case __builtin_clz(TMR_C1_FLAG):
557 timerConfig->edgeCallback[0]->fn(timerConfig->edgeCallback[0], tim->c1dt);
558 break;
559 case __builtin_clz(TMR_C2_FLAG):
560 timerConfig->edgeCallback[1]->fn(timerConfig->edgeCallback[1], tim->c2dt);
561 break;
562 case __builtin_clz(TMR_C3_FLAG):
563 timerConfig->edgeCallback[2]->fn(timerConfig->edgeCallback[2], tim->c3dt);
564 break;
565 case __builtin_clz(TMR_C4_FLAG):
566 timerConfig->edgeCallback[3]->fn(timerConfig->edgeCallback[3], tim->c4dt);
567 break;
570 #endif
573 static inline void timUpdateHandler(tmr_type *tim, timerConfig_t *timerConfig)
575 uint16_t capture;
576 unsigned tim_status;
577 tim_status = tim->ists & tim->iden;
578 while (tim_status) {
579 // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
580 // currrent order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
581 unsigned bit = __builtin_clz(tim_status);
582 unsigned mask = ~(0x80000000 >> bit);
583 tim->ists = mask;
584 tim_status &= mask;
585 switch (bit) {
586 case __builtin_clz(TMR_OVF_FLAG): { // tim_it_update= 0x0001 => TMR_OVF_FLAG
588 if (timerConfig->forcedOverflowTimerValue != 0) {
589 capture = timerConfig->forcedOverflowTimerValue - 1;
590 timerConfig->forcedOverflowTimerValue = 0;
591 } else {
592 capture = tim->pr;
595 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
596 while (cb) {
597 cb->fn(cb, capture);
598 cb = cb->next;
600 break;
606 // handler for shared interrupts when both timers need to check status bits
607 #define _TIM_IRQ_HANDLER2(name, i, j) \
608 void name(void) \
610 timCCxHandler(TMR ## i, &timerConfig[TIMER_INDEX(i)]); \
611 timCCxHandler(TMR ## j, &timerConfig[TIMER_INDEX(j)]); \
612 } struct dummy
614 #define _TIM_IRQ_HANDLER(name, i) \
615 void name(void) \
617 timCCxHandler(TMR ## i, &timerConfig[TIMER_INDEX(i)]); \
618 } struct dummy
620 #define _TIM_IRQ_HANDLER_UPDATE_ONLY(name, i) \
621 void name(void) \
623 timUpdateHandler(TMR ## i, &timerConfig[TIMER_INDEX(i)]); \
624 } struct dummy
626 #if USED_TIMERS & TIM_N(1)
627 _TIM_IRQ_HANDLER(TMR1_CH_IRQHandler, 1);
628 #endif
629 #if USED_TIMERS & TIM_N(2)
630 _TIM_IRQ_HANDLER(TMR2_GLOBAL_IRQHandler, 2);
631 #endif
632 #if USED_TIMERS & TIM_N(3)
633 _TIM_IRQ_HANDLER(TMR3_GLOBAL_IRQHandler, 3);
634 #endif
635 #if USED_TIMERS & TIM_N(4)
636 _TIM_IRQ_HANDLER(TMR4_GLOBAL_IRQHandler, 4);
637 #endif
638 #if USED_TIMERS & TIM_N(5)
639 _TIM_IRQ_HANDLER(TMR5_GLOBAL_IRQHandler, 5);
640 #endif
641 #if USED_TIMERS & TIM_N(6)
642 _TIM_IRQ_HANDLER(TMR6_DAC_GLOBAL_IRQHandler, 6);
643 #endif
645 #if USED_TIMERS & TIM_N(7)
646 _TIM_IRQ_HANDLER(TMR7_GLOBAL_IRQHandler, 7);
647 #endif
649 #if USED_TIMERS & TIM_N(8)
650 _TIM_IRQ_HANDLER(TMR8_CH_IRQHandler, 8);
651 #endif
652 #if USED_TIMERS & TIM_N(9)
653 _TIM_IRQ_HANDLER(TMR1_BRK_TMR9_IRQHandler, 9);
654 #endif
655 //TODO: there may be a bug
656 #if USED_TIMERS & TIM_N(10)
657 _TIM_IRQ_HANDLER2(TMR1_OVF_TMR10_IRQHandler, 1,10);
658 #endif
659 # if USED_TIMERS & TIM_N(11)
660 _TIM_IRQ_HANDLER(TMR1_TRG_HALL_TMR11_IRQHandler, 11);
661 # endif
662 #if USED_TIMERS & TIM_N(12)
663 _TIM_IRQ_HANDLER(TMR8_BRK_TMR12_IRQHandler, 12);
664 #endif
665 #if USED_TIMERS & TIM_N(13)
666 _TIM_IRQ_HANDLER(TMR8_OVF_TMR13_IRQHandler, 13);
667 #endif
668 #if USED_TIMERS & TIM_N(14)
669 _TIM_IRQ_HANDLER(TMR8_TRG_HALL_TMR14_IRQHandler, 14);
670 #endif
671 #if USED_TIMERS & TIM_N(20)
672 _TIM_IRQ_HANDLER(TMR20_CH_IRQHandler, 20);
673 #endif
675 void timerInit(void)
677 memset(timerConfig, 0, sizeof(timerConfig));
679 #ifdef USE_TIMER_MGMT
680 /* enable the timer peripherals */
681 for (unsigned i = 0; i < TIMER_CHANNEL_COUNT; i++) {
682 RCC_ClockCmd(timerRCC(TIMER_HARDWARE[i].tim), ENABLE);
685 // initialize timer channel structures
686 for (unsigned i = 0; i < TIMER_CHANNEL_COUNT; i++) {
687 timerChannelInfo[i].type = TYPE_FREE;
689 #endif
691 for (unsigned i = 0; i < USED_TIMER_COUNT; i++) {
692 timerInfo[i].priority = ~0;
696 void timerStart(tmr_type *tim)
698 tmr_counter_enable(tim, TRUE);
702 * Force an overflow for a given timer.
703 * Saves the current value of the counter in the relevant timerConfig's forcedOverflowTimerValue variable.
704 * @param tmr_type *tim The timer to overflow
705 * @return void
707 void timerForceOverflow(tmr_type *tim)
709 uint8_t timerIndex = lookupTimerIndex((const tmr_type *)tim);
711 ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
712 // Save the current count so that PPM reading will work on the same timer that was forced to overflow
713 timerConfig[timerIndex].forcedOverflowTimerValue = tim->cval + 1;
715 // Force an overflow by setting the UG bit
716 tim->swevt_bit.ovfswtr = 1;
720 void timerOCInit(tmr_type *tim, uint8_t channel, tmr_output_config_type *init)
722 tmr_output_channel_config(tim, TIM_CH_TO_SELCHANNEL(channel), init);
725 void timerOCPreloadConfig(tmr_type *tim, uint8_t channel, uint16_t preload)
727 tmr_output_channel_buffer_enable(tim, TIM_CH_TO_SELCHANNEL(channel), preload);
730 //tmr_channel_value_get
731 volatile timCCR_t* timerCCR(tmr_type *tim, uint8_t channel)
734 if(channel ==1)
735 return (volatile timCCR_t*)(&tim->c1dt);
736 else if(channel ==2)
737 return (volatile timCCR_t*)(&tim->c2dt);
738 else if(channel ==3)
739 return (volatile timCCR_t*)(&tim->c3dt);
740 else if(channel ==4)
741 return (volatile timCCR_t*)(&tim->c4dt);
742 else
743 return (volatile timCCR_t*)((volatile char*)&tim->c1dt + (channel-1)*0x04); //for 32bit need to debug
747 uint16_t timerDmaSource(uint8_t channel)
749 switch (channel) {
750 case 1:
751 return TMR_C1_DMA_REQUEST;
752 case 2:
753 return TMR_C2_DMA_REQUEST;
754 case 3:
755 return TMR_C3_DMA_REQUEST;
756 case 4:
757 return TMR_C4_DMA_REQUEST;
759 return 0;
762 uint16_t timerGetPrescalerByDesiredMhz(tmr_type *tim, uint16_t mhz)
764 return timerGetPrescalerByDesiredHertz(tim, MHZ_TO_HZ(mhz));
767 uint16_t timerGetPeriodByPrescaler(tmr_type *tim, uint16_t prescaler, uint32_t hz)
769 return (uint16_t)((timerClock(tim) / (prescaler + 1)) / hz);
772 uint16_t timerGetPrescalerByDesiredHertz(tmr_type *tim, uint32_t hz)
774 // protection here for desired hertz > SystemCoreClock???
775 if (hz > timerClock(tim)) {
776 return 0;
778 return (uint16_t)((timerClock(tim) + hz / 2 ) / hz) - 1;
780 #endif