Merge pull request #11297 from SteveCEvans/baro_state
[betaflight.git] / src / main / drivers / timer.c
blobd55094228ec5f829297f42e98f1707947bc78141
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(STM32F10X)
350 case TIM1_CC_IRQn:
351 timerNVICConfigure(TIM1_UP_IRQn);
352 break;
353 #endif
354 #if defined (STM32F40_41xxx) || defined(STM32F411xE)
355 case TIM1_CC_IRQn:
356 timerNVICConfigure(TIM1_UP_TIM10_IRQn);
357 break;
358 #endif
359 #if defined (STM32F40_41xxx)
360 case TIM8_CC_IRQn:
361 timerNVICConfigure(TIM8_UP_TIM13_IRQn);
362 break;
363 #endif
364 #ifdef STM32F303xC
365 case TIM1_CC_IRQn:
366 timerNVICConfigure(TIM1_UP_TIM16_IRQn);
367 break;
368 #endif
369 #if defined(STM32F10X_XL)
370 case TIM8_CC_IRQn:
371 timerNVICConfigure(TIM8_UP_IRQn);
372 break;
373 #endif
377 // allocate and configure timer channel. Timer priority is set to highest priority of its channels
378 void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority, uint8_t irq)
380 unsigned channel = timHw - TIMER_HARDWARE;
381 if (channel >= TIMER_CHANNEL_COUNT) {
382 return;
385 timerChannelInfo[channel].type = type;
386 unsigned timer = lookupTimerIndex(timHw->tim);
387 if (timer >= USED_TIMER_COUNT)
388 return;
389 if (irqPriority < timerInfo[timer].priority) {
390 // it would be better to set priority in the end, but current startup sequence is not ready
391 configTimeBase(usedTimers[timer], 0, 1);
392 TIM_Cmd(usedTimers[timer], ENABLE);
394 NVIC_InitTypeDef NVIC_InitStructure;
396 NVIC_InitStructure.NVIC_IRQChannel = irq;
397 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(irqPriority);
398 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(irqPriority);
399 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
400 NVIC_Init(&NVIC_InitStructure);
402 timerInfo[timer].priority = irqPriority;
406 void timerChCCHandlerInit(timerCCHandlerRec_t *self, timerCCHandlerCallback *fn)
408 self->fn = fn;
411 void timerChOvrHandlerInit(timerOvrHandlerRec_t *self, timerOvrHandlerCallback *fn)
413 self->fn = fn;
414 self->next = NULL;
417 // update overflow callback list
418 // some synchronization mechanism is neccesary to avoid disturbing other channels (BASEPRI used now)
419 static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, const TIM_TypeDef *tim) {
420 timerOvrHandlerRec_t **chain = &cfg->overflowCallbackActive;
421 ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
423 if (cfg->updateCallback) {
424 *chain = cfg->updateCallback;
425 chain = &cfg->updateCallback->next;
428 for (int i = 0; i < CC_CHANNELS_PER_TIMER; i++)
429 if (cfg->overflowCallback[i]) {
430 *chain = cfg->overflowCallback[i];
431 chain = &cfg->overflowCallback[i]->next;
433 *chain = NULL;
435 // enable or disable IRQ
436 TIM_ITConfig((TIM_TypeDef *)tim, TIM_IT_Update, cfg->overflowCallbackActive ? ENABLE : DISABLE);
439 // config edge and overflow callback for channel. Try to avoid per-channel overflowCallback, it is a bit expensive
440 void timerChConfigCallbacks(const timerHardware_t *timHw, timerCCHandlerRec_t *edgeCallback, timerOvrHandlerRec_t *overflowCallback)
442 uint8_t timerIndex = lookupTimerIndex(timHw->tim);
443 if (timerIndex >= USED_TIMER_COUNT) {
444 return;
446 uint8_t channelIndex = lookupChannelIndex(timHw->channel);
447 if (edgeCallback == NULL) // disable irq before changing callback to NULL
448 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), DISABLE);
449 // setup callback info
450 timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallback;
451 timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback;
452 // enable channel IRQ
453 if (edgeCallback)
454 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), ENABLE);
456 timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim);
459 void timerConfigUpdateCallback(const TIM_TypeDef *tim, timerOvrHandlerRec_t *updateCallback)
461 uint8_t timerIndex = lookupTimerIndex(tim);
462 if (timerIndex >= USED_TIMER_COUNT) {
463 return;
465 timerConfig[timerIndex].updateCallback = updateCallback;
466 timerChConfig_UpdateOverflow(&timerConfig[timerIndex], tim);
469 // configure callbacks for pair of channels (1+2 or 3+4).
470 // Hi(2,4) and Lo(1,3) callbacks are specified, it is not important which timHw channel is used.
471 // This is intended for dual capture mode (each channel handles one transition)
472 void timerChConfigCallbacksDual(const timerHardware_t *timHw, timerCCHandlerRec_t *edgeCallbackLo, timerCCHandlerRec_t *edgeCallbackHi, timerOvrHandlerRec_t *overflowCallback)
474 uint8_t timerIndex = lookupTimerIndex(timHw->tim);
475 if (timerIndex >= USED_TIMER_COUNT) {
476 return;
478 uint16_t chLo = timHw->channel & ~TIM_Channel_2; // lower channel
479 uint16_t chHi = timHw->channel | TIM_Channel_2; // upper channel
480 uint8_t channelIndex = lookupChannelIndex(chLo); // get index of lower channel
482 if (edgeCallbackLo == NULL) // disable irq before changing setting callback to NULL
483 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chLo), DISABLE);
484 if (edgeCallbackHi == NULL) // disable irq before changing setting callback to NULL
485 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chHi), DISABLE);
487 // setup callback info
488 timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallbackLo;
489 timerConfig[timerIndex].edgeCallback[channelIndex + 1] = edgeCallbackHi;
490 timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback;
491 timerConfig[timerIndex].overflowCallback[channelIndex + 1] = NULL;
493 // enable channel IRQs
494 if (edgeCallbackLo) {
495 TIM_ClearFlag(timHw->tim, TIM_IT_CCx(chLo));
496 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chLo), ENABLE);
498 if (edgeCallbackHi) {
499 TIM_ClearFlag(timHw->tim, TIM_IT_CCx(chHi));
500 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chHi), ENABLE);
503 timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim);
506 // enable/disable IRQ for low channel in dual configuration
507 void timerChITConfigDualLo(const timerHardware_t *timHw, FunctionalState newState) {
508 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel&~TIM_Channel_2), newState);
511 // enable or disable IRQ
512 void timerChITConfig(const timerHardware_t *timHw, FunctionalState newState)
514 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), newState);
517 // clear Compare/Capture flag for channel
518 void timerChClearCCFlag(const timerHardware_t *timHw)
520 TIM_ClearFlag(timHw->tim, TIM_IT_CCx(timHw->channel));
523 // configure timer channel GPIO mode
524 void timerChConfigGPIO(const timerHardware_t* timHw, ioConfig_t mode)
526 IOInit(IOGetByTag(timHw->tag), OWNER_TIMER, 0);
527 IOConfigGPIO(IOGetByTag(timHw->tag), mode);
530 // calculate input filter constant
531 // TODO - we should probably setup DTS to higher value to allow reasonable input filtering
532 // - notice that prescaler[0] does use DTS for sampling - the sequence won't be monotonous anymore
533 static unsigned getFilter(unsigned ticks)
535 static const unsigned ftab[16] = {
536 1*1, // fDTS !
537 1*2, 1*4, 1*8, // fCK_INT
538 2*6, 2*8, // fDTS/2
539 4*6, 4*8,
540 8*6, 8*8,
541 16*5, 16*6, 16*8,
542 32*5, 32*6, 32*8
544 for (unsigned i = 1; i < ARRAYLEN(ftab); i++)
545 if (ftab[i] > ticks)
546 return i - 1;
547 return 0x0f;
550 // Configure input capture
551 void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks)
553 TIM_ICInitTypeDef TIM_ICInitStructure;
555 TIM_ICStructInit(&TIM_ICInitStructure);
556 TIM_ICInitStructure.TIM_Channel = timHw->channel;
557 TIM_ICInitStructure.TIM_ICPolarity = polarityRising ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling;
558 TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
559 TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
560 TIM_ICInitStructure.TIM_ICFilter = getFilter(inputFilterTicks);
562 TIM_ICInit(timHw->tim, &TIM_ICInitStructure);
565 // configure dual channel input channel for capture
566 // polarity is for Low channel (capture order is always Lo - Hi)
567 void timerChConfigICDual(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks)
569 TIM_ICInitTypeDef TIM_ICInitStructure;
570 bool directRising = (timHw->channel & TIM_Channel_2) ? !polarityRising : polarityRising;
571 // configure direct channel
572 TIM_ICStructInit(&TIM_ICInitStructure);
574 TIM_ICInitStructure.TIM_Channel = timHw->channel;
575 TIM_ICInitStructure.TIM_ICPolarity = directRising ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling;
576 TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
577 TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
578 TIM_ICInitStructure.TIM_ICFilter = getFilter(inputFilterTicks);
579 TIM_ICInit(timHw->tim, &TIM_ICInitStructure);
580 // configure indirect channel
581 TIM_ICInitStructure.TIM_Channel = timHw->channel ^ TIM_Channel_2; // get opposite channel no
582 TIM_ICInitStructure.TIM_ICPolarity = directRising ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising;
583 TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_IndirectTI;
584 TIM_ICInit(timHw->tim, &TIM_ICInitStructure);
587 void timerChICPolarity(const timerHardware_t *timHw, bool polarityRising)
589 timCCER_t tmpccer = timHw->tim->CCER;
590 tmpccer &= ~(TIM_CCER_CC1P << timHw->channel);
591 tmpccer |= polarityRising ? (TIM_ICPolarity_Rising << timHw->channel) : (TIM_ICPolarity_Falling << timHw->channel);
592 timHw->tim->CCER = tmpccer;
595 volatile timCCR_t* timerChCCRHi(const timerHardware_t *timHw)
597 return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + (timHw->channel | TIM_Channel_2));
600 volatile timCCR_t* timerChCCRLo(const timerHardware_t *timHw)
602 return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + (timHw->channel & ~TIM_Channel_2));
605 volatile timCCR_t* timerChCCR(const timerHardware_t *timHw)
607 return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + timHw->channel);
610 void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHigh)
612 TIM_OCInitTypeDef TIM_OCInitStructure;
614 TIM_OCStructInit(&TIM_OCInitStructure);
615 if (outEnable) {
616 TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Inactive;
617 TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
618 if (timHw->output & TIMER_OUTPUT_INVERTED) {
619 stateHigh = !stateHigh;
621 TIM_OCInitStructure.TIM_OCPolarity = stateHigh ? TIM_OCPolarity_High : TIM_OCPolarity_Low;
622 } else {
623 TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Timing;
626 switch (timHw->channel) {
627 case TIM_Channel_1:
628 TIM_OC1Init(timHw->tim, &TIM_OCInitStructure);
629 TIM_OC1PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
630 break;
631 case TIM_Channel_2:
632 TIM_OC2Init(timHw->tim, &TIM_OCInitStructure);
633 TIM_OC2PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
634 break;
635 case TIM_Channel_3:
636 TIM_OC3Init(timHw->tim, &TIM_OCInitStructure);
637 TIM_OC3PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
638 break;
639 case TIM_Channel_4:
640 TIM_OC4Init(timHw->tim, &TIM_OCInitStructure);
641 TIM_OC4PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
642 break;
646 static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
648 uint16_t capture;
649 unsigned tim_status;
650 tim_status = tim->SR & tim->DIER;
651 #if 1
652 while (tim_status) {
653 // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
654 // current order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
655 unsigned bit = __builtin_clz(tim_status);
656 unsigned mask = ~(0x80000000 >> bit);
657 tim->SR = mask;
658 tim_status &= mask;
659 switch (bit) {
660 case __builtin_clz(TIM_IT_Update): {
662 if (timerConfig->forcedOverflowTimerValue != 0) {
663 capture = timerConfig->forcedOverflowTimerValue - 1;
664 timerConfig->forcedOverflowTimerValue = 0;
665 } else {
666 capture = tim->ARR;
669 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
670 while (cb) {
671 cb->fn(cb, capture);
672 cb = cb->next;
674 break;
676 case __builtin_clz(TIM_IT_CC1):
677 timerConfig->edgeCallback[0]->fn(timerConfig->edgeCallback[0], tim->CCR1);
678 break;
679 case __builtin_clz(TIM_IT_CC2):
680 timerConfig->edgeCallback[1]->fn(timerConfig->edgeCallback[1], tim->CCR2);
681 break;
682 case __builtin_clz(TIM_IT_CC3):
683 timerConfig->edgeCallback[2]->fn(timerConfig->edgeCallback[2], tim->CCR3);
684 break;
685 case __builtin_clz(TIM_IT_CC4):
686 timerConfig->edgeCallback[3]->fn(timerConfig->edgeCallback[3], tim->CCR4);
687 break;
690 #else
691 if (tim_status & (int)TIM_IT_Update) {
692 tim->SR = ~TIM_IT_Update;
693 capture = tim->ARR;
694 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
695 while (cb) {
696 cb->fn(cb, capture);
697 cb = cb->next;
700 if (tim_status & (int)TIM_IT_CC1) {
701 tim->SR = ~TIM_IT_CC1;
702 timerConfig->edgeCallback[0]->fn(timerConfig->edgeCallback[0], tim->CCR1);
704 if (tim_status & (int)TIM_IT_CC2) {
705 tim->SR = ~TIM_IT_CC2;
706 timerConfig->edgeCallback[1]->fn(timerConfig->edgeCallback[1], tim->CCR2);
708 if (tim_status & (int)TIM_IT_CC3) {
709 tim->SR = ~TIM_IT_CC3;
710 timerConfig->edgeCallback[2]->fn(timerConfig->edgeCallback[2], tim->CCR3);
712 if (tim_status & (int)TIM_IT_CC4) {
713 tim->SR = ~TIM_IT_CC4;
714 timerConfig->edgeCallback[3]->fn(timerConfig->edgeCallback[3], tim->CCR4);
716 #endif
719 static inline void timUpdateHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
721 uint16_t capture;
722 unsigned tim_status;
723 tim_status = tim->SR & tim->DIER;
724 while (tim_status) {
725 // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
726 // currrent order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
727 unsigned bit = __builtin_clz(tim_status);
728 unsigned mask = ~(0x80000000 >> bit);
729 tim->SR = mask;
730 tim_status &= mask;
731 switch (bit) {
732 case __builtin_clz(TIM_IT_Update): {
734 if (timerConfig->forcedOverflowTimerValue != 0) {
735 capture = timerConfig->forcedOverflowTimerValue - 1;
736 timerConfig->forcedOverflowTimerValue = 0;
737 } else {
738 capture = tim->ARR;
741 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
742 while (cb) {
743 cb->fn(cb, capture);
744 cb = cb->next;
746 break;
752 // handler for shared interrupts when both timers need to check status bits
753 #define _TIM_IRQ_HANDLER2(name, i, j) \
754 void name(void) \
756 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
757 timCCxHandler(TIM ## j, &timerConfig[TIMER_INDEX(j)]); \
758 } struct dummy
760 #define _TIM_IRQ_HANDLER(name, i) \
761 void name(void) \
763 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
764 } struct dummy
766 #define _TIM_IRQ_HANDLER_UPDATE_ONLY(name, i) \
767 void name(void) \
769 timUpdateHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
770 } struct dummy
772 #if USED_TIMERS & TIM_N(1)
773 _TIM_IRQ_HANDLER(TIM1_CC_IRQHandler, 1);
774 # if defined(STM32F10X)
775 _TIM_IRQ_HANDLER(TIM1_UP_IRQHandler, 1); // timer can't be shared
776 # endif
777 # if defined(STM32F40_41xxx) || defined (STM32F411xE)
778 # if USED_TIMERS & TIM_N(10)
779 _TIM_IRQ_HANDLER2(TIM1_UP_TIM10_IRQHandler, 1, 10); // both timers are in use
780 # else
781 _TIM_IRQ_HANDLER(TIM1_UP_TIM10_IRQHandler, 1); // timer10 is not used
782 # endif
783 # endif
784 # ifdef STM32F303xC
785 # if USED_TIMERS & TIM_N(16)
786 _TIM_IRQ_HANDLER2(TIM1_UP_TIM16_IRQHandler, 1, 16); // both timers are in use
787 # else
788 _TIM_IRQ_HANDLER(TIM1_UP_TIM16_IRQHandler, 1); // timer16 is not used
789 # endif
790 # endif
791 #endif
792 #if USED_TIMERS & TIM_N(2)
793 _TIM_IRQ_HANDLER(TIM2_IRQHandler, 2);
794 #endif
795 #if USED_TIMERS & TIM_N(3)
796 _TIM_IRQ_HANDLER(TIM3_IRQHandler, 3);
797 #endif
798 #if USED_TIMERS & TIM_N(4)
799 _TIM_IRQ_HANDLER(TIM4_IRQHandler, 4);
800 #endif
801 #if USED_TIMERS & TIM_N(5)
802 _TIM_IRQ_HANDLER(TIM5_IRQHandler, 5);
803 #endif
805 #if USED_TIMERS & TIM_N(6)
806 # if !(defined(USE_PID_AUDIO) && (defined(STM32H7) || defined(STM32F7)))
807 _TIM_IRQ_HANDLER_UPDATE_ONLY(TIM6_IRQHandler, 6);
808 # endif
809 #endif
810 #if USED_TIMERS & TIM_N(7)
811 // The USB VCP_HAL driver conflicts with TIM7, see TIMx_IRQHandler in usbd_cdc_interface.h
812 # if !(defined(USE_VCP) && (defined(STM32F4) || defined(STM32G4) || defined(STM32H7)))
813 # if defined(STM32G4)
814 _TIM_IRQ_HANDLER_UPDATE_ONLY(TIM7_DAC_IRQHandler, 7);
815 # else
816 _TIM_IRQ_HANDLER_UPDATE_ONLY(TIM7_IRQHandler, 7);
817 # endif
818 # endif
819 #endif
821 #if USED_TIMERS & TIM_N(8)
822 _TIM_IRQ_HANDLER(TIM8_CC_IRQHandler, 8);
823 # if defined(STM32F10X_XL)
824 _TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler, 8);
825 # else // f10x_hd, f30x
826 _TIM_IRQ_HANDLER(TIM8_UP_IRQHandler, 8);
827 # endif
828 # if defined(STM32F40_41xxx)
829 # if USED_TIMERS & TIM_N(13)
830 _TIM_IRQ_HANDLER2(TIM8_UP_TIM13_IRQHandler, 8, 13); // both timers are in use
831 # else
832 _TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler, 8); // timer13 is not used
833 # endif
834 # endif
835 # if defined (STM32F411xE)
836 # endif
837 #endif
838 #if USED_TIMERS & TIM_N(9)
839 _TIM_IRQ_HANDLER(TIM1_BRK_TIM9_IRQHandler, 9);
840 #endif
841 # if USED_TIMERS & TIM_N(11)
842 _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM11_IRQHandler, 11);
843 # endif
844 #if USED_TIMERS & TIM_N(12)
845 _TIM_IRQ_HANDLER(TIM8_BRK_TIM12_IRQHandler, 12);
846 #endif
847 #if USED_TIMERS & TIM_N(14)
848 _TIM_IRQ_HANDLER(TIM8_TRG_COM_TIM14_IRQHandler, 14);
849 #endif
850 #if USED_TIMERS & TIM_N(15)
851 _TIM_IRQ_HANDLER(TIM1_BRK_TIM15_IRQHandler, 15);
852 #endif
853 #if defined(STM32F303xC) && ((USED_TIMERS & (TIM_N(1)|TIM_N(16))) == (TIM_N(16)))
854 _TIM_IRQ_HANDLER(TIM1_UP_TIM16_IRQHandler, 16); // only timer16 is used, not timer1
855 #endif
856 #if USED_TIMERS & TIM_N(17)
857 _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM17_IRQHandler, 17);
858 #endif
860 void timerInit(void)
862 memset(timerConfig, 0, sizeof(timerConfig));
864 #if defined(PARTIAL_REMAP_TIM3)
865 GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE);
866 #endif
868 /* enable the timer peripherals */
869 for (unsigned i = 0; i < TIMER_CHANNEL_COUNT; i++) {
870 RCC_ClockCmd(timerRCC(TIMER_HARDWARE[i].tim), ENABLE);
873 // initialize timer channel structures
874 for (unsigned i = 0; i < TIMER_CHANNEL_COUNT; i++) {
875 timerChannelInfo[i].type = TYPE_FREE;
878 for (unsigned i = 0; i < USED_TIMER_COUNT; i++) {
879 timerInfo[i].priority = ~0;
883 // finish configuring timers after allocation phase
884 // start timers
885 // TODO - Work in progress - initialization routine must be modified/verified to start correctly without timers
886 void timerStart(void)
888 #if 0
889 for (unsigned timer = 0; timer < USED_TIMER_COUNT; timer++) {
890 int priority = -1;
891 int irq = -1;
892 for (unsigned hwc = 0; hwc < TIMER_CHANNEL_COUNT; hwc++)
893 if ((timerChannelInfo[hwc].type != TYPE_FREE) && (TIMER_HARDWARE[hwc].tim == usedTimers[timer])) {
894 // TODO - move IRQ to timer info
895 irq = TIMER_HARDWARE[hwc].irq;
897 // TODO - aggregate required timer parameters
898 configTimeBase(usedTimers[timer], 0, 1);
899 TIM_Cmd(usedTimers[timer], ENABLE);
900 if (priority >= 0) { // maybe none of the channels was configured
901 NVIC_InitTypeDef NVIC_InitStructure;
903 NVIC_InitStructure.NVIC_IRQChannel = irq;
904 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_SPLIT_PRIORITY_BASE(priority);
905 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_SPLIT_PRIORITY_SUB(priority);
906 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
907 NVIC_Init(&NVIC_InitStructure);
910 #endif
914 * Force an overflow for a given timer.
915 * Saves the current value of the counter in the relevant timerConfig's forcedOverflowTimerValue variable.
916 * @param TIM_Typedef *tim The timer to overflow
917 * @return void
919 void timerForceOverflow(TIM_TypeDef *tim)
921 uint8_t timerIndex = lookupTimerIndex((const TIM_TypeDef *)tim);
923 ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
924 // Save the current count so that PPM reading will work on the same timer that was forced to overflow
925 timerConfig[timerIndex].forcedOverflowTimerValue = tim->CNT + 1;
927 // Force an overflow by setting the UG bit
928 tim->EGR |= TIM_EGR_UG;
932 #if !defined(USE_HAL_DRIVER)
933 void timerOCInit(TIM_TypeDef *tim, uint8_t channel, TIM_OCInitTypeDef *init)
935 switch (channel) {
936 case TIM_Channel_1:
937 TIM_OC1Init(tim, init);
938 break;
939 case TIM_Channel_2:
940 TIM_OC2Init(tim, init);
941 break;
942 case TIM_Channel_3:
943 TIM_OC3Init(tim, init);
944 break;
945 case TIM_Channel_4:
946 TIM_OC4Init(tim, init);
947 break;
951 void timerOCPreloadConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t preload)
953 switch (channel) {
954 case TIM_Channel_1:
955 TIM_OC1PreloadConfig(tim, preload);
956 break;
957 case TIM_Channel_2:
958 TIM_OC2PreloadConfig(tim, preload);
959 break;
960 case TIM_Channel_3:
961 TIM_OC3PreloadConfig(tim, preload);
962 break;
963 case TIM_Channel_4:
964 TIM_OC4PreloadConfig(tim, preload);
965 break;
968 #endif
970 volatile timCCR_t* timerCCR(TIM_TypeDef *tim, uint8_t channel)
972 return (volatile timCCR_t*)((volatile char*)&tim->CCR1 + channel);
975 #ifndef USE_HAL_DRIVER
976 uint16_t timerDmaSource(uint8_t channel)
978 switch (channel) {
979 case TIM_Channel_1:
980 return TIM_DMA_CC1;
981 case TIM_Channel_2:
982 return TIM_DMA_CC2;
983 case TIM_Channel_3:
984 return TIM_DMA_CC3;
985 case TIM_Channel_4:
986 return TIM_DMA_CC4;
988 return 0;
990 #endif
992 uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz)
994 return timerGetPrescalerByDesiredHertz(tim, MHZ_TO_HZ(mhz));
997 uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hz)
999 return (uint16_t)((timerClock(tim) / (prescaler + 1)) / hz);
1002 uint16_t timerGetPrescalerByDesiredHertz(TIM_TypeDef *tim, uint32_t hz)
1004 // protection here for desired hertz > SystemCoreClock???
1005 if (hz > timerClock(tim)) {
1006 return 0;
1008 return (uint16_t)((timerClock(tim) + hz / 2 ) / hz) - 1;
1010 #endif