Renamed pin on timerHardware_t to tag for clarity
[betaflight.git] / src / main / drivers / timer.c
blob673265f545a94e3b5b249b69d99ba4946785d6f0
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <stdlib.h>
21 #include <string.h>
23 #include "platform.h"
24 #include "common/utils.h"
25 #include "common/atomic.h"
27 #include "nvic.h"
29 #include "gpio.h"
30 #include "gpio.h"
31 #include "rcc.h"
32 #include "system.h"
34 #include "timer.h"
35 #include "timer_impl.h"
37 #define TIM_N(n) (1 << (n))
40 Groups that allow running different period (ex 50Hz servos + 400Hz throttle + etc):
41 TIM1 2 channels
42 TIM2 4 channels
43 TIM3 4 channels
44 TIM4 4 channels
47 #define USED_TIMER_COUNT BITCOUNT(USED_TIMERS)
48 #define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4
50 #define TIM_IT_CCx(ch) (TIM_IT_CC1 << ((ch) / 4))
52 typedef struct timerConfig_s {
53 timerCCHandlerRec_t *edgeCallback[CC_CHANNELS_PER_TIMER];
54 timerOvrHandlerRec_t *overflowCallback[CC_CHANNELS_PER_TIMER];
55 timerOvrHandlerRec_t *overflowCallbackActive; // null-terminated linkded list of active overflow callbacks
56 uint32_t forcedOverflowTimerValue;
57 } timerConfig_t;
58 timerConfig_t timerConfig[USED_TIMER_COUNT];
60 typedef struct {
61 channelType_t type;
62 } timerChannelInfo_t;
63 timerChannelInfo_t timerChannelInfo[USABLE_TIMER_CHANNEL_COUNT];
65 typedef struct {
66 uint8_t priority;
67 } timerInfo_t;
68 timerInfo_t timerInfo[USED_TIMER_COUNT];
70 // return index of timer in timer table. Lowest timer has index 0
71 #define TIMER_INDEX(i) BITCOUNT((TIM_N(i) - 1) & USED_TIMERS)
73 static uint8_t lookupTimerIndex(const TIM_TypeDef *tim)
75 #define _CASE_SHF 10 // amount we can safely shift timer address to the right. gcc will throw error if some timers overlap
76 #define _CASE_(tim, index) case ((unsigned)tim >> _CASE_SHF): return index; break
77 #define _CASE(i) _CASE_(TIM##i##_BASE, TIMER_INDEX(i))
79 // let gcc do the work, switch should be quite optimized
80 switch((unsigned)tim >> _CASE_SHF) {
81 #if USED_TIMERS & TIM_N(1)
82 _CASE(1);
83 #endif
84 #if USED_TIMERS & TIM_N(2)
85 _CASE(2);
86 #endif
87 #if USED_TIMERS & TIM_N(3)
88 _CASE(3);
89 #endif
90 #if USED_TIMERS & TIM_N(4)
91 _CASE(4);
92 #endif
93 #if USED_TIMERS & TIM_N(8)
94 _CASE(8);
95 #endif
96 #if USED_TIMERS & TIM_N(15)
97 _CASE(15);
98 #endif
99 #if USED_TIMERS & TIM_N(16)
100 _CASE(16);
101 #endif
102 #if USED_TIMERS & TIM_N(17)
103 _CASE(17);
104 #endif
105 default: return ~1; // make sure final index is out of range
107 #undef _CASE
108 #undef _CASE_
111 TIM_TypeDef * const usedTimers[USED_TIMER_COUNT] = {
112 #define _DEF(i) TIM##i
114 #if USED_TIMERS & TIM_N(1)
115 _DEF(1),
116 #endif
117 #if USED_TIMERS & TIM_N(2)
118 _DEF(2),
119 #endif
120 #if USED_TIMERS & TIM_N(3)
121 _DEF(3),
122 #endif
123 #if USED_TIMERS & TIM_N(4)
124 _DEF(4),
125 #endif
126 #if USED_TIMERS & TIM_N(8)
127 _DEF(8),
128 #endif
129 #if USED_TIMERS & TIM_N(15)
130 _DEF(15),
131 #endif
132 #if USED_TIMERS & TIM_N(16)
133 _DEF(16),
134 #endif
135 #if USED_TIMERS & TIM_N(17)
136 _DEF(17),
137 #endif
138 #undef _DEF
141 static inline uint8_t lookupChannelIndex(const uint16_t channel)
143 return channel >> 2;
146 rccPeriphTag_t timerRCC(TIM_TypeDef *tim)
148 for (uint8_t i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
149 if (timerDefinitions[i].TIMx == tim) {
150 return timerDefinitions[i].rcc;
153 return 0;
156 void timerNVICConfigure(uint8_t irq)
158 NVIC_InitTypeDef NVIC_InitStructure;
160 NVIC_InitStructure.NVIC_IRQChannel = irq;
161 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER);
162 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER);
163 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
164 NVIC_Init(&NVIC_InitStructure);
167 void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
169 TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
171 TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
172 TIM_TimeBaseStructure.TIM_Period = (period - 1) & 0xffff; // AKA TIMx_ARR
174 // "The counter clock frequency (CK_CNT) is equal to f CK_PSC / (PSC[15:0] + 1)." - STM32F10x Reference Manual 14.4.11
175 // Thus for 1Mhz: 72000000 / 1000000 = 72, 72 - 1 = 71 = TIM_Prescaler
176 #if defined (STM32F40_41xxx)
177 if (tim == TIM1 || tim == TIM8 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
178 TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
180 else {
181 TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 2 / ((uint32_t)mhz * 1000000)) - 1;
183 #elif defined (STM32F411xE)
184 if (tim == TIM1 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
185 TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
187 else {
188 TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 2 / ((uint32_t)mhz * 1000000)) - 1;
190 #else
191 TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
192 #endif
194 TIM_TimeBaseStructure.TIM_ClockDivision = 0;
195 TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
196 TIM_TimeBaseInit(tim, &TIM_TimeBaseStructure);
199 // old interface for PWM inputs. It should be replaced
200 void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, uint8_t mhz)
202 configTimeBase(timerHardwarePtr->tim, period, mhz);
203 TIM_Cmd(timerHardwarePtr->tim, ENABLE);
204 timerNVICConfigure(timerHardwarePtr->irq);
205 // HACK - enable second IRQ on timers that need it
206 switch(timerHardwarePtr->irq) {
207 #if defined(STM32F10X)
208 case TIM1_CC_IRQn:
209 timerNVICConfigure(TIM1_UP_IRQn);
210 break;
211 #endif
212 #if defined (STM32F40_41xxx) || defined(STM32F411xE)
213 case TIM1_CC_IRQn:
214 timerNVICConfigure(TIM1_UP_TIM10_IRQn);
215 break;
216 #endif
217 #if defined (STM32F40_41xxx)
218 case TIM8_CC_IRQn:
219 timerNVICConfigure(TIM8_UP_TIM13_IRQn);
220 break;
221 #endif
222 #ifdef STM32F303xC
223 case TIM1_CC_IRQn:
224 timerNVICConfigure(TIM1_UP_TIM16_IRQn);
225 break;
226 #endif
227 #if defined(STM32F10X_XL)
228 case TIM8_CC_IRQn:
229 timerNVICConfigure(TIM8_UP_IRQn);
230 break;
231 #endif
235 // allocate and configure timer channel. Timer priority is set to highest priority of its channels
236 void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority)
238 unsigned channel = timHw - timerHardware;
239 if(channel >= USABLE_TIMER_CHANNEL_COUNT)
240 return;
242 timerChannelInfo[channel].type = type;
243 unsigned timer = lookupTimerIndex(timHw->tim);
244 if(timer >= USED_TIMER_COUNT)
245 return;
246 if(irqPriority < timerInfo[timer].priority) {
247 // it would be better to set priority in the end, but current startup sequence is not ready
248 configTimeBase(usedTimers[timer], 0, 1);
249 TIM_Cmd(usedTimers[timer], ENABLE);
251 NVIC_InitTypeDef NVIC_InitStructure;
253 NVIC_InitStructure.NVIC_IRQChannel = timHw->irq;
254 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(irqPriority);
255 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(irqPriority);
256 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
257 NVIC_Init(&NVIC_InitStructure);
259 timerInfo[timer].priority = irqPriority;
263 void timerChCCHandlerInit(timerCCHandlerRec_t *self, timerCCHandlerCallback *fn)
265 self->fn = fn;
268 void timerChOvrHandlerInit(timerOvrHandlerRec_t *self, timerOvrHandlerCallback *fn)
270 self->fn = fn;
271 self->next = NULL;
274 // update overflow callback list
275 // some synchronization mechanism is neccesary to avoid disturbing other channels (BASEPRI used now)
276 static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, TIM_TypeDef *tim) {
277 timerOvrHandlerRec_t **chain = &cfg->overflowCallbackActive;
278 ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
279 for(int i = 0; i < CC_CHANNELS_PER_TIMER; i++)
280 if(cfg->overflowCallback[i]) {
281 *chain = cfg->overflowCallback[i];
282 chain = &cfg->overflowCallback[i]->next;
284 *chain = NULL;
286 // enable or disable IRQ
287 TIM_ITConfig(tim, TIM_IT_Update, cfg->overflowCallbackActive ? ENABLE : DISABLE);
290 // config edge and overflow callback for channel. Try to avoid overflowCallback, it is a bit expensive
291 void timerChConfigCallbacks(const timerHardware_t *timHw, timerCCHandlerRec_t *edgeCallback, timerOvrHandlerRec_t *overflowCallback)
293 uint8_t timerIndex = lookupTimerIndex(timHw->tim);
294 if (timerIndex >= USED_TIMER_COUNT) {
295 return;
297 uint8_t channelIndex = lookupChannelIndex(timHw->channel);
298 if(edgeCallback == NULL) // disable irq before changing callback to NULL
299 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), DISABLE);
300 // setup callback info
301 timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallback;
302 timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback;
303 // enable channel IRQ
304 if(edgeCallback)
305 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), ENABLE);
307 timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim);
310 // configure callbacks for pair of channels (1+2 or 3+4).
311 // Hi(2,4) and Lo(1,3) callbacks are specified, it is not important which timHw channel is used.
312 // This is intended for dual capture mode (each channel handles one transition)
313 void timerChConfigCallbacksDual(const timerHardware_t *timHw, timerCCHandlerRec_t *edgeCallbackLo, timerCCHandlerRec_t *edgeCallbackHi, timerOvrHandlerRec_t *overflowCallback)
315 uint8_t timerIndex = lookupTimerIndex(timHw->tim);
316 if (timerIndex >= USED_TIMER_COUNT) {
317 return;
319 uint16_t chLo = timHw->channel & ~TIM_Channel_2; // lower channel
320 uint16_t chHi = timHw->channel | TIM_Channel_2; // upper channel
321 uint8_t channelIndex = lookupChannelIndex(chLo); // get index of lower channel
323 if(edgeCallbackLo == NULL) // disable irq before changing setting callback to NULL
324 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chLo), DISABLE);
325 if(edgeCallbackHi == NULL) // disable irq before changing setting callback to NULL
326 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chHi), DISABLE);
328 // setup callback info
329 timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallbackLo;
330 timerConfig[timerIndex].edgeCallback[channelIndex + 1] = edgeCallbackHi;
331 timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback;
332 timerConfig[timerIndex].overflowCallback[channelIndex + 1] = NULL;
334 // enable channel IRQs
335 if(edgeCallbackLo) {
336 TIM_ClearFlag(timHw->tim, TIM_IT_CCx(chLo));
337 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chLo), ENABLE);
339 if(edgeCallbackHi) {
340 TIM_ClearFlag(timHw->tim, TIM_IT_CCx(chHi));
341 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chHi), ENABLE);
344 timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim);
347 // enable/disable IRQ for low channel in dual configuration
348 void timerChITConfigDualLo(const timerHardware_t *timHw, FunctionalState newState) {
349 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel&~TIM_Channel_2), newState);
352 // enable or disable IRQ
353 void timerChITConfig(const timerHardware_t *timHw, FunctionalState newState)
355 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), newState);
358 // clear Compare/Capture flag for channel
359 void timerChClearCCFlag(const timerHardware_t *timHw)
361 TIM_ClearFlag(timHw->tim, TIM_IT_CCx(timHw->channel));
364 // configure timer channel GPIO mode
365 void timerChConfigGPIO(const timerHardware_t* timHw, ioConfig_t mode)
367 IOInit(IOGetByTag(timHw->tag), OWNER_TIMER, RESOURCE_TIMER);
368 IOConfigGPIO(IOGetByTag(timHw->tag), mode);
371 // calculate input filter constant
372 // TODO - we should probably setup DTS to higher value to allow reasonable input filtering
373 // - notice that prescaler[0] does use DTS for sampling - the sequence won't be monotonous anymore
374 static unsigned getFilter(unsigned ticks)
376 static const unsigned ftab[16] = {
377 1*1, // fDTS !
378 1*2, 1*4, 1*8, // fCK_INT
379 2*6, 2*8, // fDTS/2
380 4*6, 4*8,
381 8*6, 8*8,
382 16*5, 16*6, 16*8,
383 32*5, 32*6, 32*8
385 for(unsigned i = 1; i < ARRAYLEN(ftab); i++)
386 if(ftab[i] > ticks)
387 return i - 1;
388 return 0x0f;
391 // Configure input captupre
392 void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks)
394 TIM_ICInitTypeDef TIM_ICInitStructure;
396 TIM_ICStructInit(&TIM_ICInitStructure);
397 TIM_ICInitStructure.TIM_Channel = timHw->channel;
398 TIM_ICInitStructure.TIM_ICPolarity = polarityRising ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling;
399 TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
400 TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
401 TIM_ICInitStructure.TIM_ICFilter = getFilter(inputFilterTicks);
403 TIM_ICInit(timHw->tim, &TIM_ICInitStructure);
406 // configure dual channel input channel for capture
407 // polarity is for Low channel (capture order is always Lo - Hi)
408 void timerChConfigICDual(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks)
410 TIM_ICInitTypeDef TIM_ICInitStructure;
411 bool directRising = (timHw->channel & TIM_Channel_2) ? !polarityRising : polarityRising;
412 // configure direct channel
413 TIM_ICStructInit(&TIM_ICInitStructure);
415 TIM_ICInitStructure.TIM_Channel = timHw->channel;
416 TIM_ICInitStructure.TIM_ICPolarity = directRising ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling;
417 TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
418 TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
419 TIM_ICInitStructure.TIM_ICFilter = getFilter(inputFilterTicks);
420 TIM_ICInit(timHw->tim, &TIM_ICInitStructure);
421 // configure indirect channel
422 TIM_ICInitStructure.TIM_Channel = timHw->channel ^ TIM_Channel_2; // get opposite channel no
423 TIM_ICInitStructure.TIM_ICPolarity = directRising ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising;
424 TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_IndirectTI;
425 TIM_ICInit(timHw->tim, &TIM_ICInitStructure);
428 void timerChICPolarity(const timerHardware_t *timHw, bool polarityRising)
430 timCCER_t tmpccer = timHw->tim->CCER;
431 tmpccer &= ~(TIM_CCER_CC1P << timHw->channel);
432 tmpccer |= polarityRising ? (TIM_ICPolarity_Rising << timHw->channel) : (TIM_ICPolarity_Falling << timHw->channel);
433 timHw->tim->CCER = tmpccer;
436 volatile timCCR_t* timerChCCRHi(const timerHardware_t *timHw)
438 return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + (timHw->channel | TIM_Channel_2));
441 volatile timCCR_t* timerChCCRLo(const timerHardware_t *timHw)
443 return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + (timHw->channel & ~TIM_Channel_2));
448 volatile timCCR_t* timerChCCR(const timerHardware_t *timHw)
450 return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + timHw->channel);
453 void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHigh)
455 TIM_OCInitTypeDef TIM_OCInitStructure;
457 TIM_OCStructInit(&TIM_OCInitStructure);
458 if(outEnable) {
459 TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Inactive;
460 TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
461 if (timHw->outputInverted) {
462 stateHigh = !stateHigh;
464 TIM_OCInitStructure.TIM_OCPolarity = stateHigh ? TIM_OCPolarity_High : TIM_OCPolarity_Low;
465 } else {
466 TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Timing;
469 switch (timHw->channel) {
470 case TIM_Channel_1:
471 TIM_OC1Init(timHw->tim, &TIM_OCInitStructure);
472 TIM_OC1PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
473 break;
474 case TIM_Channel_2:
475 TIM_OC2Init(timHw->tim, &TIM_OCInitStructure);
476 TIM_OC2PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
477 break;
478 case TIM_Channel_3:
479 TIM_OC3Init(timHw->tim, &TIM_OCInitStructure);
480 TIM_OC3PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
481 break;
482 case TIM_Channel_4:
483 TIM_OC4Init(timHw->tim, &TIM_OCInitStructure);
484 TIM_OC4PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
485 break;
489 static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
491 uint16_t capture;
492 unsigned tim_status;
493 tim_status = tim->SR & tim->DIER;
494 #if 1
495 while(tim_status) {
496 // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
497 // currrent order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
498 unsigned bit = __builtin_clz(tim_status);
499 unsigned mask = ~(0x80000000 >> bit);
500 tim->SR = mask;
501 tim_status &= mask;
502 switch(bit) {
503 case __builtin_clz(TIM_IT_Update): {
505 if(timerConfig->forcedOverflowTimerValue != 0){
506 capture = timerConfig->forcedOverflowTimerValue - 1;
507 timerConfig->forcedOverflowTimerValue = 0;
508 } else {
509 capture = tim->ARR;
512 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
513 while(cb) {
514 cb->fn(cb, capture);
515 cb = cb->next;
517 break;
519 case __builtin_clz(TIM_IT_CC1):
520 timerConfig->edgeCallback[0]->fn(timerConfig->edgeCallback[0], tim->CCR1);
521 break;
522 case __builtin_clz(TIM_IT_CC2):
523 timerConfig->edgeCallback[1]->fn(timerConfig->edgeCallback[1], tim->CCR2);
524 break;
525 case __builtin_clz(TIM_IT_CC3):
526 timerConfig->edgeCallback[2]->fn(timerConfig->edgeCallback[2], tim->CCR3);
527 break;
528 case __builtin_clz(TIM_IT_CC4):
529 timerConfig->edgeCallback[3]->fn(timerConfig->edgeCallback[3], tim->CCR4);
530 break;
533 #else
534 if (tim_status & (int)TIM_IT_Update) {
535 tim->SR = ~TIM_IT_Update;
536 capture = tim->ARR;
537 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
538 while(cb) {
539 cb->fn(cb, capture);
540 cb = cb->next;
543 if (tim_status & (int)TIM_IT_CC1) {
544 tim->SR = ~TIM_IT_CC1;
545 timerConfig->edgeCallback[0]->fn(timerConfig->edgeCallback[0], tim->CCR1);
547 if (tim_status & (int)TIM_IT_CC2) {
548 tim->SR = ~TIM_IT_CC2;
549 timerConfig->edgeCallback[1]->fn(timerConfig->edgeCallback[1], tim->CCR2);
551 if (tim_status & (int)TIM_IT_CC3) {
552 tim->SR = ~TIM_IT_CC3;
553 timerConfig->edgeCallback[2]->fn(timerConfig->edgeCallback[2], tim->CCR3);
555 if (tim_status & (int)TIM_IT_CC4) {
556 tim->SR = ~TIM_IT_CC4;
557 timerConfig->edgeCallback[3]->fn(timerConfig->edgeCallback[3], tim->CCR4);
559 #endif
562 // handler for shared interrupts when both timers need to check status bits
563 #define _TIM_IRQ_HANDLER2(name, i, j) \
564 void name(void) \
566 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
567 timCCxHandler(TIM ## j, &timerConfig[TIMER_INDEX(j)]); \
568 } struct dummy
570 #define _TIM_IRQ_HANDLER(name, i) \
571 void name(void) \
573 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
574 } struct dummy
576 #if USED_TIMERS & TIM_N(1)
577 _TIM_IRQ_HANDLER(TIM1_CC_IRQHandler, 1);
578 # if defined(STM32F10X)
579 _TIM_IRQ_HANDLER(TIM1_UP_IRQHandler, 1); // timer can't be shared
580 # endif
581 # if defined(STM32F40_41xxx) || defined (STM32F411xE)
582 # if USED_TIMERS & TIM_N(10)
583 _TIM_IRQ_HANDLER2(TIM1_UP_TIM10_IRQHandler, 1, 10); // both timers are in use
584 # else
585 _TIM_IRQ_HANDLER(TIM1_UP_TIM10_IRQHandler, 1); // timer10 is not used
586 # endif
587 # endif
588 # ifdef STM32F303xC
589 # if USED_TIMERS & TIM_N(16)
590 _TIM_IRQ_HANDLER2(TIM1_UP_TIM16_IRQHandler, 1, 16); // both timers are in use
591 # else
592 _TIM_IRQ_HANDLER(TIM1_UP_TIM16_IRQHandler, 1); // timer16 is not used
593 # endif
594 # endif
595 #endif
596 #if USED_TIMERS & TIM_N(2)
597 _TIM_IRQ_HANDLER(TIM2_IRQHandler, 2);
598 #endif
599 #if USED_TIMERS & TIM_N(3)
600 _TIM_IRQ_HANDLER(TIM3_IRQHandler, 3);
601 #endif
602 #if USED_TIMERS & TIM_N(4)
603 _TIM_IRQ_HANDLER(TIM4_IRQHandler, 4);
604 #endif
605 #if USED_TIMERS & TIM_N(5)
606 _TIM_IRQ_HANDLER(TIM5_IRQHandler, 5);
607 #endif
608 #if USED_TIMERS & TIM_N(8)
609 _TIM_IRQ_HANDLER(TIM8_CC_IRQHandler, 8);
610 # if defined(STM32F10X_XL)
611 _TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler, 8);
612 # else // f10x_hd, f30x
613 _TIM_IRQ_HANDLER(TIM8_UP_IRQHandler, 8);
614 # endif
615 # if defined(STM32F40_41xxx)
616 # if USED_TIMERS & TIM_N(13)
617 _TIM_IRQ_HANDLER2(TIM8_UP_TIM13_IRQHandler, 8, 13); // both timers are in use
618 # else
619 _TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler, 8); // timer13 is not used
620 # endif
621 # endif
622 # if defined (STM32F411xE)
623 # endif
624 #endif
625 #if USED_TIMERS & TIM_N(9)
626 _TIM_IRQ_HANDLER(TIM1_BRK_TIM9_IRQHandler, 9);
627 #endif
628 # if USED_TIMERS & TIM_N(11)
629 _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM11_IRQHandler, 11);
630 # endif
631 #if USED_TIMERS & TIM_N(12)
632 _TIM_IRQ_HANDLER(TIM8_BRK_TIM12_IRQHandler, 12);
633 #endif
634 #if USED_TIMERS & TIM_N(15)
635 _TIM_IRQ_HANDLER(TIM1_BRK_TIM15_IRQHandler, 15);
636 #endif
637 #if defined(STM32F303xC) && ((USED_TIMERS & (TIM_N(1)|TIM_N(16))) == (TIM_N(16)))
638 _TIM_IRQ_HANDLER(TIM1_UP_TIM16_IRQHandler, 16); // only timer16 is used, not timer1
639 #endif
640 #if USED_TIMERS & TIM_N(17)
641 _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM17_IRQHandler, 17);
642 #endif
644 void timerInit(void)
646 memset(timerConfig, 0, sizeof (timerConfig));
648 #ifdef CC3D
649 GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE);
650 #endif
652 /* enable the timer peripherals */
653 for (uint8_t i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
654 RCC_ClockCmd(timerRCC(timerHardware[i].tim), ENABLE);
657 #if defined(STM32F3) || defined(STM32F4)
658 for (uint8_t timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
659 const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
660 IOConfigGPIOAF(IOGetByTag(timerHardwarePtr->tag), timerHardwarePtr->ioMode, timerHardwarePtr->alternateFunction);
662 #endif
664 // initialize timer channel structures
665 for(int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
666 timerChannelInfo[i].type = TYPE_FREE;
668 for(int i = 0; i < USED_TIMER_COUNT; i++) {
669 timerInfo[i].priority = ~0;
673 // finish configuring timers after allocation phase
674 // start timers
675 // TODO - Work in progress - initialization routine must be modified/verified to start correctly without timers
676 void timerStart(void)
678 #if 0
679 for(unsigned timer = 0; timer < USED_TIMER_COUNT; timer++) {
680 int priority = -1;
681 int irq = -1;
682 for(unsigned hwc = 0; hwc < USABLE_TIMER_CHANNEL_COUNT; hwc++)
683 if((timerChannelInfo[hwc].type != TYPE_FREE) && (timerHardware[hwc].tim == usedTimers[timer])) {
684 // TODO - move IRQ to timer info
685 irq = timerHardware[hwc].irq;
687 // TODO - aggregate required timer paramaters
688 configTimeBase(usedTimers[timer], 0, 1);
689 TIM_Cmd(usedTimers[timer], ENABLE);
690 if(priority >= 0) { // maybe none of the channels was configured
691 NVIC_InitTypeDef NVIC_InitStructure;
693 NVIC_InitStructure.NVIC_IRQChannel = irq;
694 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_SPLIT_PRIORITY_BASE(priority);
695 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_SPLIT_PRIORITY_SUB(priority);
696 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
697 NVIC_Init(&NVIC_InitStructure);
700 #endif
704 * Force an overflow for a given timer.
705 * Saves the current value of the counter in the relevant timerConfig's forcedOverflowTimerValue variable.
706 * @param TIM_Typedef *tim The timer to overflow
707 * @return void
709 void timerForceOverflow(TIM_TypeDef *tim)
711 uint8_t timerIndex = lookupTimerIndex((const TIM_TypeDef *)tim);
713 ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
714 // Save the current count so that PPM reading will work on the same timer that was forced to overflow
715 timerConfig[timerIndex].forcedOverflowTimerValue = tim->CNT + 1;
717 // Force an overflow by setting the UG bit
718 tim->EGR |= TIM_EGR_UG;