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)
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/>.
30 #include "build/atomic.h"
32 #include "common/utils.h"
34 #include "drivers/nvic.h"
36 #include "drivers/io.h"
38 #include "drivers/system.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):
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 timerCCHandlerRec_t
*edgeCallback
[CC_CHANNELS_PER_TIMER
];
60 timerOvrHandlerRec_t
*overflowCallback
[CC_CHANNELS_PER_TIMER
];
61 timerOvrHandlerRec_t
*overflowCallbackActive
; // null-terminated linkded list of active overflow callbacks
62 uint32_t forcedOverflowTimerValue
;
64 timerConfig_t timerConfig
[USED_TIMER_COUNT
];
70 timerChannelInfo_t timerChannelInfo
[TIMER_CHANNEL_COUNT
];
75 timerInfo_t timerInfo
[USED_TIMER_COUNT
];
77 // return index of timer in timer table. Lowest timer has index 0
78 #define TIMER_INDEX(i) BITCOUNT((TIM_N(i) - 1) & USED_TIMERS)
80 static uint8_t lookupTimerIndex(const TIM_TypeDef
*tim
)
82 #define _CASE_SHF 10 // amount we can safely shift timer address to the right. gcc will throw error if some timers overlap
83 #define _CASE_(tim, index) case ((unsigned)tim >> _CASE_SHF): return index; break
84 #define _CASE(i) _CASE_(TIM##i##_BASE, TIMER_INDEX(i))
86 // let gcc do the work, switch should be quite optimized
87 switch ((unsigned)tim
>> _CASE_SHF
) {
88 #if USED_TIMERS & TIM_N(1)
91 #if USED_TIMERS & TIM_N(2)
94 #if USED_TIMERS & TIM_N(3)
97 #if USED_TIMERS & TIM_N(4)
100 #if USED_TIMERS & TIM_N(5)
103 #if USED_TIMERS & TIM_N(6)
106 #if USED_TIMERS & TIM_N(7)
109 #if USED_TIMERS & TIM_N(8)
112 #if USED_TIMERS & TIM_N(9)
115 #if USED_TIMERS & TIM_N(10)
118 #if USED_TIMERS & TIM_N(11)
121 #if USED_TIMERS & TIM_N(12)
124 #if USED_TIMERS & TIM_N(13)
127 #if USED_TIMERS & TIM_N(14)
130 #if USED_TIMERS & TIM_N(15)
133 #if USED_TIMERS & TIM_N(16)
136 #if USED_TIMERS & TIM_N(17)
139 default: return ~1; // make sure final index is out of range
145 TIM_TypeDef
* const usedTimers
[USED_TIMER_COUNT
] = {
146 #define _DEF(i) TIM##i
148 #if USED_TIMERS & TIM_N(1)
151 #if USED_TIMERS & TIM_N(2)
154 #if USED_TIMERS & TIM_N(3)
157 #if USED_TIMERS & TIM_N(4)
160 #if USED_TIMERS & TIM_N(5)
163 #if USED_TIMERS & TIM_N(6)
166 #if USED_TIMERS & TIM_N(7)
169 #if USED_TIMERS & TIM_N(8)
172 #if USED_TIMERS & TIM_N(9)
175 #if USED_TIMERS & TIM_N(10)
178 #if USED_TIMERS & TIM_N(11)
181 #if USED_TIMERS & TIM_N(12)
184 #if USED_TIMERS & TIM_N(13)
187 #if USED_TIMERS & TIM_N(14)
190 #if USED_TIMERS & TIM_N(15)
193 #if USED_TIMERS & TIM_N(16)
196 #if USED_TIMERS & TIM_N(17)
202 // Map timer index to timer number (Straight copy of usedTimers array)
203 const int8_t timerNumbers
[USED_TIMER_COUNT
] = {
206 #if USED_TIMERS & TIM_N(1)
209 #if USED_TIMERS & TIM_N(2)
212 #if USED_TIMERS & TIM_N(3)
215 #if USED_TIMERS & TIM_N(4)
218 #if USED_TIMERS & TIM_N(5)
221 #if USED_TIMERS & TIM_N(6)
224 #if USED_TIMERS & TIM_N(7)
227 #if USED_TIMERS & TIM_N(8)
230 #if USED_TIMERS & TIM_N(9)
233 #if USED_TIMERS & TIM_N(10)
236 #if USED_TIMERS & TIM_N(11)
239 #if USED_TIMERS & TIM_N(12)
242 #if USED_TIMERS & TIM_N(13)
245 #if USED_TIMERS & TIM_N(14)
248 #if USED_TIMERS & TIM_N(15)
251 #if USED_TIMERS & TIM_N(16)
254 #if USED_TIMERS & TIM_N(17)
260 int8_t timerGetNumberByIndex(uint8_t index
)
262 if (index
< USED_TIMER_COUNT
) {
263 return timerNumbers
[index
];
269 int8_t timerGetTIMNumber(const TIM_TypeDef
*tim
)
271 const uint8_t index
= lookupTimerIndex(tim
);
273 return timerGetNumberByIndex(index
);
276 static inline uint8_t lookupChannelIndex(const uint16_t channel
)
281 uint8_t timerLookupChannelIndex(const uint16_t channel
)
283 return lookupChannelIndex(channel
);
286 rccPeriphTag_t
timerRCC(TIM_TypeDef
*tim
)
288 for (int i
= 0; i
< HARDWARE_TIMER_DEFINITION_COUNT
; i
++) {
289 if (timerDefinitions
[i
].TIMx
== tim
) {
290 return timerDefinitions
[i
].rcc
;
296 uint8_t timerInputIrq(TIM_TypeDef
*tim
)
298 for (int i
= 0; i
< HARDWARE_TIMER_DEFINITION_COUNT
; i
++) {
299 if (timerDefinitions
[i
].TIMx
== tim
) {
300 return timerDefinitions
[i
].inputIrq
;
306 void timerNVICConfigure(uint8_t irq
)
308 NVIC_InitTypeDef NVIC_InitStructure
;
310 NVIC_InitStructure
.NVIC_IRQChannel
= irq
;
311 NVIC_InitStructure
.NVIC_IRQChannelPreemptionPriority
= NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER
);
312 NVIC_InitStructure
.NVIC_IRQChannelSubPriority
= NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER
);
313 NVIC_InitStructure
.NVIC_IRQChannelCmd
= ENABLE
;
314 NVIC_Init(&NVIC_InitStructure
);
317 void configTimeBase(TIM_TypeDef
*tim
, uint16_t period
, uint32_t hz
)
319 TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure
;
321 TIM_TimeBaseStructInit(&TIM_TimeBaseStructure
);
322 TIM_TimeBaseStructure
.TIM_Period
= (period
- 1) & 0xFFFF; // AKA TIMx_ARR
324 // "The counter clock frequency (CK_CNT) is equal to f CK_PSC / (PSC[15:0] + 1)." - STM32F10x Reference Manual 14.4.11
325 // Thus for 1Mhz: 72000000 / 1000000 = 72, 72 - 1 = 71 = TIM_Prescaler
326 TIM_TimeBaseStructure
.TIM_Prescaler
= (timerClock(tim
) / hz
) - 1;
328 TIM_TimeBaseStructure
.TIM_ClockDivision
= 0;
329 TIM_TimeBaseStructure
.TIM_CounterMode
= TIM_CounterMode_Up
;
330 TIM_TimeBaseInit(tim
, &TIM_TimeBaseStructure
);
333 // old interface for PWM inputs. It should be replaced
334 void timerConfigure(const timerHardware_t
*timerHardwarePtr
, uint16_t period
, uint32_t hz
)
336 configTimeBase(timerHardwarePtr
->tim
, period
, hz
);
337 TIM_Cmd(timerHardwarePtr
->tim
, ENABLE
);
339 uint8_t irq
= timerInputIrq(timerHardwarePtr
->tim
);
340 timerNVICConfigure(irq
);
341 // HACK - enable second IRQ on timers that need it
343 #if defined(STM32F10X)
345 timerNVICConfigure(TIM1_UP_IRQn
);
348 #if defined (STM32F40_41xxx) || defined(STM32F411xE)
350 timerNVICConfigure(TIM1_UP_TIM10_IRQn
);
353 #if defined (STM32F40_41xxx)
355 timerNVICConfigure(TIM8_UP_TIM13_IRQn
);
360 timerNVICConfigure(TIM1_UP_TIM16_IRQn
);
363 #if defined(STM32F10X_XL)
365 timerNVICConfigure(TIM8_UP_IRQn
);
371 // allocate and configure timer channel. Timer priority is set to highest priority of its channels
372 void timerChInit(const timerHardware_t
*timHw
, channelType_t type
, int irqPriority
, uint8_t irq
)
374 unsigned channel
= timHw
- TIMER_HARDWARE
;
375 if (channel
>= TIMER_CHANNEL_COUNT
) {
379 timerChannelInfo
[channel
].type
= type
;
380 unsigned timer
= lookupTimerIndex(timHw
->tim
);
381 if (timer
>= USED_TIMER_COUNT
)
383 if (irqPriority
< timerInfo
[timer
].priority
) {
384 // it would be better to set priority in the end, but current startup sequence is not ready
385 configTimeBase(usedTimers
[timer
], 0, 1);
386 TIM_Cmd(usedTimers
[timer
], ENABLE
);
388 NVIC_InitTypeDef NVIC_InitStructure
;
390 NVIC_InitStructure
.NVIC_IRQChannel
= irq
;
391 NVIC_InitStructure
.NVIC_IRQChannelPreemptionPriority
= NVIC_PRIORITY_BASE(irqPriority
);
392 NVIC_InitStructure
.NVIC_IRQChannelSubPriority
= NVIC_PRIORITY_SUB(irqPriority
);
393 NVIC_InitStructure
.NVIC_IRQChannelCmd
= ENABLE
;
394 NVIC_Init(&NVIC_InitStructure
);
396 timerInfo
[timer
].priority
= irqPriority
;
400 void timerChCCHandlerInit(timerCCHandlerRec_t
*self
, timerCCHandlerCallback
*fn
)
405 void timerChOvrHandlerInit(timerOvrHandlerRec_t
*self
, timerOvrHandlerCallback
*fn
)
411 // update overflow callback list
412 // some synchronization mechanism is neccesary to avoid disturbing other channels (BASEPRI used now)
413 static void timerChConfig_UpdateOverflow(timerConfig_t
*cfg
, TIM_TypeDef
*tim
) {
414 timerOvrHandlerRec_t
**chain
= &cfg
->overflowCallbackActive
;
415 ATOMIC_BLOCK(NVIC_PRIO_TIMER
) {
416 for (int i
= 0; i
< CC_CHANNELS_PER_TIMER
; i
++)
417 if (cfg
->overflowCallback
[i
]) {
418 *chain
= cfg
->overflowCallback
[i
];
419 chain
= &cfg
->overflowCallback
[i
]->next
;
423 // enable or disable IRQ
424 TIM_ITConfig(tim
, TIM_IT_Update
, cfg
->overflowCallbackActive
? ENABLE
: DISABLE
);
427 // config edge and overflow callback for channel. Try to avoid overflowCallback, it is a bit expensive
428 void timerChConfigCallbacks(const timerHardware_t
*timHw
, timerCCHandlerRec_t
*edgeCallback
, timerOvrHandlerRec_t
*overflowCallback
)
430 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
431 if (timerIndex
>= USED_TIMER_COUNT
) {
434 uint8_t channelIndex
= lookupChannelIndex(timHw
->channel
);
435 if (edgeCallback
== NULL
) // disable irq before changing callback to NULL
436 TIM_ITConfig(timHw
->tim
, TIM_IT_CCx(timHw
->channel
), DISABLE
);
437 // setup callback info
438 timerConfig
[timerIndex
].edgeCallback
[channelIndex
] = edgeCallback
;
439 timerConfig
[timerIndex
].overflowCallback
[channelIndex
] = overflowCallback
;
440 // enable channel IRQ
442 TIM_ITConfig(timHw
->tim
, TIM_IT_CCx(timHw
->channel
), ENABLE
);
444 timerChConfig_UpdateOverflow(&timerConfig
[timerIndex
], timHw
->tim
);
447 // configure callbacks for pair of channels (1+2 or 3+4).
448 // Hi(2,4) and Lo(1,3) callbacks are specified, it is not important which timHw channel is used.
449 // This is intended for dual capture mode (each channel handles one transition)
450 void timerChConfigCallbacksDual(const timerHardware_t
*timHw
, timerCCHandlerRec_t
*edgeCallbackLo
, timerCCHandlerRec_t
*edgeCallbackHi
, timerOvrHandlerRec_t
*overflowCallback
)
452 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
453 if (timerIndex
>= USED_TIMER_COUNT
) {
456 uint16_t chLo
= timHw
->channel
& ~TIM_Channel_2
; // lower channel
457 uint16_t chHi
= timHw
->channel
| TIM_Channel_2
; // upper channel
458 uint8_t channelIndex
= lookupChannelIndex(chLo
); // get index of lower channel
460 if (edgeCallbackLo
== NULL
) // disable irq before changing setting callback to NULL
461 TIM_ITConfig(timHw
->tim
, TIM_IT_CCx(chLo
), DISABLE
);
462 if (edgeCallbackHi
== NULL
) // disable irq before changing setting callback to NULL
463 TIM_ITConfig(timHw
->tim
, TIM_IT_CCx(chHi
), DISABLE
);
465 // setup callback info
466 timerConfig
[timerIndex
].edgeCallback
[channelIndex
] = edgeCallbackLo
;
467 timerConfig
[timerIndex
].edgeCallback
[channelIndex
+ 1] = edgeCallbackHi
;
468 timerConfig
[timerIndex
].overflowCallback
[channelIndex
] = overflowCallback
;
469 timerConfig
[timerIndex
].overflowCallback
[channelIndex
+ 1] = NULL
;
471 // enable channel IRQs
472 if (edgeCallbackLo
) {
473 TIM_ClearFlag(timHw
->tim
, TIM_IT_CCx(chLo
));
474 TIM_ITConfig(timHw
->tim
, TIM_IT_CCx(chLo
), ENABLE
);
476 if (edgeCallbackHi
) {
477 TIM_ClearFlag(timHw
->tim
, TIM_IT_CCx(chHi
));
478 TIM_ITConfig(timHw
->tim
, TIM_IT_CCx(chHi
), ENABLE
);
481 timerChConfig_UpdateOverflow(&timerConfig
[timerIndex
], timHw
->tim
);
484 // enable/disable IRQ for low channel in dual configuration
485 void timerChITConfigDualLo(const timerHardware_t
*timHw
, FunctionalState newState
) {
486 TIM_ITConfig(timHw
->tim
, TIM_IT_CCx(timHw
->channel
&~TIM_Channel_2
), newState
);
489 // enable or disable IRQ
490 void timerChITConfig(const timerHardware_t
*timHw
, FunctionalState newState
)
492 TIM_ITConfig(timHw
->tim
, TIM_IT_CCx(timHw
->channel
), newState
);
495 // clear Compare/Capture flag for channel
496 void timerChClearCCFlag(const timerHardware_t
*timHw
)
498 TIM_ClearFlag(timHw
->tim
, TIM_IT_CCx(timHw
->channel
));
501 // configure timer channel GPIO mode
502 void timerChConfigGPIO(const timerHardware_t
* timHw
, ioConfig_t mode
)
504 IOInit(IOGetByTag(timHw
->tag
), OWNER_TIMER
, 0);
505 IOConfigGPIO(IOGetByTag(timHw
->tag
), mode
);
508 // calculate input filter constant
509 // TODO - we should probably setup DTS to higher value to allow reasonable input filtering
510 // - notice that prescaler[0] does use DTS for sampling - the sequence won't be monotonous anymore
511 static unsigned getFilter(unsigned ticks
)
513 static const unsigned ftab
[16] = {
515 1*2, 1*4, 1*8, // fCK_INT
522 for (unsigned i
= 1; i
< ARRAYLEN(ftab
); i
++)
528 // Configure input captupre
529 void timerChConfigIC(const timerHardware_t
*timHw
, bool polarityRising
, unsigned inputFilterTicks
)
531 TIM_ICInitTypeDef TIM_ICInitStructure
;
533 TIM_ICStructInit(&TIM_ICInitStructure
);
534 TIM_ICInitStructure
.TIM_Channel
= timHw
->channel
;
535 TIM_ICInitStructure
.TIM_ICPolarity
= polarityRising
? TIM_ICPolarity_Rising
: TIM_ICPolarity_Falling
;
536 TIM_ICInitStructure
.TIM_ICSelection
= TIM_ICSelection_DirectTI
;
537 TIM_ICInitStructure
.TIM_ICPrescaler
= TIM_ICPSC_DIV1
;
538 TIM_ICInitStructure
.TIM_ICFilter
= getFilter(inputFilterTicks
);
540 TIM_ICInit(timHw
->tim
, &TIM_ICInitStructure
);
543 // configure dual channel input channel for capture
544 // polarity is for Low channel (capture order is always Lo - Hi)
545 void timerChConfigICDual(const timerHardware_t
*timHw
, bool polarityRising
, unsigned inputFilterTicks
)
547 TIM_ICInitTypeDef TIM_ICInitStructure
;
548 bool directRising
= (timHw
->channel
& TIM_Channel_2
) ? !polarityRising
: polarityRising
;
549 // configure direct channel
550 TIM_ICStructInit(&TIM_ICInitStructure
);
552 TIM_ICInitStructure
.TIM_Channel
= timHw
->channel
;
553 TIM_ICInitStructure
.TIM_ICPolarity
= directRising
? TIM_ICPolarity_Rising
: TIM_ICPolarity_Falling
;
554 TIM_ICInitStructure
.TIM_ICSelection
= TIM_ICSelection_DirectTI
;
555 TIM_ICInitStructure
.TIM_ICPrescaler
= TIM_ICPSC_DIV1
;
556 TIM_ICInitStructure
.TIM_ICFilter
= getFilter(inputFilterTicks
);
557 TIM_ICInit(timHw
->tim
, &TIM_ICInitStructure
);
558 // configure indirect channel
559 TIM_ICInitStructure
.TIM_Channel
= timHw
->channel
^ TIM_Channel_2
; // get opposite channel no
560 TIM_ICInitStructure
.TIM_ICPolarity
= directRising
? TIM_ICPolarity_Falling
: TIM_ICPolarity_Rising
;
561 TIM_ICInitStructure
.TIM_ICSelection
= TIM_ICSelection_IndirectTI
;
562 TIM_ICInit(timHw
->tim
, &TIM_ICInitStructure
);
565 void timerChICPolarity(const timerHardware_t
*timHw
, bool polarityRising
)
567 timCCER_t tmpccer
= timHw
->tim
->CCER
;
568 tmpccer
&= ~(TIM_CCER_CC1P
<< timHw
->channel
);
569 tmpccer
|= polarityRising
? (TIM_ICPolarity_Rising
<< timHw
->channel
) : (TIM_ICPolarity_Falling
<< timHw
->channel
);
570 timHw
->tim
->CCER
= tmpccer
;
573 volatile timCCR_t
* timerChCCRHi(const timerHardware_t
*timHw
)
575 return (volatile timCCR_t
*)((volatile char*)&timHw
->tim
->CCR1
+ (timHw
->channel
| TIM_Channel_2
));
578 volatile timCCR_t
* timerChCCRLo(const timerHardware_t
*timHw
)
580 return (volatile timCCR_t
*)((volatile char*)&timHw
->tim
->CCR1
+ (timHw
->channel
& ~TIM_Channel_2
));
583 volatile timCCR_t
* timerChCCR(const timerHardware_t
*timHw
)
585 return (volatile timCCR_t
*)((volatile char*)&timHw
->tim
->CCR1
+ timHw
->channel
);
588 void timerChConfigOC(const timerHardware_t
* timHw
, bool outEnable
, bool stateHigh
)
590 TIM_OCInitTypeDef TIM_OCInitStructure
;
592 TIM_OCStructInit(&TIM_OCInitStructure
);
594 TIM_OCInitStructure
.TIM_OCMode
= TIM_OCMode_Inactive
;
595 TIM_OCInitStructure
.TIM_OutputState
= TIM_OutputState_Enable
;
596 if (timHw
->output
& TIMER_OUTPUT_INVERTED
) {
597 stateHigh
= !stateHigh
;
599 TIM_OCInitStructure
.TIM_OCPolarity
= stateHigh
? TIM_OCPolarity_High
: TIM_OCPolarity_Low
;
601 TIM_OCInitStructure
.TIM_OCMode
= TIM_OCMode_Timing
;
604 switch (timHw
->channel
) {
606 TIM_OC1Init(timHw
->tim
, &TIM_OCInitStructure
);
607 TIM_OC1PreloadConfig(timHw
->tim
, TIM_OCPreload_Disable
);
610 TIM_OC2Init(timHw
->tim
, &TIM_OCInitStructure
);
611 TIM_OC2PreloadConfig(timHw
->tim
, TIM_OCPreload_Disable
);
614 TIM_OC3Init(timHw
->tim
, &TIM_OCInitStructure
);
615 TIM_OC3PreloadConfig(timHw
->tim
, TIM_OCPreload_Disable
);
618 TIM_OC4Init(timHw
->tim
, &TIM_OCInitStructure
);
619 TIM_OC4PreloadConfig(timHw
->tim
, TIM_OCPreload_Disable
);
624 static void timCCxHandler(TIM_TypeDef
*tim
, timerConfig_t
*timerConfig
)
628 tim_status
= tim
->SR
& tim
->DIER
;
631 // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
632 // currrent order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
633 unsigned bit
= __builtin_clz(tim_status
);
634 unsigned mask
= ~(0x80000000 >> bit
);
638 case __builtin_clz(TIM_IT_Update
): {
640 if (timerConfig
->forcedOverflowTimerValue
!= 0) {
641 capture
= timerConfig
->forcedOverflowTimerValue
- 1;
642 timerConfig
->forcedOverflowTimerValue
= 0;
647 timerOvrHandlerRec_t
*cb
= timerConfig
->overflowCallbackActive
;
654 case __builtin_clz(TIM_IT_CC1
):
655 timerConfig
->edgeCallback
[0]->fn(timerConfig
->edgeCallback
[0], tim
->CCR1
);
657 case __builtin_clz(TIM_IT_CC2
):
658 timerConfig
->edgeCallback
[1]->fn(timerConfig
->edgeCallback
[1], tim
->CCR2
);
660 case __builtin_clz(TIM_IT_CC3
):
661 timerConfig
->edgeCallback
[2]->fn(timerConfig
->edgeCallback
[2], tim
->CCR3
);
663 case __builtin_clz(TIM_IT_CC4
):
664 timerConfig
->edgeCallback
[3]->fn(timerConfig
->edgeCallback
[3], tim
->CCR4
);
669 if (tim_status
& (int)TIM_IT_Update
) {
670 tim
->SR
= ~TIM_IT_Update
;
672 timerOvrHandlerRec_t
*cb
= timerConfig
->overflowCallbackActive
;
678 if (tim_status
& (int)TIM_IT_CC1
) {
679 tim
->SR
= ~TIM_IT_CC1
;
680 timerConfig
->edgeCallback
[0]->fn(timerConfig
->edgeCallback
[0], tim
->CCR1
);
682 if (tim_status
& (int)TIM_IT_CC2
) {
683 tim
->SR
= ~TIM_IT_CC2
;
684 timerConfig
->edgeCallback
[1]->fn(timerConfig
->edgeCallback
[1], tim
->CCR2
);
686 if (tim_status
& (int)TIM_IT_CC3
) {
687 tim
->SR
= ~TIM_IT_CC3
;
688 timerConfig
->edgeCallback
[2]->fn(timerConfig
->edgeCallback
[2], tim
->CCR3
);
690 if (tim_status
& (int)TIM_IT_CC4
) {
691 tim
->SR
= ~TIM_IT_CC4
;
692 timerConfig
->edgeCallback
[3]->fn(timerConfig
->edgeCallback
[3], tim
->CCR4
);
697 // handler for shared interrupts when both timers need to check status bits
698 #define _TIM_IRQ_HANDLER2(name, i, j) \
701 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
702 timCCxHandler(TIM ## j, &timerConfig[TIMER_INDEX(j)]); \
705 #define _TIM_IRQ_HANDLER(name, i) \
708 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
711 #if USED_TIMERS & TIM_N(1)
712 _TIM_IRQ_HANDLER(TIM1_CC_IRQHandler
, 1);
713 # if defined(STM32F10X)
714 _TIM_IRQ_HANDLER(TIM1_UP_IRQHandler
, 1); // timer can't be shared
716 # if defined(STM32F40_41xxx) || defined (STM32F411xE)
717 # if USED_TIMERS & TIM_N(10)
718 _TIM_IRQ_HANDLER2(TIM1_UP_TIM10_IRQHandler
, 1, 10); // both timers are in use
720 _TIM_IRQ_HANDLER(TIM1_UP_TIM10_IRQHandler
, 1); // timer10 is not used
724 # if USED_TIMERS & TIM_N(16)
725 _TIM_IRQ_HANDLER2(TIM1_UP_TIM16_IRQHandler
, 1, 16); // both timers are in use
727 _TIM_IRQ_HANDLER(TIM1_UP_TIM16_IRQHandler
, 1); // timer16 is not used
731 #if USED_TIMERS & TIM_N(2)
732 _TIM_IRQ_HANDLER(TIM2_IRQHandler
, 2);
734 #if USED_TIMERS & TIM_N(3)
735 _TIM_IRQ_HANDLER(TIM3_IRQHandler
, 3);
737 #if USED_TIMERS & TIM_N(4)
738 _TIM_IRQ_HANDLER(TIM4_IRQHandler
, 4);
740 #if USED_TIMERS & TIM_N(5)
741 _TIM_IRQ_HANDLER(TIM5_IRQHandler
, 5);
743 #if USED_TIMERS & TIM_N(8)
744 _TIM_IRQ_HANDLER(TIM8_CC_IRQHandler
, 8);
745 # if defined(STM32F10X_XL)
746 _TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler
, 8);
747 # else // f10x_hd, f30x
748 _TIM_IRQ_HANDLER(TIM8_UP_IRQHandler
, 8);
750 # if defined(STM32F40_41xxx)
751 # if USED_TIMERS & TIM_N(13)
752 _TIM_IRQ_HANDLER2(TIM8_UP_TIM13_IRQHandler
, 8, 13); // both timers are in use
754 _TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler
, 8); // timer13 is not used
757 # if defined (STM32F411xE)
760 #if USED_TIMERS & TIM_N(9)
761 _TIM_IRQ_HANDLER(TIM1_BRK_TIM9_IRQHandler
, 9);
763 # if USED_TIMERS & TIM_N(11)
764 _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM11_IRQHandler
, 11);
766 #if USED_TIMERS & TIM_N(12)
767 _TIM_IRQ_HANDLER(TIM8_BRK_TIM12_IRQHandler
, 12);
769 #if USED_TIMERS & TIM_N(14)
770 _TIM_IRQ_HANDLER(TIM8_TRG_COM_TIM14_IRQHandler
, 14);
772 #if USED_TIMERS & TIM_N(15)
773 _TIM_IRQ_HANDLER(TIM1_BRK_TIM15_IRQHandler
, 15);
775 #if defined(STM32F303xC) && ((USED_TIMERS & (TIM_N(1)|TIM_N(16))) == (TIM_N(16)))
776 _TIM_IRQ_HANDLER(TIM1_UP_TIM16_IRQHandler
, 16); // only timer16 is used, not timer1
778 #if USED_TIMERS & TIM_N(17)
779 _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM17_IRQHandler
, 17);
784 memset(timerConfig
, 0, sizeof (timerConfig
));
786 #if defined(PARTIAL_REMAP_TIM3)
787 GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3
, ENABLE
);
790 /* enable the timer peripherals */
791 for (unsigned i
= 0; i
< TIMER_CHANNEL_COUNT
; i
++) {
792 RCC_ClockCmd(timerRCC(TIMER_HARDWARE
[i
].tim
), ENABLE
);
795 // initialize timer channel structures
796 for (unsigned i
= 0; i
< TIMER_CHANNEL_COUNT
; i
++) {
797 timerChannelInfo
[i
].type
= TYPE_FREE
;
800 for (unsigned i
= 0; i
< USED_TIMER_COUNT
; i
++) {
801 timerInfo
[i
].priority
= ~0;
805 // finish configuring timers after allocation phase
807 // TODO - Work in progress - initialization routine must be modified/verified to start correctly without timers
808 void timerStart(void)
811 for (unsigned timer
= 0; timer
< USED_TIMER_COUNT
; timer
++) {
814 for (unsigned hwc
= 0; hwc
< TIMER_CHANNEL_COUNT
; hwc
++)
815 if ((timerChannelInfo
[hwc
].type
!= TYPE_FREE
) && (TIMER_HARDWARE
[hwc
].tim
== usedTimers
[timer
])) {
816 // TODO - move IRQ to timer info
817 irq
= TIMER_HARDWARE
[hwc
].irq
;
819 // TODO - aggregate required timer paramaters
820 configTimeBase(usedTimers
[timer
], 0, 1);
821 TIM_Cmd(usedTimers
[timer
], ENABLE
);
822 if (priority
>= 0) { // maybe none of the channels was configured
823 NVIC_InitTypeDef NVIC_InitStructure
;
825 NVIC_InitStructure
.NVIC_IRQChannel
= irq
;
826 NVIC_InitStructure
.NVIC_IRQChannelPreemptionPriority
= NVIC_SPLIT_PRIORITY_BASE(priority
);
827 NVIC_InitStructure
.NVIC_IRQChannelSubPriority
= NVIC_SPLIT_PRIORITY_SUB(priority
);
828 NVIC_InitStructure
.NVIC_IRQChannelCmd
= ENABLE
;
829 NVIC_Init(&NVIC_InitStructure
);
836 * Force an overflow for a given timer.
837 * Saves the current value of the counter in the relevant timerConfig's forcedOverflowTimerValue variable.
838 * @param TIM_Typedef *tim The timer to overflow
841 void timerForceOverflow(TIM_TypeDef
*tim
)
843 uint8_t timerIndex
= lookupTimerIndex((const TIM_TypeDef
*)tim
);
845 ATOMIC_BLOCK(NVIC_PRIO_TIMER
) {
846 // Save the current count so that PPM reading will work on the same timer that was forced to overflow
847 timerConfig
[timerIndex
].forcedOverflowTimerValue
= tim
->CNT
+ 1;
849 // Force an overflow by setting the UG bit
850 tim
->EGR
|= TIM_EGR_UG
;
854 #if !defined(USE_HAL_DRIVER)
855 void timerOCInit(TIM_TypeDef
*tim
, uint8_t channel
, TIM_OCInitTypeDef
*init
)
859 TIM_OC1Init(tim
, init
);
862 TIM_OC2Init(tim
, init
);
865 TIM_OC3Init(tim
, init
);
868 TIM_OC4Init(tim
, init
);
873 void timerOCPreloadConfig(TIM_TypeDef
*tim
, uint8_t channel
, uint16_t preload
)
877 TIM_OC1PreloadConfig(tim
, preload
);
880 TIM_OC2PreloadConfig(tim
, preload
);
883 TIM_OC3PreloadConfig(tim
, preload
);
886 TIM_OC4PreloadConfig(tim
, preload
);
892 volatile timCCR_t
* timerCCR(TIM_TypeDef
*tim
, uint8_t channel
)
894 return (volatile timCCR_t
*)((volatile char*)&tim
->CCR1
+ channel
);
897 #ifndef USE_HAL_DRIVER
898 uint16_t timerDmaSource(uint8_t channel
)
914 uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef
*tim
, uint16_t mhz
)
916 return timerGetPrescalerByDesiredHertz(tim
, MHZ_TO_HZ(mhz
));
919 uint16_t timerGetPeriodByPrescaler(TIM_TypeDef
*tim
, uint16_t prescaler
, uint32_t hz
)
921 return (uint16_t)((timerClock(tim
) / (prescaler
+ 1)) / hz
);
924 uint16_t timerGetPrescalerByDesiredHertz(TIM_TypeDef
*tim
, uint32_t hz
)
926 // protection here for desired hertz > SystemCoreClock???
927 if (hz
> timerClock(tim
)) {
930 return (uint16_t)((timerClock(tim
) + hz
/ 2 ) / hz
) - 1;