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/>.
24 #include "build/atomic.h"
26 #include "common/utils.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):
48 /// TODO: HAL in a lot af calls lookupTimerIndex is used. Instead of passing the timer instance the index should be passed.
50 #define USED_TIMER_COUNT BITCOUNT(USED_TIMERS)
51 #define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4
53 #define TIM_IT_CCx(ch) (TIM_IT_CC1 << ((ch) / 4))
55 typedef struct timerConfig_s
{
56 timerCCHandlerRec_t
*edgeCallback
[CC_CHANNELS_PER_TIMER
];
57 timerOvrHandlerRec_t
*overflowCallback
[CC_CHANNELS_PER_TIMER
];
58 timerOvrHandlerRec_t
*overflowCallbackActive
; // null-terminated linkded list of active overflow callbacks
59 uint32_t forcedOverflowTimerValue
;
61 timerConfig_t timerConfig
[USED_TIMER_COUNT
+1];
66 timerChannelInfo_t timerChannelInfo
[USABLE_TIMER_CHANNEL_COUNT
];
71 timerInfo_t timerInfo
[USED_TIMER_COUNT
+1];
75 TIM_HandleTypeDef Handle
;
77 timerHandle_t timerHandle
[USED_TIMER_COUNT
+1];
79 // return index of timer in timer table. Lowest timer has index 0
80 #define TIMER_INDEX(i) BITCOUNT((TIM_N(i) - 1) & USED_TIMERS)
82 static uint8_t lookupTimerIndex(const TIM_TypeDef
*tim
)
84 #define _CASE_SHF 10 // amount we can safely shift timer address to the right. gcc will throw error if some timers overlap
85 #define _CASE_(tim, index) case ((unsigned)tim >> _CASE_SHF): return index; break
86 #define _CASE(i) _CASE_(TIM##i##_BASE, TIMER_INDEX(i))
88 // let gcc do the work, switch should be quite optimized
89 switch((unsigned)tim
>> _CASE_SHF
) {
90 #if USED_TIMERS & TIM_N(1)
93 #if USED_TIMERS & TIM_N(2)
96 #if USED_TIMERS & TIM_N(3)
99 #if USED_TIMERS & TIM_N(4)
102 #if USED_TIMERS & TIM_N(5)
105 #if USED_TIMERS & TIM_N(6)
108 #if USED_TIMERS & TIM_N(7)
111 #if USED_TIMERS & TIM_N(8)
114 #if USED_TIMERS & TIM_N(9)
117 #if USED_TIMERS & TIM_N(10)
120 #if USED_TIMERS & TIM_N(11)
123 #if USED_TIMERS & TIM_N(12)
126 #if USED_TIMERS & TIM_N(13)
129 #if USED_TIMERS & TIM_N(14)
132 #if USED_TIMERS & TIM_N(15)
135 #if USED_TIMERS & TIM_N(16)
138 #if USED_TIMERS & TIM_N(17)
141 default: return ~1; // make sure final index is out of range
147 TIM_TypeDef
* const usedTimers
[USED_TIMER_COUNT
] = {
148 #define _DEF(i) TIM##i
150 #if USED_TIMERS & TIM_N(1)
153 #if USED_TIMERS & TIM_N(2)
156 #if USED_TIMERS & TIM_N(3)
159 #if USED_TIMERS & TIM_N(4)
162 #if USED_TIMERS & TIM_N(5)
165 #if USED_TIMERS & TIM_N(6)
168 #if USED_TIMERS & TIM_N(7)
171 #if USED_TIMERS & TIM_N(8)
174 #if USED_TIMERS & TIM_N(9)
177 #if USED_TIMERS & TIM_N(10)
180 #if USED_TIMERS & TIM_N(11)
183 #if USED_TIMERS & TIM_N(12)
186 #if USED_TIMERS & TIM_N(13)
189 #if USED_TIMERS & TIM_N(14)
192 #if USED_TIMERS & TIM_N(15)
195 #if USED_TIMERS & TIM_N(16)
198 #if USED_TIMERS & TIM_N(17)
204 static inline uint8_t lookupChannelIndex(const uint16_t channel
)
209 rccPeriphTag_t
timerRCC(TIM_TypeDef
*tim
)
211 for (int i
= 0; i
< HARDWARE_TIMER_DEFINITION_COUNT
; i
++) {
212 if (timerDefinitions
[i
].TIMx
== tim
) {
213 return timerDefinitions
[i
].rcc
;
219 void timerNVICConfigure(uint8_t irq
)
221 HAL_NVIC_SetPriority(irq
, NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER
), NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER
));
222 HAL_NVIC_EnableIRQ(irq
);
225 TIM_HandleTypeDef
* timerFindTimerHandle(TIM_TypeDef
*tim
)
227 uint8_t timerIndex
= lookupTimerIndex(tim
);
228 if (timerIndex
>= USED_TIMER_COUNT
)
231 return &timerHandle
[timerIndex
].Handle
;
234 void configTimeBase(TIM_TypeDef
*tim
, uint16_t period
, uint8_t mhz
)
236 uint8_t timerIndex
= lookupTimerIndex(tim
);
237 if (timerIndex
>= USED_TIMER_COUNT
) {
240 if(timerHandle
[timerIndex
].Handle
.Instance
== tim
)
242 // already configured
246 timerHandle
[timerIndex
].Handle
.Instance
= tim
;
248 timerHandle
[timerIndex
].Handle
.Init
.Period
= (period
- 1) & 0xffff; // AKA TIMx_ARR
249 timerHandle
[timerIndex
].Handle
.Init
.Prescaler
= (SystemCoreClock
/ timerClockDivisor(tim
) / ((uint32_t)mhz
* 1000000)) - 1;
251 timerHandle
[timerIndex
].Handle
.Init
.ClockDivision
= TIM_CLOCKDIVISION_DIV1
;
252 timerHandle
[timerIndex
].Handle
.Init
.CounterMode
= TIM_COUNTERMODE_UP
;
253 timerHandle
[timerIndex
].Handle
.Init
.RepetitionCounter
= 0x0000;
255 HAL_TIM_Base_Init(&timerHandle
[timerIndex
].Handle
);
256 if(tim
== TIM1
|| tim
== TIM2
|| tim
== TIM3
|| tim
== TIM4
|| tim
== TIM5
|| tim
== TIM8
|| tim
== TIM9
)
258 TIM_ClockConfigTypeDef sClockSourceConfig
;
259 sClockSourceConfig
.ClockSource
= TIM_CLOCKSOURCE_INTERNAL
;
260 if (HAL_TIM_ConfigClockSource(&timerHandle
[timerIndex
].Handle
, &sClockSourceConfig
) != HAL_OK
)
265 if(tim
== TIM1
|| tim
== TIM2
|| tim
== TIM3
|| tim
== TIM4
|| tim
== TIM5
|| tim
== TIM8
)
267 TIM_MasterConfigTypeDef sMasterConfig
;
268 sMasterConfig
.MasterOutputTrigger
= TIM_TRGO_RESET
;
269 sMasterConfig
.MasterSlaveMode
= TIM_MASTERSLAVEMODE_DISABLE
;
270 if (HAL_TIMEx_MasterConfigSynchronization(&timerHandle
[timerIndex
].Handle
, &sMasterConfig
) != HAL_OK
)
278 // old interface for PWM inputs. It should be replaced
279 void timerConfigure(const timerHardware_t
*timerHardwarePtr
, uint16_t period
, uint8_t mhz
)
281 uint8_t timerIndex
= lookupTimerIndex(timerHardwarePtr
->tim
);
282 if (timerIndex
>= USED_TIMER_COUNT
) {
286 configTimeBase(timerHardwarePtr
->tim
, period
, mhz
);
287 HAL_TIM_Base_Start(&timerHandle
[timerIndex
].Handle
);
288 timerNVICConfigure(timerHardwarePtr
->irq
);
289 // HACK - enable second IRQ on timers that need it
290 switch(timerHardwarePtr
->irq
) {
293 timerNVICConfigure(TIM1_UP_TIM10_IRQn
);
296 timerNVICConfigure(TIM8_UP_TIM13_IRQn
);
302 // allocate and configure timer channel. Timer priority is set to highest priority of its channels
303 void timerChInit(const timerHardware_t
*timHw
, channelType_t type
, int irqPriority
)
305 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
306 if (timerIndex
>= USED_TIMER_COUNT
) {
309 unsigned channel
= timHw
- timerHardware
;
310 if(channel
>= USABLE_TIMER_CHANNEL_COUNT
)
313 timerChannelInfo
[channel
].type
= type
;
314 unsigned timer
= lookupTimerIndex(timHw
->tim
);
315 if(timer
>= USED_TIMER_COUNT
)
317 if(irqPriority
< timerInfo
[timer
].priority
) {
318 // it would be better to set priority in the end, but current startup sequence is not ready
319 configTimeBase(usedTimers
[timer
], 0, 1);
320 HAL_TIM_Base_Start(&timerHandle
[timerIndex
].Handle
);
323 HAL_NVIC_SetPriority(timHw
->irq
, NVIC_PRIORITY_BASE(irqPriority
), NVIC_PRIORITY_SUB(irqPriority
));
324 HAL_NVIC_EnableIRQ(timHw
->irq
);
326 timerInfo
[timer
].priority
= irqPriority
;
330 void timerChCCHandlerInit(timerCCHandlerRec_t
*self
, timerCCHandlerCallback
*fn
)
335 void timerChOvrHandlerInit(timerOvrHandlerRec_t
*self
, timerOvrHandlerCallback
*fn
)
341 // update overflow callback list
342 // some synchronization mechanism is neccesary to avoid disturbing other channels (BASEPRI used now)
343 static void timerChConfig_UpdateOverflow(timerConfig_t
*cfg
, TIM_TypeDef
*tim
) {
344 uint8_t timerIndex
= lookupTimerIndex(tim
);
345 if (timerIndex
>= USED_TIMER_COUNT
) {
349 timerOvrHandlerRec_t
**chain
= &cfg
->overflowCallbackActive
;
350 ATOMIC_BLOCK(NVIC_PRIO_TIMER
) {
351 for(int i
= 0; i
< CC_CHANNELS_PER_TIMER
; i
++)
352 if(cfg
->overflowCallback
[i
]) {
353 *chain
= cfg
->overflowCallback
[i
];
354 chain
= &cfg
->overflowCallback
[i
]->next
;
358 // enable or disable IRQ
359 if(cfg
->overflowCallbackActive
)
360 __HAL_TIM_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_UPDATE
);
362 __HAL_TIM_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_UPDATE
);
365 // config edge and overflow callback for channel. Try to avoid overflowCallback, it is a bit expensive
366 void timerChConfigCallbacks(const timerHardware_t
*timHw
, timerCCHandlerRec_t
*edgeCallback
, timerOvrHandlerRec_t
*overflowCallback
)
368 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
369 if (timerIndex
>= USED_TIMER_COUNT
) {
372 uint8_t channelIndex
= lookupChannelIndex(timHw
->channel
);
373 if(edgeCallback
== NULL
) // disable irq before changing callback to NULL
374 __HAL_TIM_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
));
375 // setup callback info
376 timerConfig
[timerIndex
].edgeCallback
[channelIndex
] = edgeCallback
;
377 timerConfig
[timerIndex
].overflowCallback
[channelIndex
] = overflowCallback
;
378 // enable channel IRQ
380 __HAL_TIM_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
));
382 timerChConfig_UpdateOverflow(&timerConfig
[timerIndex
], timHw
->tim
);
385 // configure callbacks for pair of channels (1+2 or 3+4).
386 // Hi(2,4) and Lo(1,3) callbacks are specified, it is not important which timHw channel is used.
387 // This is intended for dual capture mode (each channel handles one transition)
388 void timerChConfigCallbacksDual(const timerHardware_t
*timHw
, timerCCHandlerRec_t
*edgeCallbackLo
, timerCCHandlerRec_t
*edgeCallbackHi
, timerOvrHandlerRec_t
*overflowCallback
)
390 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
391 if (timerIndex
>= USED_TIMER_COUNT
) {
394 uint16_t chLo
= timHw
->channel
& ~TIM_CHANNEL_2
; // lower channel
395 uint16_t chHi
= timHw
->channel
| TIM_CHANNEL_2
; // upper channel
396 uint8_t channelIndex
= lookupChannelIndex(chLo
); // get index of lower channel
398 if(edgeCallbackLo
== NULL
) // disable irq before changing setting callback to NULL
399 __HAL_TIM_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chLo
));
400 if(edgeCallbackHi
== NULL
) // disable irq before changing setting callback to NULL
401 __HAL_TIM_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chHi
));
403 // setup callback info
404 timerConfig
[timerIndex
].edgeCallback
[channelIndex
] = edgeCallbackLo
;
405 timerConfig
[timerIndex
].edgeCallback
[channelIndex
+ 1] = edgeCallbackHi
;
406 timerConfig
[timerIndex
].overflowCallback
[channelIndex
] = overflowCallback
;
407 timerConfig
[timerIndex
].overflowCallback
[channelIndex
+ 1] = NULL
;
409 // enable channel IRQs
411 __HAL_TIM_CLEAR_FLAG(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chLo
));
412 __HAL_TIM_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chLo
));
415 __HAL_TIM_CLEAR_FLAG(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chHi
));
416 __HAL_TIM_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chHi
));
419 timerChConfig_UpdateOverflow(&timerConfig
[timerIndex
], timHw
->tim
);
422 // enable/disable IRQ for low channel in dual configuration
423 //void timerChITConfigDualLo(const timerHardware_t *timHw, FunctionalState newState) {
424 // TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel&~TIM_Channel_2), newState);
426 // enable/disable IRQ for low channel in dual configuration
427 void timerChITConfigDualLo(const timerHardware_t
*timHw
, FunctionalState newState
) {
428 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
429 if (timerIndex
>= USED_TIMER_COUNT
) {
434 __HAL_TIM_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
&~TIM_CHANNEL_2
));
436 __HAL_TIM_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
&~TIM_CHANNEL_2
));
439 //// enable or disable IRQ
440 //void timerChITConfig(const timerHardware_t *timHw, FunctionalState newState)
442 // TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), newState);
444 // enable or disable IRQ
445 void timerChITConfig(const timerHardware_t
*timHw
, FunctionalState newState
)
447 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
448 if (timerIndex
>= USED_TIMER_COUNT
) {
453 __HAL_TIM_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
));
455 __HAL_TIM_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
));
458 // clear Compare/Capture flag for channel
459 //void timerChClearCCFlag(const timerHardware_t *timHw)
461 // TIM_ClearFlag(timHw->tim, TIM_IT_CCx(timHw->channel));
463 // clear Compare/Capture flag for channel
464 void timerChClearCCFlag(const timerHardware_t
*timHw
)
466 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
467 if (timerIndex
>= USED_TIMER_COUNT
) {
471 __HAL_TIM_CLEAR_FLAG(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
));
474 // configure timer channel GPIO mode
475 void timerChConfigGPIO(const timerHardware_t
* timHw
, ioConfig_t mode
)
477 IOInit(IOGetByTag(timHw
->tag
), OWNER_TIMER
, RESOURCE_TIMER
, 0);
478 IOConfigGPIO(IOGetByTag(timHw
->tag
), mode
);
481 // calculate input filter constant
482 // TODO - we should probably setup DTS to higher value to allow reasonable input filtering
483 // - notice that prescaler[0] does use DTS for sampling - the sequence won't be monotonous anymore
484 static unsigned getFilter(unsigned ticks
)
486 static const unsigned ftab
[16] = {
488 1*2, 1*4, 1*8, // fCK_INT
495 for(unsigned i
= 1; i
< ARRAYLEN(ftab
); i
++)
501 // Configure input captupre
502 void timerChConfigIC(const timerHardware_t
*timHw
, bool polarityRising
, unsigned inputFilterTicks
)
504 unsigned timer
= lookupTimerIndex(timHw
->tim
);
505 if(timer
>= USED_TIMER_COUNT
)
508 TIM_IC_InitTypeDef TIM_ICInitStructure
;
510 TIM_ICInitStructure
.ICPolarity
= polarityRising
? TIM_ICPOLARITY_RISING
: TIM_ICPOLARITY_FALLING
;
511 TIM_ICInitStructure
.ICSelection
= TIM_ICSELECTION_DIRECTTI
;
512 TIM_ICInitStructure
.ICPrescaler
= TIM_ICPSC_DIV1
;
513 TIM_ICInitStructure
.ICFilter
= getFilter(inputFilterTicks
);
514 HAL_TIM_IC_ConfigChannel(&timerHandle
[timer
].Handle
,&TIM_ICInitStructure
, timHw
->channel
);
517 // configure dual channel input channel for capture
518 // polarity is for Low channel (capture order is always Lo - Hi)
519 void timerChConfigICDual(const timerHardware_t
*timHw
, bool polarityRising
, unsigned inputFilterTicks
)
521 unsigned timer
= lookupTimerIndex(timHw
->tim
);
522 if(timer
>= USED_TIMER_COUNT
)
525 TIM_IC_InitTypeDef TIM_ICInitStructure
;
526 bool directRising
= (timHw
->channel
& TIM_CHANNEL_2
) ? !polarityRising
: polarityRising
;
528 // configure direct channel
529 TIM_ICInitStructure
.ICPolarity
= directRising
? TIM_ICPOLARITY_RISING
: TIM_ICPOLARITY_FALLING
;
530 TIM_ICInitStructure
.ICSelection
= TIM_ICSELECTION_DIRECTTI
;
531 TIM_ICInitStructure
.ICPrescaler
= TIM_ICPSC_DIV1
;
532 TIM_ICInitStructure
.ICFilter
= getFilter(inputFilterTicks
);
533 HAL_TIM_IC_ConfigChannel(&timerHandle
[timer
].Handle
,&TIM_ICInitStructure
, timHw
->channel
);
535 // configure indirect channel
536 TIM_ICInitStructure
.ICPolarity
= directRising
? TIM_ICPOLARITY_FALLING
: TIM_ICPOLARITY_RISING
;
537 TIM_ICInitStructure
.ICSelection
= TIM_ICSELECTION_INDIRECTTI
;
538 HAL_TIM_IC_ConfigChannel(&timerHandle
[timer
].Handle
,&TIM_ICInitStructure
, timHw
->channel
^ TIM_CHANNEL_2
);
541 void timerChICPolarity(const timerHardware_t
*timHw
, bool polarityRising
)
543 timCCER_t tmpccer
= timHw
->tim
->CCER
;
544 tmpccer
&= ~(TIM_CCER_CC1P
<< timHw
->channel
);
545 tmpccer
|= polarityRising
? (TIM_ICPOLARITY_RISING
<< timHw
->channel
) : (TIM_ICPOLARITY_FALLING
<< timHw
->channel
);
546 timHw
->tim
->CCER
= tmpccer
;
549 volatile timCCR_t
* timerChCCRHi(const timerHardware_t
*timHw
)
551 return (volatile timCCR_t
*)((volatile char*)&timHw
->tim
->CCR1
+ (timHw
->channel
| TIM_CHANNEL_2
));
554 volatile timCCR_t
* timerChCCRLo(const timerHardware_t
*timHw
)
556 return (volatile timCCR_t
*)((volatile char*)&timHw
->tim
->CCR1
+ (timHw
->channel
& ~TIM_CHANNEL_2
));
561 volatile timCCR_t
* timerChCCR(const timerHardware_t
*timHw
)
563 return (volatile timCCR_t
*)((volatile char*)&timHw
->tim
->CCR1
+ timHw
->channel
);
566 void timerChConfigOC(const timerHardware_t
* timHw
, bool outEnable
, bool stateHigh
)
568 unsigned timer
= lookupTimerIndex(timHw
->tim
);
569 if(timer
>= USED_TIMER_COUNT
)
572 TIM_OC_InitTypeDef TIM_OCInitStructure
;
574 TIM_OCInitStructure
.OCMode
= TIM_OCMODE_INACTIVE
;
575 TIM_OCInitStructure
.Pulse
= 0x00000000;
576 TIM_OCInitStructure
.OCPolarity
= stateHigh
? TIM_OCPOLARITY_HIGH
: TIM_OCPOLARITY_LOW
;
577 TIM_OCInitStructure
.OCNPolarity
= TIM_OCPOLARITY_HIGH
;
578 TIM_OCInitStructure
.OCIdleState
= TIM_OCIDLESTATE_RESET
;
579 TIM_OCInitStructure
.OCNIdleState
= TIM_OCNIDLESTATE_RESET
;
581 HAL_TIM_OC_ConfigChannel(&timerHandle
[timer
].Handle
, &TIM_OCInitStructure
, timHw
->channel
);
584 TIM_OCInitStructure
.OCMode
= TIM_OCMODE_INACTIVE
;
585 HAL_TIM_OC_ConfigChannel(&timerHandle
[timer
].Handle
, &TIM_OCInitStructure
, timHw
->channel
);
586 HAL_TIM_OC_Start(&timerHandle
[timer
].Handle
, timHw
->channel
);
588 TIM_OCInitStructure
.OCMode
= TIM_OCMODE_TIMING
;
589 HAL_TIM_OC_ConfigChannel(&timerHandle
[timer
].Handle
, &TIM_OCInitStructure
, timHw
->channel
);
590 HAL_TIM_OC_Start_IT(&timerHandle
[timer
].Handle
, timHw
->channel
);
594 static void timCCxHandler(TIM_TypeDef
*tim
, timerConfig_t
*timerConfig
)
598 tim_status
= tim
->SR
& tim
->DIER
;
601 // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
602 // currrent order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
603 unsigned bit
= __builtin_clz(tim_status
);
604 unsigned mask
= ~(0x80000000 >> bit
);
608 case __builtin_clz(TIM_IT_UPDATE
): {
610 if(timerConfig
->forcedOverflowTimerValue
!= 0){
611 capture
= timerConfig
->forcedOverflowTimerValue
- 1;
612 timerConfig
->forcedOverflowTimerValue
= 0;
617 timerOvrHandlerRec_t
*cb
= timerConfig
->overflowCallbackActive
;
624 case __builtin_clz(TIM_IT_CC1
):
625 timerConfig
->edgeCallback
[0]->fn(timerConfig
->edgeCallback
[0], tim
->CCR1
);
627 case __builtin_clz(TIM_IT_CC2
):
628 timerConfig
->edgeCallback
[1]->fn(timerConfig
->edgeCallback
[1], tim
->CCR2
);
630 case __builtin_clz(TIM_IT_CC3
):
631 timerConfig
->edgeCallback
[2]->fn(timerConfig
->edgeCallback
[2], tim
->CCR3
);
633 case __builtin_clz(TIM_IT_CC4
):
634 timerConfig
->edgeCallback
[3]->fn(timerConfig
->edgeCallback
[3], tim
->CCR4
);
639 if (tim_status
& (int)TIM_IT_Update
) {
640 tim
->SR
= ~TIM_IT_Update
;
642 timerOvrHandlerRec_t
*cb
= timerConfig
->overflowCallbackActive
;
648 if (tim_status
& (int)TIM_IT_CC1
) {
649 tim
->SR
= ~TIM_IT_CC1
;
650 timerConfig
->edgeCallback
[0]->fn(timerConfig
->edgeCallback
[0], tim
->CCR1
);
652 if (tim_status
& (int)TIM_IT_CC2
) {
653 tim
->SR
= ~TIM_IT_CC2
;
654 timerConfig
->edgeCallback
[1]->fn(timerConfig
->edgeCallback
[1], tim
->CCR2
);
656 if (tim_status
& (int)TIM_IT_CC3
) {
657 tim
->SR
= ~TIM_IT_CC3
;
658 timerConfig
->edgeCallback
[2]->fn(timerConfig
->edgeCallback
[2], tim
->CCR3
);
660 if (tim_status
& (int)TIM_IT_CC4
) {
661 tim
->SR
= ~TIM_IT_CC4
;
662 timerConfig
->edgeCallback
[3]->fn(timerConfig
->edgeCallback
[3], tim
->CCR4
);
667 // handler for shared interrupts when both timers need to check status bits
668 #define _TIM_IRQ_HANDLER2(name, i, j) \
671 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
672 timCCxHandler(TIM ## j, &timerConfig[TIMER_INDEX(j)]); \
675 #define _TIM_IRQ_HANDLER(name, i) \
678 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
681 #if USED_TIMERS & TIM_N(1)
682 _TIM_IRQ_HANDLER(TIM1_CC_IRQHandler
, 1);
683 # if USED_TIMERS & TIM_N(10)
684 _TIM_IRQ_HANDLER2(TIM1_UP_TIM10_IRQHandler
, 1, 10); // both timers are in use
686 _TIM_IRQ_HANDLER(TIM1_UP_TIM10_IRQHandler
, 1); // timer10 is not used
690 #if USED_TIMERS & TIM_N(2)
691 _TIM_IRQ_HANDLER(TIM2_IRQHandler
, 2);
693 #if USED_TIMERS & TIM_N(3)
694 _TIM_IRQ_HANDLER(TIM3_IRQHandler
, 3);
696 #if USED_TIMERS & TIM_N(4)
697 _TIM_IRQ_HANDLER(TIM4_IRQHandler
, 4);
699 #if USED_TIMERS & TIM_N(5)
700 _TIM_IRQ_HANDLER(TIM5_IRQHandler
, 5);
703 #if USED_TIMERS & TIM_N(8)
704 _TIM_IRQ_HANDLER(TIM8_CC_IRQHandler
, 8);
706 # if USED_TIMERS & TIM_N(13)
707 _TIM_IRQ_HANDLER2(TIM8_UP_TIM13_IRQHandler
, 8, 13); // both timers are in use
709 _TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler
, 8); // timer13 is not used
713 #if USED_TIMERS & TIM_N(9)
714 _TIM_IRQ_HANDLER(TIM1_BRK_TIM9_IRQHandler
, 9);
716 # if USED_TIMERS & TIM_N(11)
717 _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM11_IRQHandler
, 11);
719 #if USED_TIMERS & TIM_N(12)
720 _TIM_IRQ_HANDLER(TIM8_BRK_TIM12_IRQHandler
, 12);
722 #if USED_TIMERS & TIM_N(15)
723 _TIM_IRQ_HANDLER(TIM1_BRK_TIM15_IRQHandler
, 15);
725 #if defined(STM32F303xC) && ((USED_TIMERS & (TIM_N(1)|TIM_N(16))) == (TIM_N(16)))
726 _TIM_IRQ_HANDLER(TIM1_UP_TIM16_IRQHandler
, 16); // only timer16 is used, not timer1
728 #if USED_TIMERS & TIM_N(17)
729 _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM17_IRQHandler
, 17);
734 memset(timerConfig
, 0, sizeof (timerConfig
));
737 #if USED_TIMERS & TIM_N(1)
738 __HAL_RCC_TIM1_CLK_ENABLE();
740 #if USED_TIMERS & TIM_N(2)
741 __HAL_RCC_TIM2_CLK_ENABLE();
743 #if USED_TIMERS & TIM_N(3)
744 __HAL_RCC_TIM3_CLK_ENABLE();
746 #if USED_TIMERS & TIM_N(4)
747 __HAL_RCC_TIM4_CLK_ENABLE();
749 #if USED_TIMERS & TIM_N(5)
750 __HAL_RCC_TIM5_CLK_ENABLE();
752 #if USED_TIMERS & TIM_N(6)
753 __HAL_RCC_TIM6_CLK_ENABLE();
755 #if USED_TIMERS & TIM_N(7)
756 __HAL_RCC_TIM7_CLK_ENABLE();
758 #if USED_TIMERS & TIM_N(8)
759 __HAL_RCC_TIM8_CLK_ENABLE();
761 #if USED_TIMERS & TIM_N(9)
762 __HAL_RCC_TIM9_CLK_ENABLE();
764 #if USED_TIMERS & TIM_N(10)
765 __HAL_RCC_TIM10_CLK_ENABLE();
767 #if USED_TIMERS & TIM_N(11)
768 __HAL_RCC_TIM11_CLK_ENABLE();
770 #if USED_TIMERS & TIM_N(12)
771 __HAL_RCC_TIM12_CLK_ENABLE();
773 #if USED_TIMERS & TIM_N(13)
774 __HAL_RCC_TIM13_CLK_ENABLE();
776 #if USED_TIMERS & TIM_N(14)
777 __HAL_RCC_TIM14_CLK_ENABLE();
779 #if USED_TIMERS & TIM_N(15)
780 __HAL_RCC_TIM15_CLK_ENABLE();
782 #if USED_TIMERS & TIM_N(16)
783 __HAL_RCC_TIM16_CLK_ENABLE();
785 #if USED_TIMERS & TIM_N(17)
786 __HAL_RCC_TIM17_CLK_ENABLE();
789 /* enable the timer peripherals */
790 for (int i
= 0; i
< USABLE_TIMER_CHANNEL_COUNT
; i
++) {
791 RCC_ClockCmd(timerRCC(timerHardware
[i
].tim
), ENABLE
);
794 #if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
795 for (int timerIndex
= 0; timerIndex
< USABLE_TIMER_CHANNEL_COUNT
; timerIndex
++) {
796 const timerHardware_t
*timerHardwarePtr
= &timerHardware
[timerIndex
];
797 IOConfigGPIOAF(IOGetByTag(timerHardwarePtr
->tag
), IOCFG_AF_PP
, timerHardwarePtr
->alternateFunction
);
801 // initialize timer channel structures
802 for(int i
= 0; i
< USABLE_TIMER_CHANNEL_COUNT
; i
++) {
803 timerChannelInfo
[i
].type
= TYPE_FREE
;
805 for(int i
= 0; i
< USED_TIMER_COUNT
; i
++) {
806 timerInfo
[i
].priority
= ~0;
810 // finish configuring timers after allocation phase
812 // TODO - Work in progress - initialization routine must be modified/verified to start correctly without timers
813 void timerStart(void)
816 for(unsigned timer
= 0; timer
< USED_TIMER_COUNT
; timer
++) {
819 for(unsigned hwc
= 0; hwc
< USABLE_TIMER_CHANNEL_COUNT
; hwc
++)
820 if((timerChannelInfo
[hwc
].type
!= TYPE_FREE
) && (timerHardware
[hwc
].tim
== usedTimers
[timer
])) {
821 // TODO - move IRQ to timer info
822 irq
= timerHardware
[hwc
].irq
;
824 // TODO - aggregate required timer paramaters
825 configTimeBase(usedTimers
[timer
], 0, 1);
826 TIM_Cmd(usedTimers
[timer
], ENABLE
);
827 if(priority
>= 0) { // maybe none of the channels was configured
828 NVIC_InitTypeDef NVIC_InitStructure
;
830 NVIC_InitStructure
.NVIC_IRQChannel
= irq
;
831 NVIC_InitStructure
.NVIC_IRQChannelPreemptionPriority
= NVIC_SPLIT_PRIORITY_BASE(priority
);
832 NVIC_InitStructure
.NVIC_IRQChannelSubPriority
= NVIC_SPLIT_PRIORITY_SUB(priority
);
833 NVIC_InitStructure
.NVIC_IRQChannelCmd
= ENABLE
;
834 NVIC_Init(&NVIC_InitStructure
);
841 * Force an overflow for a given timer.
842 * Saves the current value of the counter in the relevant timerConfig's forcedOverflowTimerValue variable.
843 * @param TIM_Typedef *tim The timer to overflow
846 void timerForceOverflow(TIM_TypeDef
*tim
)
848 uint8_t timerIndex
= lookupTimerIndex((const TIM_TypeDef
*)tim
);
850 ATOMIC_BLOCK(NVIC_PRIO_TIMER
) {
851 // Save the current count so that PPM reading will work on the same timer that was forced to overflow
852 timerConfig
[timerIndex
].forcedOverflowTimerValue
= tim
->CNT
+ 1;
854 // Force an overflow by setting the UG bit
855 tim
->EGR
|= TIM_EGR_UG
;
859 const timerHardware_t
*timerGetByTag(ioTag_t tag
, timerUsageFlag_e flag
)
861 for (int i
= 0; i
< USABLE_TIMER_CHANNEL_COUNT
; i
++) {
862 if (timerHardware
[i
].tag
== tag
) {
863 if (timerHardware
[i
].output
& flag
) {
864 return &timerHardware
[i
];