Fix function brace style
[betaflight.git] / src / main / drivers / timer.c
blob6f218371db8f1170ebc42ade0dd302186554fca4
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 #include <stdbool.h>
22 #include <stdint.h>
23 #include <string.h>
24 #include <math.h>
26 #include "platform.h"
28 #ifdef USE_TIMER
30 #include "build/atomic.h"
32 #include "common/utils.h"
34 #include "drivers/nvic.h"
36 #include "drivers/io.h"
37 #include "rcc.h"
38 #include "drivers/system.h"
40 #include "timer.h"
41 #include "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 // TIM_Channel_1..4
56 #define TIM_IT_CCx(ch) (TIM_IT_CC1 << ((ch) / 4))
58 typedef struct timerConfig_s {
59 // per-timer
60 timerOvrHandlerRec_t *updateCallback;
62 // per-channel
63 timerCCHandlerRec_t *edgeCallback[CC_CHANNELS_PER_TIMER];
64 timerOvrHandlerRec_t *overflowCallback[CC_CHANNELS_PER_TIMER];
66 // state
67 timerOvrHandlerRec_t *overflowCallbackActive; // null-terminated linked list of active overflow callbacks
68 uint32_t forcedOverflowTimerValue;
69 } timerConfig_t;
70 timerConfig_t timerConfig[USED_TIMER_COUNT];
72 typedef struct {
73 channelType_t type;
74 } timerChannelInfo_t;
76 timerChannelInfo_t timerChannelInfo[TIMER_CHANNEL_COUNT];
78 typedef struct {
79 uint8_t priority;
80 } timerInfo_t;
81 timerInfo_t timerInfo[USED_TIMER_COUNT];
83 // return index of timer in timer table. Lowest timer has index 0
84 #define TIMER_INDEX(i) BITCOUNT((TIM_N(i) - 1) & USED_TIMERS)
86 static uint8_t lookupTimerIndex(const TIM_TypeDef *tim)
88 #define _CASE_SHF 10 // amount we can safely shift timer address to the right. gcc will throw error if some timers overlap
89 #define _CASE_(tim, index) case ((unsigned)tim >> _CASE_SHF): return index; break
90 #define _CASE(i) _CASE_(TIM##i##_BASE, TIMER_INDEX(i))
92 // let gcc do the work, switch should be quite optimized
93 switch ((unsigned)tim >> _CASE_SHF) {
94 #if USED_TIMERS & TIM_N(1)
95 _CASE(1);
96 #endif
97 #if USED_TIMERS & TIM_N(2)
98 _CASE(2);
99 #endif
100 #if USED_TIMERS & TIM_N(3)
101 _CASE(3);
102 #endif
103 #if USED_TIMERS & TIM_N(4)
104 _CASE(4);
105 #endif
106 #if USED_TIMERS & TIM_N(5)
107 _CASE(5);
108 #endif
109 #if USED_TIMERS & TIM_N(6)
110 _CASE(6);
111 #endif
112 #if USED_TIMERS & TIM_N(7)
113 _CASE(7);
114 #endif
115 #if USED_TIMERS & TIM_N(8)
116 _CASE(8);
117 #endif
118 #if USED_TIMERS & TIM_N(9)
119 _CASE(9);
120 #endif
121 #if USED_TIMERS & TIM_N(10)
122 _CASE(10);
123 #endif
124 #if USED_TIMERS & TIM_N(11)
125 _CASE(11);
126 #endif
127 #if USED_TIMERS & TIM_N(12)
128 _CASE(12);
129 #endif
130 #if USED_TIMERS & TIM_N(13)
131 _CASE(13);
132 #endif
133 #if USED_TIMERS & TIM_N(14)
134 _CASE(14);
135 #endif
136 #if USED_TIMERS & TIM_N(15)
137 _CASE(15);
138 #endif
139 #if USED_TIMERS & TIM_N(16)
140 _CASE(16);
141 #endif
142 #if USED_TIMERS & TIM_N(17)
143 _CASE(17);
144 #endif
145 default: return ~1; // make sure final index is out of range
147 #undef _CASE
148 #undef _CASE_
151 TIM_TypeDef * const usedTimers[USED_TIMER_COUNT] = {
152 #define _DEF(i) TIM##i
154 #if USED_TIMERS & TIM_N(1)
155 _DEF(1),
156 #endif
157 #if USED_TIMERS & TIM_N(2)
158 _DEF(2),
159 #endif
160 #if USED_TIMERS & TIM_N(3)
161 _DEF(3),
162 #endif
163 #if USED_TIMERS & TIM_N(4)
164 _DEF(4),
165 #endif
166 #if USED_TIMERS & TIM_N(5)
167 _DEF(5),
168 #endif
169 #if USED_TIMERS & TIM_N(6)
170 _DEF(6),
171 #endif
172 #if USED_TIMERS & TIM_N(7)
173 _DEF(7),
174 #endif
175 #if USED_TIMERS & TIM_N(8)
176 _DEF(8),
177 #endif
178 #if USED_TIMERS & TIM_N(9)
179 _DEF(9),
180 #endif
181 #if USED_TIMERS & TIM_N(10)
182 _DEF(10),
183 #endif
184 #if USED_TIMERS & TIM_N(11)
185 _DEF(11),
186 #endif
187 #if USED_TIMERS & TIM_N(12)
188 _DEF(12),
189 #endif
190 #if USED_TIMERS & TIM_N(13)
191 _DEF(13),
192 #endif
193 #if USED_TIMERS & TIM_N(14)
194 _DEF(14),
195 #endif
196 #if USED_TIMERS & TIM_N(15)
197 _DEF(15),
198 #endif
199 #if USED_TIMERS & TIM_N(16)
200 _DEF(16),
201 #endif
202 #if USED_TIMERS & TIM_N(17)
203 _DEF(17),
204 #endif
205 #undef _DEF
208 // Map timer index to timer number (Straight copy of usedTimers array)
209 const int8_t timerNumbers[USED_TIMER_COUNT] = {
210 #define _DEF(i) i
212 #if USED_TIMERS & TIM_N(1)
213 _DEF(1),
214 #endif
215 #if USED_TIMERS & TIM_N(2)
216 _DEF(2),
217 #endif
218 #if USED_TIMERS & TIM_N(3)
219 _DEF(3),
220 #endif
221 #if USED_TIMERS & TIM_N(4)
222 _DEF(4),
223 #endif
224 #if USED_TIMERS & TIM_N(5)
225 _DEF(5),
226 #endif
227 #if USED_TIMERS & TIM_N(6)
228 _DEF(6),
229 #endif
230 #if USED_TIMERS & TIM_N(7)
231 _DEF(7),
232 #endif
233 #if USED_TIMERS & TIM_N(8)
234 _DEF(8),
235 #endif
236 #if USED_TIMERS & TIM_N(9)
237 _DEF(9),
238 #endif
239 #if USED_TIMERS & TIM_N(10)
240 _DEF(10),
241 #endif
242 #if USED_TIMERS & TIM_N(11)
243 _DEF(11),
244 #endif
245 #if USED_TIMERS & TIM_N(12)
246 _DEF(12),
247 #endif
248 #if USED_TIMERS & TIM_N(13)
249 _DEF(13),
250 #endif
251 #if USED_TIMERS & TIM_N(14)
252 _DEF(14),
253 #endif
254 #if USED_TIMERS & TIM_N(15)
255 _DEF(15),
256 #endif
257 #if USED_TIMERS & TIM_N(16)
258 _DEF(16),
259 #endif
260 #if USED_TIMERS & TIM_N(17)
261 _DEF(17),
262 #endif
263 #undef _DEF
266 int8_t timerGetNumberByIndex(uint8_t index)
268 if (index < USED_TIMER_COUNT) {
269 return timerNumbers[index];
270 } else {
271 return 0;
275 int8_t timerGetTIMNumber(const TIM_TypeDef *tim)
277 const uint8_t index = lookupTimerIndex(tim);
279 return timerGetNumberByIndex(index);
282 static inline uint8_t lookupChannelIndex(const uint16_t channel)
284 return channel >> 2;
287 uint8_t timerLookupChannelIndex(const uint16_t channel)
289 return lookupChannelIndex(channel);
292 rccPeriphTag_t timerRCC(TIM_TypeDef *tim)
294 for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
295 if (timerDefinitions[i].TIMx == tim) {
296 return timerDefinitions[i].rcc;
299 return 0;
302 uint8_t timerInputIrq(TIM_TypeDef *tim)
304 for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
305 if (timerDefinitions[i].TIMx == tim) {
306 return timerDefinitions[i].inputIrq;
309 return 0;
312 void timerNVICConfigure(uint8_t irq)
314 NVIC_InitTypeDef NVIC_InitStructure;
316 NVIC_InitStructure.NVIC_IRQChannel = irq;
317 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER);
318 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER);
319 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
320 NVIC_Init(&NVIC_InitStructure);
323 void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint32_t hz)
325 TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
327 TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
328 TIM_TimeBaseStructure.TIM_Period = (period - 1) & 0xFFFF; // AKA TIMx_ARR
330 // "The counter clock frequency (CK_CNT) is equal to f CK_PSC / (PSC[15:0] + 1)." - STM32F10x Reference Manual 14.4.11
331 // Thus for 1Mhz: 72000000 / 1000000 = 72, 72 - 1 = 71 = TIM_Prescaler
332 TIM_TimeBaseStructure.TIM_Prescaler = (timerClock(tim) / hz) - 1;
334 TIM_TimeBaseStructure.TIM_ClockDivision = 0;
335 TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
336 TIM_TimeBaseInit(tim, &TIM_TimeBaseStructure);
339 // old interface for PWM inputs. It should be replaced
340 void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, uint32_t hz)
342 configTimeBase(timerHardwarePtr->tim, period, hz);
343 TIM_Cmd(timerHardwarePtr->tim, ENABLE);
345 uint8_t irq = timerInputIrq(timerHardwarePtr->tim);
346 timerNVICConfigure(irq);
347 // HACK - enable second IRQ on timers that need it
348 switch (irq) {
349 #if defined (STM32F40_41xxx) || defined(STM32F411xE)
350 case TIM1_CC_IRQn:
351 timerNVICConfigure(TIM1_UP_TIM10_IRQn);
352 break;
353 #endif
354 #if defined (STM32F40_41xxx)
355 case TIM8_CC_IRQn:
356 timerNVICConfigure(TIM8_UP_TIM13_IRQn);
357 break;
358 #endif
362 // allocate and configure timer channel. Timer priority is set to highest priority of its channels
363 void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority, uint8_t irq)
365 unsigned channel = timHw - TIMER_HARDWARE;
366 if (channel >= TIMER_CHANNEL_COUNT) {
367 return;
370 timerChannelInfo[channel].type = type;
371 unsigned timer = lookupTimerIndex(timHw->tim);
372 if (timer >= USED_TIMER_COUNT)
373 return;
374 if (irqPriority < timerInfo[timer].priority) {
375 // it would be better to set priority in the end, but current startup sequence is not ready
376 configTimeBase(usedTimers[timer], 0, 1);
377 TIM_Cmd(usedTimers[timer], ENABLE);
379 NVIC_InitTypeDef NVIC_InitStructure;
381 NVIC_InitStructure.NVIC_IRQChannel = irq;
382 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(irqPriority);
383 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(irqPriority);
384 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
385 NVIC_Init(&NVIC_InitStructure);
387 timerInfo[timer].priority = irqPriority;
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 TIM_TypeDef *tim)
406 timerOvrHandlerRec_t **chain = &cfg->overflowCallbackActive;
407 ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
409 if (cfg->updateCallback) {
410 *chain = cfg->updateCallback;
411 chain = &cfg->updateCallback->next;
414 for (int i = 0; i < CC_CHANNELS_PER_TIMER; i++)
415 if (cfg->overflowCallback[i]) {
416 *chain = cfg->overflowCallback[i];
417 chain = &cfg->overflowCallback[i]->next;
419 *chain = NULL;
421 // enable or disable IRQ
422 TIM_ITConfig((TIM_TypeDef *)tim, TIM_IT_Update, cfg->overflowCallbackActive ? ENABLE : DISABLE);
425 // config edge and overflow callback for channel. Try to avoid per-channel overflowCallback, it is a bit expensive
426 void timerChConfigCallbacks(const timerHardware_t *timHw, timerCCHandlerRec_t *edgeCallback, timerOvrHandlerRec_t *overflowCallback)
428 uint8_t timerIndex = lookupTimerIndex(timHw->tim);
429 if (timerIndex >= USED_TIMER_COUNT) {
430 return;
432 uint8_t channelIndex = lookupChannelIndex(timHw->channel);
433 if (edgeCallback == NULL) // disable irq before changing callback to NULL
434 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), DISABLE);
435 // setup callback info
436 timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallback;
437 timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback;
438 // enable channel IRQ
439 if (edgeCallback)
440 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), ENABLE);
442 timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim);
445 void timerConfigUpdateCallback(const TIM_TypeDef *tim, timerOvrHandlerRec_t *updateCallback)
447 uint8_t timerIndex = lookupTimerIndex(tim);
448 if (timerIndex >= USED_TIMER_COUNT) {
449 return;
451 timerConfig[timerIndex].updateCallback = updateCallback;
452 timerChConfig_UpdateOverflow(&timerConfig[timerIndex], tim);
455 // configure callbacks for pair of channels (1+2 or 3+4).
456 // Hi(2,4) and Lo(1,3) callbacks are specified, it is not important which timHw channel is used.
457 // This is intended for dual capture mode (each channel handles one transition)
458 void timerChConfigCallbacksDual(const timerHardware_t *timHw, timerCCHandlerRec_t *edgeCallbackLo, timerCCHandlerRec_t *edgeCallbackHi, timerOvrHandlerRec_t *overflowCallback)
460 uint8_t timerIndex = lookupTimerIndex(timHw->tim);
461 if (timerIndex >= USED_TIMER_COUNT) {
462 return;
464 uint16_t chLo = timHw->channel & ~TIM_Channel_2; // lower channel
465 uint16_t chHi = timHw->channel | TIM_Channel_2; // upper channel
466 uint8_t channelIndex = lookupChannelIndex(chLo); // get index of lower channel
468 if (edgeCallbackLo == NULL) // disable irq before changing setting callback to NULL
469 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chLo), DISABLE);
470 if (edgeCallbackHi == NULL) // disable irq before changing setting callback to NULL
471 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chHi), DISABLE);
473 // setup callback info
474 timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallbackLo;
475 timerConfig[timerIndex].edgeCallback[channelIndex + 1] = edgeCallbackHi;
476 timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback;
477 timerConfig[timerIndex].overflowCallback[channelIndex + 1] = NULL;
479 // enable channel IRQs
480 if (edgeCallbackLo) {
481 TIM_ClearFlag(timHw->tim, TIM_IT_CCx(chLo));
482 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chLo), ENABLE);
484 if (edgeCallbackHi) {
485 TIM_ClearFlag(timHw->tim, TIM_IT_CCx(chHi));
486 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chHi), ENABLE);
489 timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim);
492 // enable/disable IRQ for low channel in dual configuration
493 void timerChITConfigDualLo(const timerHardware_t *timHw, FunctionalState newState)
495 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel&~TIM_Channel_2), newState);
498 // enable or disable IRQ
499 void timerChITConfig(const timerHardware_t *timHw, FunctionalState newState)
501 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), newState);
504 // clear Compare/Capture flag for channel
505 void timerChClearCCFlag(const timerHardware_t *timHw)
507 TIM_ClearFlag(timHw->tim, TIM_IT_CCx(timHw->channel));
510 // configure timer channel GPIO mode
511 void timerChConfigGPIO(const timerHardware_t* timHw, ioConfig_t mode)
513 IOInit(IOGetByTag(timHw->tag), OWNER_TIMER, 0);
514 IOConfigGPIO(IOGetByTag(timHw->tag), mode);
517 // calculate input filter constant
518 // TODO - we should probably setup DTS to higher value to allow reasonable input filtering
519 // - notice that prescaler[0] does use DTS for sampling - the sequence won't be monotonous anymore
520 static unsigned getFilter(unsigned ticks)
522 static const unsigned ftab[16] = {
523 1*1, // fDTS !
524 1*2, 1*4, 1*8, // fCK_INT
525 2*6, 2*8, // fDTS/2
526 4*6, 4*8,
527 8*6, 8*8,
528 16*5, 16*6, 16*8,
529 32*5, 32*6, 32*8
531 for (unsigned i = 1; i < ARRAYLEN(ftab); i++)
532 if (ftab[i] > ticks)
533 return i - 1;
534 return 0x0f;
537 // Configure input capture
538 void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks)
540 TIM_ICInitTypeDef TIM_ICInitStructure;
542 TIM_ICStructInit(&TIM_ICInitStructure);
543 TIM_ICInitStructure.TIM_Channel = timHw->channel;
544 TIM_ICInitStructure.TIM_ICPolarity = polarityRising ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling;
545 TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
546 TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
547 TIM_ICInitStructure.TIM_ICFilter = getFilter(inputFilterTicks);
549 TIM_ICInit(timHw->tim, &TIM_ICInitStructure);
552 // configure dual channel input channel for capture
553 // polarity is for Low channel (capture order is always Lo - Hi)
554 void timerChConfigICDual(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks)
556 TIM_ICInitTypeDef TIM_ICInitStructure;
557 bool directRising = (timHw->channel & TIM_Channel_2) ? !polarityRising : polarityRising;
558 // configure direct channel
559 TIM_ICStructInit(&TIM_ICInitStructure);
561 TIM_ICInitStructure.TIM_Channel = timHw->channel;
562 TIM_ICInitStructure.TIM_ICPolarity = directRising ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling;
563 TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
564 TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
565 TIM_ICInitStructure.TIM_ICFilter = getFilter(inputFilterTicks);
566 TIM_ICInit(timHw->tim, &TIM_ICInitStructure);
567 // configure indirect channel
568 TIM_ICInitStructure.TIM_Channel = timHw->channel ^ TIM_Channel_2; // get opposite channel no
569 TIM_ICInitStructure.TIM_ICPolarity = directRising ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising;
570 TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_IndirectTI;
571 TIM_ICInit(timHw->tim, &TIM_ICInitStructure);
574 void timerChICPolarity(const timerHardware_t *timHw, bool polarityRising)
576 timCCER_t tmpccer = timHw->tim->CCER;
577 tmpccer &= ~(TIM_CCER_CC1P << timHw->channel);
578 tmpccer |= polarityRising ? (TIM_ICPolarity_Rising << timHw->channel) : (TIM_ICPolarity_Falling << timHw->channel);
579 timHw->tim->CCER = tmpccer;
582 volatile timCCR_t* timerChCCRHi(const timerHardware_t *timHw)
584 return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + (timHw->channel | TIM_Channel_2));
587 volatile timCCR_t* timerChCCRLo(const timerHardware_t *timHw)
589 return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + (timHw->channel & ~TIM_Channel_2));
592 volatile timCCR_t* timerChCCR(const timerHardware_t *timHw)
594 return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + timHw->channel);
597 void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHigh)
599 TIM_OCInitTypeDef TIM_OCInitStructure;
601 TIM_OCStructInit(&TIM_OCInitStructure);
602 if (outEnable) {
603 TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Inactive;
604 TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
605 if (timHw->output & TIMER_OUTPUT_INVERTED) {
606 stateHigh = !stateHigh;
608 TIM_OCInitStructure.TIM_OCPolarity = stateHigh ? TIM_OCPolarity_High : TIM_OCPolarity_Low;
609 } else {
610 TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Timing;
613 switch (timHw->channel) {
614 case TIM_Channel_1:
615 TIM_OC1Init(timHw->tim, &TIM_OCInitStructure);
616 TIM_OC1PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
617 break;
618 case TIM_Channel_2:
619 TIM_OC2Init(timHw->tim, &TIM_OCInitStructure);
620 TIM_OC2PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
621 break;
622 case TIM_Channel_3:
623 TIM_OC3Init(timHw->tim, &TIM_OCInitStructure);
624 TIM_OC3PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
625 break;
626 case TIM_Channel_4:
627 TIM_OC4Init(timHw->tim, &TIM_OCInitStructure);
628 TIM_OC4PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
629 break;
633 static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
635 uint16_t capture;
636 unsigned tim_status;
637 tim_status = tim->SR & tim->DIER;
638 #if 1
639 while (tim_status) {
640 // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
641 // current order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
642 unsigned bit = __builtin_clz(tim_status);
643 unsigned mask = ~(0x80000000 >> bit);
644 tim->SR = mask;
645 tim_status &= mask;
646 switch (bit) {
647 case __builtin_clz(TIM_IT_Update): {
649 if (timerConfig->forcedOverflowTimerValue != 0) {
650 capture = timerConfig->forcedOverflowTimerValue - 1;
651 timerConfig->forcedOverflowTimerValue = 0;
652 } else {
653 capture = tim->ARR;
656 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
657 while (cb) {
658 cb->fn(cb, capture);
659 cb = cb->next;
661 break;
663 case __builtin_clz(TIM_IT_CC1):
664 timerConfig->edgeCallback[0]->fn(timerConfig->edgeCallback[0], tim->CCR1);
665 break;
666 case __builtin_clz(TIM_IT_CC2):
667 timerConfig->edgeCallback[1]->fn(timerConfig->edgeCallback[1], tim->CCR2);
668 break;
669 case __builtin_clz(TIM_IT_CC3):
670 timerConfig->edgeCallback[2]->fn(timerConfig->edgeCallback[2], tim->CCR3);
671 break;
672 case __builtin_clz(TIM_IT_CC4):
673 timerConfig->edgeCallback[3]->fn(timerConfig->edgeCallback[3], tim->CCR4);
674 break;
677 #else
678 if (tim_status & (int)TIM_IT_Update) {
679 tim->SR = ~TIM_IT_Update;
680 capture = tim->ARR;
681 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
682 while (cb) {
683 cb->fn(cb, capture);
684 cb = cb->next;
687 if (tim_status & (int)TIM_IT_CC1) {
688 tim->SR = ~TIM_IT_CC1;
689 timerConfig->edgeCallback[0]->fn(timerConfig->edgeCallback[0], tim->CCR1);
691 if (tim_status & (int)TIM_IT_CC2) {
692 tim->SR = ~TIM_IT_CC2;
693 timerConfig->edgeCallback[1]->fn(timerConfig->edgeCallback[1], tim->CCR2);
695 if (tim_status & (int)TIM_IT_CC3) {
696 tim->SR = ~TIM_IT_CC3;
697 timerConfig->edgeCallback[2]->fn(timerConfig->edgeCallback[2], tim->CCR3);
699 if (tim_status & (int)TIM_IT_CC4) {
700 tim->SR = ~TIM_IT_CC4;
701 timerConfig->edgeCallback[3]->fn(timerConfig->edgeCallback[3], tim->CCR4);
703 #endif
706 static inline void timUpdateHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
708 uint16_t capture;
709 unsigned tim_status;
710 tim_status = tim->SR & tim->DIER;
711 while (tim_status) {
712 // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
713 // currrent order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
714 unsigned bit = __builtin_clz(tim_status);
715 unsigned mask = ~(0x80000000 >> bit);
716 tim->SR = mask;
717 tim_status &= mask;
718 switch (bit) {
719 case __builtin_clz(TIM_IT_Update): {
721 if (timerConfig->forcedOverflowTimerValue != 0) {
722 capture = timerConfig->forcedOverflowTimerValue - 1;
723 timerConfig->forcedOverflowTimerValue = 0;
724 } else {
725 capture = tim->ARR;
728 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
729 while (cb) {
730 cb->fn(cb, capture);
731 cb = cb->next;
733 break;
739 // handler for shared interrupts when both timers need to check status bits
740 #define _TIM_IRQ_HANDLER2(name, i, j) \
741 void name(void) \
743 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
744 timCCxHandler(TIM ## j, &timerConfig[TIMER_INDEX(j)]); \
745 } struct dummy
747 #define _TIM_IRQ_HANDLER(name, i) \
748 void name(void) \
750 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
751 } struct dummy
753 #define _TIM_IRQ_HANDLER_UPDATE_ONLY(name, i) \
754 void name(void) \
756 timUpdateHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
757 } struct dummy
759 #if USED_TIMERS & TIM_N(1)
760 _TIM_IRQ_HANDLER(TIM1_CC_IRQHandler, 1);
761 # if defined(STM32F40_41xxx) || defined (STM32F411xE)
762 # if USED_TIMERS & TIM_N(10)
763 _TIM_IRQ_HANDLER2(TIM1_UP_TIM10_IRQHandler, 1, 10); // both timers are in use
764 # else
765 _TIM_IRQ_HANDLER(TIM1_UP_TIM10_IRQHandler, 1); // timer10 is not used
766 # endif
767 # endif
768 #endif
769 #if USED_TIMERS & TIM_N(2)
770 _TIM_IRQ_HANDLER(TIM2_IRQHandler, 2);
771 #endif
772 #if USED_TIMERS & TIM_N(3)
773 _TIM_IRQ_HANDLER(TIM3_IRQHandler, 3);
774 #endif
775 #if USED_TIMERS & TIM_N(4)
776 _TIM_IRQ_HANDLER(TIM4_IRQHandler, 4);
777 #endif
778 #if USED_TIMERS & TIM_N(5)
779 _TIM_IRQ_HANDLER(TIM5_IRQHandler, 5);
780 #endif
782 #if USED_TIMERS & TIM_N(6)
783 # if !(defined(USE_PID_AUDIO) && (defined(STM32H7) || defined(STM32F7)))
784 _TIM_IRQ_HANDLER_UPDATE_ONLY(TIM6_IRQHandler, 6);
785 # endif
786 #endif
787 #if USED_TIMERS & TIM_N(7)
788 // The USB VCP_HAL driver conflicts with TIM7, see TIMx_IRQHandler in usbd_cdc_interface.h
789 # if !(defined(USE_VCP) && (defined(STM32F4) || defined(STM32G4) || defined(STM32H7)))
790 # if defined(STM32G4)
791 _TIM_IRQ_HANDLER_UPDATE_ONLY(TIM7_DAC_IRQHandler, 7);
792 # else
793 _TIM_IRQ_HANDLER_UPDATE_ONLY(TIM7_IRQHandler, 7);
794 # endif
795 # endif
796 #endif
798 #if USED_TIMERS & TIM_N(8)
799 _TIM_IRQ_HANDLER(TIM8_CC_IRQHandler, 8);
800 _TIM_IRQ_HANDLER(TIM8_UP_IRQHandler, 8);
801 # if defined(STM32F40_41xxx)
802 # if USED_TIMERS & TIM_N(13)
803 _TIM_IRQ_HANDLER2(TIM8_UP_TIM13_IRQHandler, 8, 13); // both timers are in use
804 # else
805 _TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler, 8); // timer13 is not used
806 # endif
807 # endif
808 # if defined (STM32F411xE)
809 # endif
810 #endif
811 #if USED_TIMERS & TIM_N(9)
812 _TIM_IRQ_HANDLER(TIM1_BRK_TIM9_IRQHandler, 9);
813 #endif
814 # if USED_TIMERS & TIM_N(11)
815 _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM11_IRQHandler, 11);
816 # endif
817 #if USED_TIMERS & TIM_N(12)
818 _TIM_IRQ_HANDLER(TIM8_BRK_TIM12_IRQHandler, 12);
819 #endif
820 #if USED_TIMERS & TIM_N(14)
821 _TIM_IRQ_HANDLER(TIM8_TRG_COM_TIM14_IRQHandler, 14);
822 #endif
823 #if USED_TIMERS & TIM_N(15)
824 _TIM_IRQ_HANDLER(TIM1_BRK_TIM15_IRQHandler, 15);
825 #endif
826 #if USED_TIMERS & TIM_N(17)
827 _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM17_IRQHandler, 17);
828 #endif
830 void timerInit(void)
832 memset(timerConfig, 0, sizeof(timerConfig));
834 #if defined(PARTIAL_REMAP_TIM3)
835 GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE);
836 #endif
838 /* enable the timer peripherals */
839 for (unsigned i = 0; i < TIMER_CHANNEL_COUNT; i++) {
840 RCC_ClockCmd(timerRCC(TIMER_HARDWARE[i].tim), ENABLE);
843 // initialize timer channel structures
844 for (unsigned i = 0; i < TIMER_CHANNEL_COUNT; i++) {
845 timerChannelInfo[i].type = TYPE_FREE;
848 for (unsigned i = 0; i < USED_TIMER_COUNT; i++) {
849 timerInfo[i].priority = ~0;
853 // finish configuring timers after allocation phase
854 // start timers
855 // TODO - Work in progress - initialization routine must be modified/verified to start correctly without timers
856 void timerStart(void)
858 #if 0
859 for (unsigned timer = 0; timer < USED_TIMER_COUNT; timer++) {
860 int priority = -1;
861 int irq = -1;
862 for (unsigned hwc = 0; hwc < TIMER_CHANNEL_COUNT; hwc++)
863 if ((timerChannelInfo[hwc].type != TYPE_FREE) && (TIMER_HARDWARE[hwc].tim == usedTimers[timer])) {
864 // TODO - move IRQ to timer info
865 irq = TIMER_HARDWARE[hwc].irq;
867 // TODO - aggregate required timer parameters
868 configTimeBase(usedTimers[timer], 0, 1);
869 TIM_Cmd(usedTimers[timer], ENABLE);
870 if (priority >= 0) { // maybe none of the channels was configured
871 NVIC_InitTypeDef NVIC_InitStructure;
873 NVIC_InitStructure.NVIC_IRQChannel = irq;
874 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_SPLIT_PRIORITY_BASE(priority);
875 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_SPLIT_PRIORITY_SUB(priority);
876 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
877 NVIC_Init(&NVIC_InitStructure);
880 #endif
884 * Force an overflow for a given timer.
885 * Saves the current value of the counter in the relevant timerConfig's forcedOverflowTimerValue variable.
886 * @param TIM_Typedef *tim The timer to overflow
887 * @return void
889 void timerForceOverflow(TIM_TypeDef *tim)
891 uint8_t timerIndex = lookupTimerIndex((const TIM_TypeDef *)tim);
893 ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
894 // Save the current count so that PPM reading will work on the same timer that was forced to overflow
895 timerConfig[timerIndex].forcedOverflowTimerValue = tim->CNT + 1;
897 // Force an overflow by setting the UG bit
898 tim->EGR |= TIM_EGR_UG;
902 #if !defined(USE_HAL_DRIVER)
903 void timerOCInit(TIM_TypeDef *tim, uint8_t channel, TIM_OCInitTypeDef *init)
905 switch (channel) {
906 case TIM_Channel_1:
907 TIM_OC1Init(tim, init);
908 break;
909 case TIM_Channel_2:
910 TIM_OC2Init(tim, init);
911 break;
912 case TIM_Channel_3:
913 TIM_OC3Init(tim, init);
914 break;
915 case TIM_Channel_4:
916 TIM_OC4Init(tim, init);
917 break;
921 void timerOCPreloadConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t preload)
923 switch (channel) {
924 case TIM_Channel_1:
925 TIM_OC1PreloadConfig(tim, preload);
926 break;
927 case TIM_Channel_2:
928 TIM_OC2PreloadConfig(tim, preload);
929 break;
930 case TIM_Channel_3:
931 TIM_OC3PreloadConfig(tim, preload);
932 break;
933 case TIM_Channel_4:
934 TIM_OC4PreloadConfig(tim, preload);
935 break;
938 #endif
940 volatile timCCR_t* timerCCR(TIM_TypeDef *tim, uint8_t channel)
942 return (volatile timCCR_t*)((volatile char*)&tim->CCR1 + channel);
945 #ifndef USE_HAL_DRIVER
946 uint16_t timerDmaSource(uint8_t channel)
948 switch (channel) {
949 case TIM_Channel_1:
950 return TIM_DMA_CC1;
951 case TIM_Channel_2:
952 return TIM_DMA_CC2;
953 case TIM_Channel_3:
954 return TIM_DMA_CC3;
955 case TIM_Channel_4:
956 return TIM_DMA_CC4;
958 return 0;
960 #endif
962 uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz)
964 return timerGetPrescalerByDesiredHertz(tim, MHZ_TO_HZ(mhz));
967 uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hz)
969 return (uint16_t)((timerClock(tim) / (prescaler + 1)) / hz);
972 uint16_t timerGetPrescalerByDesiredHertz(TIM_TypeDef *tim, uint32_t hz)
974 // protection here for desired hertz > SystemCoreClock???
975 if (hz > timerClock(tim)) {
976 return 0;
978 return (uint16_t)((timerClock(tim) + hz / 2 ) / hz) - 1;
980 #endif