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"
37 #include "drivers/dma.h"
42 #include "timer_impl.h"
44 #define TIM_N(n) (1 << (n))
47 Groups that allow running different period (ex 50Hz servos + 400Hz throttle + etc):
54 /// TODO: HAL in a lot af calls lookupTimerIndex is used. Instead of passing the timer instance the index should be passed.
55 #define USED_TIMER_COUNT BITCOUNT(USED_TIMERS)
57 #define TIM_IT_CCx(ch) (TIM_IT_CC1 << ((ch) / 4))
59 typedef struct timerConfig_s
{
61 timerOvrHandlerRec_t
*updateCallback
;
64 timerCCHandlerRec_t
*edgeCallback
[CC_CHANNELS_PER_TIMER
];
65 timerOvrHandlerRec_t
*overflowCallback
[CC_CHANNELS_PER_TIMER
];
68 timerOvrHandlerRec_t
*overflowCallbackActive
; // null-terminated linkded list of active overflow callbacks
69 uint32_t forcedOverflowTimerValue
;
71 timerConfig_t timerConfig
[USED_TIMER_COUNT
+ 1];
76 timerChannelInfo_t timerChannelInfo
[TIMER_CHANNEL_COUNT
];
81 timerInfo_t timerInfo
[USED_TIMER_COUNT
+ 1];
84 TIM_HandleTypeDef Handle
;
86 timerHandle_t timerHandle
[USED_TIMER_COUNT
+ 1];
88 // return index of timer in timer table. Lowest timer has index 0
89 #define TIMER_INDEX(i) BITCOUNT((TIM_N(i) - 1) & USED_TIMERS)
91 static uint8_t lookupTimerIndex(const TIM_TypeDef
*tim
)
93 #define _CASE_SHF 10 // amount we can safely shift timer address to the right. gcc will throw error if some timers overlap
94 #define _CASE_(tim, index) case ((unsigned)tim >> _CASE_SHF): return index; break
95 #define _CASE(i) _CASE_(TIM##i##_BASE, TIMER_INDEX(i))
97 // let gcc do the work, switch should be quite optimized
98 switch ((unsigned)tim
>> _CASE_SHF
) {
99 #if USED_TIMERS & TIM_N(1)
102 #if USED_TIMERS & TIM_N(2)
105 #if USED_TIMERS & TIM_N(3)
108 #if USED_TIMERS & TIM_N(4)
111 #if USED_TIMERS & TIM_N(5)
114 #if USED_TIMERS & TIM_N(6)
117 #if USED_TIMERS & TIM_N(7)
120 #if USED_TIMERS & TIM_N(8)
123 #if USED_TIMERS & TIM_N(9)
126 #if USED_TIMERS & TIM_N(10)
129 #if USED_TIMERS & TIM_N(11)
132 #if USED_TIMERS & TIM_N(12)
135 #if USED_TIMERS & TIM_N(13)
138 #if USED_TIMERS & TIM_N(14)
141 #if USED_TIMERS & TIM_N(15)
144 #if USED_TIMERS & TIM_N(16)
147 #if USED_TIMERS & TIM_N(17)
150 #if USED_TIMERS & TIM_N(20)
153 default: return ~1; // make sure final index is out of range
159 TIM_TypeDef
* const usedTimers
[USED_TIMER_COUNT
] = {
160 #define _DEF(i) TIM##i
162 #if USED_TIMERS & TIM_N(1)
165 #if USED_TIMERS & TIM_N(2)
168 #if USED_TIMERS & TIM_N(3)
171 #if USED_TIMERS & TIM_N(4)
174 #if USED_TIMERS & TIM_N(5)
177 #if USED_TIMERS & TIM_N(6)
180 #if USED_TIMERS & TIM_N(7)
183 #if USED_TIMERS & TIM_N(8)
186 #if !(defined(STM32H7) || defined(STM32G4))
187 #if USED_TIMERS & TIM_N(9)
190 #if USED_TIMERS & TIM_N(10)
193 #if USED_TIMERS & TIM_N(11)
197 #if !defined(STM32G4)
198 #if USED_TIMERS & TIM_N(12)
201 #if USED_TIMERS & TIM_N(13)
204 #if USED_TIMERS & TIM_N(14)
208 #if USED_TIMERS & TIM_N(15)
211 #if USED_TIMERS & TIM_N(16)
214 #if USED_TIMERS & TIM_N(17)
218 #if USED_TIMERS & TIM_N(20)
225 // Map timer index to timer number (Straight copy of usedTimers array)
226 const int8_t timerNumbers
[USED_TIMER_COUNT
] = {
229 #if USED_TIMERS & TIM_N(1)
232 #if USED_TIMERS & TIM_N(2)
235 #if USED_TIMERS & TIM_N(3)
238 #if USED_TIMERS & TIM_N(4)
241 #if USED_TIMERS & TIM_N(5)
244 #if USED_TIMERS & TIM_N(6)
247 #if USED_TIMERS & TIM_N(7)
250 #if USED_TIMERS & TIM_N(8)
253 #if USED_TIMERS & TIM_N(9)
256 #if USED_TIMERS & TIM_N(10)
259 #if USED_TIMERS & TIM_N(11)
262 #if USED_TIMERS & TIM_N(12)
265 #if USED_TIMERS & TIM_N(13)
268 #if USED_TIMERS & TIM_N(14)
271 #if USED_TIMERS & TIM_N(15)
274 #if USED_TIMERS & TIM_N(16)
277 #if USED_TIMERS & TIM_N(17)
280 #if USED_TIMERS & TIM_N(20)
286 int8_t timerGetNumberByIndex(uint8_t index
)
288 if (index
< USED_TIMER_COUNT
) {
289 return timerNumbers
[index
];
295 int8_t timerGetTIMNumber(const TIM_TypeDef
*tim
)
297 uint8_t index
= lookupTimerIndex(tim
);
299 return timerGetNumberByIndex(index
);
302 static inline uint8_t lookupChannelIndex(const uint16_t channel
)
307 uint8_t timerLookupChannelIndex(const uint16_t channel
)
309 return lookupChannelIndex(channel
);
312 rccPeriphTag_t
timerRCC(TIM_TypeDef
*tim
)
314 for (int i
= 0; i
< HARDWARE_TIMER_DEFINITION_COUNT
; i
++) {
315 if (timerDefinitions
[i
].TIMx
== tim
) {
316 return timerDefinitions
[i
].rcc
;
322 uint8_t timerInputIrq(TIM_TypeDef
*tim
)
324 for (int i
= 0; i
< HARDWARE_TIMER_DEFINITION_COUNT
; i
++) {
325 if (timerDefinitions
[i
].TIMx
== tim
) {
326 return timerDefinitions
[i
].inputIrq
;
332 void timerNVICConfigure(uint8_t irq
)
334 HAL_NVIC_SetPriority(irq
, NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER
), NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER
));
335 HAL_NVIC_EnableIRQ(irq
);
338 TIM_HandleTypeDef
* timerFindTimerHandle(TIM_TypeDef
*tim
)
340 uint8_t timerIndex
= lookupTimerIndex(tim
);
341 if (timerIndex
>= USED_TIMER_COUNT
)
344 return &timerHandle
[timerIndex
].Handle
;
347 void timerReconfigureTimeBase(TIM_TypeDef
*tim
, uint16_t period
, uint32_t hz
)
349 TIM_HandleTypeDef
* handle
= timerFindTimerHandle(tim
);
350 if (handle
== NULL
) return;
352 handle
->Init
.Period
= (period
- 1) & 0xffff; // AKA TIMx_ARR
353 handle
->Init
.Prescaler
= (timerClock(tim
) / hz
) - 1;
355 TIM_Base_SetConfig(handle
->Instance
, &handle
->Init
);
358 void configTimeBase(TIM_TypeDef
*tim
, uint16_t period
, uint32_t hz
)
360 TIM_HandleTypeDef
* handle
= timerFindTimerHandle(tim
);
361 if (handle
== NULL
) return;
363 if (handle
->Instance
== tim
) {
364 // already configured
368 handle
->Instance
= tim
;
370 handle
->Init
.Period
= (period
- 1) & 0xffff; // AKA TIMx_ARR
371 handle
->Init
.Prescaler
= (timerClock(tim
) / hz
) - 1;
373 handle
->Init
.ClockDivision
= TIM_CLOCKDIVISION_DIV1
;
374 handle
->Init
.CounterMode
= TIM_COUNTERMODE_UP
;
375 handle
->Init
.RepetitionCounter
= 0x0000;
377 HAL_TIM_Base_Init(handle
);
378 if (tim
== TIM1
|| tim
== TIM2
|| tim
== TIM3
|| tim
== TIM4
|| tim
== TIM5
|| tim
== TIM8
379 #if !(defined(STM32H7) || defined(STM32G4))
383 TIM_ClockConfigTypeDef sClockSourceConfig
;
384 memset(&sClockSourceConfig
, 0, sizeof(sClockSourceConfig
));
385 sClockSourceConfig
.ClockSource
= TIM_CLOCKSOURCE_INTERNAL
;
386 if (HAL_TIM_ConfigClockSource(handle
, &sClockSourceConfig
) != HAL_OK
) {
390 if (tim
== TIM1
|| tim
== TIM2
|| tim
== TIM3
|| tim
== TIM4
|| tim
== TIM5
|| tim
== TIM8
) {
391 TIM_MasterConfigTypeDef sMasterConfig
;
392 memset(&sMasterConfig
, 0, sizeof(sMasterConfig
));
393 sMasterConfig
.MasterSlaveMode
= TIM_MASTERSLAVEMODE_DISABLE
;
394 if (HAL_TIMEx_MasterConfigSynchronization(handle
, &sMasterConfig
) != HAL_OK
) {
400 // old interface for PWM inputs. It should be replaced
401 void timerConfigure(const timerHardware_t
*timerHardwarePtr
, uint16_t period
, uint32_t hz
)
403 uint8_t timerIndex
= lookupTimerIndex(timerHardwarePtr
->tim
);
404 if (timerIndex
>= USED_TIMER_COUNT
) {
408 configTimeBase(timerHardwarePtr
->tim
, period
, hz
);
409 HAL_TIM_Base_Start(&timerHandle
[timerIndex
].Handle
);
411 uint8_t irq
= timerInputIrq(timerHardwarePtr
->tim
);
412 timerNVICConfigure(irq
);
413 // HACK - enable second IRQ on timers that need it
418 timerNVICConfigure(TIM1_UP_TIM10_IRQn
);
419 #elif defined(STM32H7)
420 timerNVICConfigure(TIM1_UP_IRQn
);
421 #elif defined(STM32G4)
422 timerNVICConfigure(TIM1_UP_TIM16_IRQn
);
429 timerNVICConfigure(TIM8_UP_IRQn
);
431 timerNVICConfigure(TIM8_UP_TIM13_IRQn
);
438 // allocate and configure timer channel. Timer priority is set to highest priority of its channels
439 void timerChInit(const timerHardware_t
*timHw
, channelType_t type
, int irqPriority
, uint8_t irq
)
441 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
442 if (timerIndex
>= USED_TIMER_COUNT
) {
445 unsigned channel
= timHw
- TIMER_HARDWARE
;
446 if (channel
>= TIMER_CHANNEL_COUNT
)
449 timerChannelInfo
[channel
].type
= type
;
450 unsigned timer
= lookupTimerIndex(timHw
->tim
);
451 if (timer
>= USED_TIMER_COUNT
)
453 if (irqPriority
< timerInfo
[timer
].priority
) {
454 // it would be better to set priority in the end, but current startup sequence is not ready
455 configTimeBase(usedTimers
[timer
], 0, 1);
456 HAL_TIM_Base_Start(&timerHandle
[timerIndex
].Handle
);
458 HAL_NVIC_SetPriority(irq
, NVIC_PRIORITY_BASE(irqPriority
), NVIC_PRIORITY_SUB(irqPriority
));
459 HAL_NVIC_EnableIRQ(irq
);
461 timerInfo
[timer
].priority
= irqPriority
;
465 void timerChCCHandlerInit(timerCCHandlerRec_t
*self
, timerCCHandlerCallback
*fn
)
470 void timerChOvrHandlerInit(timerOvrHandlerRec_t
*self
, timerOvrHandlerCallback
*fn
)
476 // update overflow callback list
477 // some synchronization mechanism is neccesary to avoid disturbing other channels (BASEPRI used now)
478 static void timerChConfig_UpdateOverflow(timerConfig_t
*cfg
, const TIM_TypeDef
*tim
)
480 uint8_t timerIndex
= lookupTimerIndex(tim
);
481 if (timerIndex
>= USED_TIMER_COUNT
) {
485 timerOvrHandlerRec_t
**chain
= &cfg
->overflowCallbackActive
;
486 ATOMIC_BLOCK(NVIC_PRIO_TIMER
) {
488 if (cfg
->updateCallback
) {
489 *chain
= cfg
->updateCallback
;
490 chain
= &cfg
->updateCallback
->next
;
493 for (int i
= 0; i
< CC_CHANNELS_PER_TIMER
; i
++)
494 if (cfg
->overflowCallback
[i
]) {
495 *chain
= cfg
->overflowCallback
[i
];
496 chain
= &cfg
->overflowCallback
[i
]->next
;
500 // enable or disable IRQ
501 if (cfg
->overflowCallbackActive
)
502 __HAL_TIM_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_UPDATE
);
504 __HAL_TIM_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_UPDATE
);
507 // config edge and overflow callback for channel. Try to avoid overflowCallback, it is a bit expensive
508 void timerChConfigCallbacks(const timerHardware_t
*timHw
, timerCCHandlerRec_t
*edgeCallback
, timerOvrHandlerRec_t
*overflowCallback
)
510 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
511 if (timerIndex
>= USED_TIMER_COUNT
) {
514 uint8_t channelIndex
= lookupChannelIndex(timHw
->channel
);
515 if (edgeCallback
== NULL
) // disable irq before changing callback to NULL
516 __HAL_TIM_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
));
517 // setup callback info
518 timerConfig
[timerIndex
].edgeCallback
[channelIndex
] = edgeCallback
;
519 timerConfig
[timerIndex
].overflowCallback
[channelIndex
] = overflowCallback
;
520 // enable channel IRQ
522 __HAL_TIM_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
));
524 timerChConfig_UpdateOverflow(&timerConfig
[timerIndex
], timHw
->tim
);
527 void timerConfigUpdateCallback(const TIM_TypeDef
*tim
, timerOvrHandlerRec_t
*updateCallback
)
529 uint8_t timerIndex
= lookupTimerIndex(tim
);
530 if (timerIndex
>= USED_TIMER_COUNT
) {
533 timerConfig
[timerIndex
].updateCallback
= updateCallback
;
534 timerChConfig_UpdateOverflow(&timerConfig
[timerIndex
], tim
);
537 // configure callbacks for pair of channels (1+2 or 3+4).
538 // Hi(2,4) and Lo(1,3) callbacks are specified, it is not important which timHw channel is used.
539 // This is intended for dual capture mode (each channel handles one transition)
540 void timerChConfigCallbacksDual(const timerHardware_t
*timHw
, timerCCHandlerRec_t
*edgeCallbackLo
, timerCCHandlerRec_t
*edgeCallbackHi
, timerOvrHandlerRec_t
*overflowCallback
)
542 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
543 if (timerIndex
>= USED_TIMER_COUNT
) {
546 uint16_t chLo
= timHw
->channel
& ~TIM_CHANNEL_2
; // lower channel
547 uint16_t chHi
= timHw
->channel
| TIM_CHANNEL_2
; // upper channel
548 uint8_t channelIndex
= lookupChannelIndex(chLo
); // get index of lower channel
550 if (edgeCallbackLo
== NULL
) // disable irq before changing setting callback to NULL
551 __HAL_TIM_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chLo
));
552 if (edgeCallbackHi
== NULL
) // disable irq before changing setting callback to NULL
553 __HAL_TIM_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chHi
));
555 // setup callback info
556 timerConfig
[timerIndex
].edgeCallback
[channelIndex
] = edgeCallbackLo
;
557 timerConfig
[timerIndex
].edgeCallback
[channelIndex
+ 1] = edgeCallbackHi
;
558 timerConfig
[timerIndex
].overflowCallback
[channelIndex
] = overflowCallback
;
559 timerConfig
[timerIndex
].overflowCallback
[channelIndex
+ 1] = NULL
;
561 // enable channel IRQs
562 if (edgeCallbackLo
) {
563 __HAL_TIM_CLEAR_FLAG(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chLo
));
564 __HAL_TIM_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chLo
));
566 if (edgeCallbackHi
) {
567 __HAL_TIM_CLEAR_FLAG(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chHi
));
568 __HAL_TIM_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chHi
));
571 timerChConfig_UpdateOverflow(&timerConfig
[timerIndex
], timHw
->tim
);
574 // enable/disable IRQ for low channel in dual configuration
575 //void timerChITConfigDualLo(const timerHardware_t *timHw, FunctionalState newState) {
576 // TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel&~TIM_Channel_2), newState);
578 // enable/disable IRQ for low channel in dual configuration
579 void timerChITConfigDualLo(const timerHardware_t
*timHw
, FunctionalState newState
)
581 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
582 if (timerIndex
>= USED_TIMER_COUNT
) {
587 __HAL_TIM_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
& ~TIM_CHANNEL_2
));
589 __HAL_TIM_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
& ~TIM_CHANNEL_2
));
592 //// enable or disable IRQ
593 //void timerChITConfig(const timerHardware_t *timHw, FunctionalState newState)
595 // TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), newState);
597 // enable or disable IRQ
598 void timerChITConfig(const timerHardware_t
*timHw
, FunctionalState newState
)
600 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
601 if (timerIndex
>= USED_TIMER_COUNT
) {
606 __HAL_TIM_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
));
608 __HAL_TIM_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
));
611 // clear Compare/Capture flag for channel
612 //void timerChClearCCFlag(const timerHardware_t *timHw)
614 // TIM_ClearFlag(timHw->tim, TIM_IT_CCx(timHw->channel));
616 // clear Compare/Capture flag for channel
617 void timerChClearCCFlag(const timerHardware_t
*timHw
)
619 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
620 if (timerIndex
>= USED_TIMER_COUNT
) {
624 __HAL_TIM_CLEAR_FLAG(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
));
627 // configure timer channel GPIO mode
628 void timerChConfigGPIO(const timerHardware_t
* timHw
, ioConfig_t mode
)
630 IOInit(IOGetByTag(timHw
->tag
), OWNER_TIMER
, 0);
631 IOConfigGPIO(IOGetByTag(timHw
->tag
), mode
);
634 // calculate input filter constant
635 // TODO - we should probably setup DTS to higher value to allow reasonable input filtering
636 // - notice that prescaler[0] does use DTS for sampling - the sequence won't be monotonous anymore
637 static unsigned getFilter(unsigned ticks
)
639 static const unsigned ftab
[16] = {
641 1*2, 1*4, 1*8, // fCK_INT
648 for (unsigned i
= 1; i
< ARRAYLEN(ftab
); i
++)
654 // Configure input captupre
655 void timerChConfigIC(const timerHardware_t
*timHw
, bool polarityRising
, unsigned inputFilterTicks
)
657 unsigned timer
= lookupTimerIndex(timHw
->tim
);
658 if (timer
>= USED_TIMER_COUNT
)
661 TIM_IC_InitTypeDef TIM_ICInitStructure
;
663 TIM_ICInitStructure
.ICPolarity
= polarityRising
? TIM_ICPOLARITY_RISING
: TIM_ICPOLARITY_FALLING
;
664 TIM_ICInitStructure
.ICSelection
= TIM_ICSELECTION_DIRECTTI
;
665 TIM_ICInitStructure
.ICPrescaler
= TIM_ICPSC_DIV1
;
666 TIM_ICInitStructure
.ICFilter
= getFilter(inputFilterTicks
);
667 HAL_TIM_IC_ConfigChannel(&timerHandle
[timer
].Handle
, &TIM_ICInitStructure
, timHw
->channel
);
670 // configure dual channel input channel for capture
671 // polarity is for Low channel (capture order is always Lo - Hi)
672 void timerChConfigICDual(const timerHardware_t
*timHw
, bool polarityRising
, unsigned inputFilterTicks
)
674 unsigned timer
= lookupTimerIndex(timHw
->tim
);
675 if (timer
>= USED_TIMER_COUNT
)
678 TIM_IC_InitTypeDef TIM_ICInitStructure
;
679 bool directRising
= (timHw
->channel
& TIM_CHANNEL_2
) ? !polarityRising
: polarityRising
;
681 // configure direct channel
682 TIM_ICInitStructure
.ICPolarity
= directRising
? TIM_ICPOLARITY_RISING
: TIM_ICPOLARITY_FALLING
;
683 TIM_ICInitStructure
.ICSelection
= TIM_ICSELECTION_DIRECTTI
;
684 TIM_ICInitStructure
.ICPrescaler
= TIM_ICPSC_DIV1
;
685 TIM_ICInitStructure
.ICFilter
= getFilter(inputFilterTicks
);
686 HAL_TIM_IC_ConfigChannel(&timerHandle
[timer
].Handle
, &TIM_ICInitStructure
, timHw
->channel
);
688 // configure indirect channel
689 TIM_ICInitStructure
.ICPolarity
= directRising
? TIM_ICPOLARITY_FALLING
: TIM_ICPOLARITY_RISING
;
690 TIM_ICInitStructure
.ICSelection
= TIM_ICSELECTION_INDIRECTTI
;
691 HAL_TIM_IC_ConfigChannel(&timerHandle
[timer
].Handle
, &TIM_ICInitStructure
, timHw
->channel
^ TIM_CHANNEL_2
);
694 void timerChICPolarity(const timerHardware_t
*timHw
, bool polarityRising
)
696 timCCER_t tmpccer
= timHw
->tim
->CCER
;
697 tmpccer
&= ~(TIM_CCER_CC1P
<< timHw
->channel
);
698 tmpccer
|= polarityRising
? (TIM_ICPOLARITY_RISING
<< timHw
->channel
) : (TIM_ICPOLARITY_FALLING
<< timHw
->channel
);
699 timHw
->tim
->CCER
= tmpccer
;
702 volatile timCCR_t
* timerChCCRHi(const timerHardware_t
*timHw
)
704 return (volatile timCCR_t
*)((volatile char*)&timHw
->tim
->CCR1
+ (timHw
->channel
| TIM_CHANNEL_2
));
707 volatile timCCR_t
* timerChCCRLo(const timerHardware_t
*timHw
)
709 return (volatile timCCR_t
*)((volatile char*)&timHw
->tim
->CCR1
+ (timHw
->channel
& ~TIM_CHANNEL_2
));
712 volatile timCCR_t
* timerChCCR(const timerHardware_t
*timHw
)
714 return (volatile timCCR_t
*)((volatile char*)&timHw
->tim
->CCR1
+ timHw
->channel
);
717 void timerChConfigOC(const timerHardware_t
* timHw
, bool outEnable
, bool stateHigh
)
719 unsigned timer
= lookupTimerIndex(timHw
->tim
);
720 if (timer
>= USED_TIMER_COUNT
)
723 TIM_OC_InitTypeDef TIM_OCInitStructure
;
725 TIM_OCInitStructure
.OCMode
= TIM_OCMODE_INACTIVE
;
726 TIM_OCInitStructure
.Pulse
= 0x00000000;
727 TIM_OCInitStructure
.OCPolarity
= stateHigh
? TIM_OCPOLARITY_HIGH
: TIM_OCPOLARITY_LOW
;
728 TIM_OCInitStructure
.OCNPolarity
= TIM_OCPOLARITY_HIGH
;
729 TIM_OCInitStructure
.OCIdleState
= TIM_OCIDLESTATE_RESET
;
730 TIM_OCInitStructure
.OCNIdleState
= TIM_OCNIDLESTATE_RESET
;
732 HAL_TIM_OC_ConfigChannel(&timerHandle
[timer
].Handle
, &TIM_OCInitStructure
, timHw
->channel
);
735 TIM_OCInitStructure
.OCMode
= TIM_OCMODE_INACTIVE
;
736 HAL_TIM_OC_ConfigChannel(&timerHandle
[timer
].Handle
, &TIM_OCInitStructure
, timHw
->channel
);
737 HAL_TIM_OC_Start(&timerHandle
[timer
].Handle
, timHw
->channel
);
739 TIM_OCInitStructure
.OCMode
= TIM_OCMODE_TIMING
;
740 HAL_TIM_OC_ConfigChannel(&timerHandle
[timer
].Handle
, &TIM_OCInitStructure
, timHw
->channel
);
741 HAL_TIM_OC_Start_IT(&timerHandle
[timer
].Handle
, timHw
->channel
);
745 static void timCCxHandler(TIM_TypeDef
*tim
, timerConfig_t
*timerConfig
)
749 tim_status
= tim
->SR
& tim
->DIER
;
752 // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
753 // currrent order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
754 unsigned bit
= __builtin_clz(tim_status
);
755 unsigned mask
= ~(0x80000000 >> bit
);
759 case __builtin_clz(TIM_IT_UPDATE
): {
761 if (timerConfig
->forcedOverflowTimerValue
!= 0) {
762 capture
= timerConfig
->forcedOverflowTimerValue
- 1;
763 timerConfig
->forcedOverflowTimerValue
= 0;
768 timerOvrHandlerRec_t
*cb
= timerConfig
->overflowCallbackActive
;
775 case __builtin_clz(TIM_IT_CC1
):
776 timerConfig
->edgeCallback
[0]->fn(timerConfig
->edgeCallback
[0], tim
->CCR1
);
778 case __builtin_clz(TIM_IT_CC2
):
779 timerConfig
->edgeCallback
[1]->fn(timerConfig
->edgeCallback
[1], tim
->CCR2
);
781 case __builtin_clz(TIM_IT_CC3
):
782 timerConfig
->edgeCallback
[2]->fn(timerConfig
->edgeCallback
[2], tim
->CCR3
);
784 case __builtin_clz(TIM_IT_CC4
):
785 timerConfig
->edgeCallback
[3]->fn(timerConfig
->edgeCallback
[3], tim
->CCR4
);
790 if (tim_status
& (int)TIM_IT_Update
) {
791 tim
->SR
= ~TIM_IT_Update
;
793 timerOvrHandlerRec_t
*cb
= timerConfig
->overflowCallbackActive
;
799 if (tim_status
& (int)TIM_IT_CC1
) {
800 tim
->SR
= ~TIM_IT_CC1
;
801 timerConfig
->edgeCallback
[0]->fn(timerConfig
->edgeCallback
[0], tim
->CCR1
);
803 if (tim_status
& (int)TIM_IT_CC2
) {
804 tim
->SR
= ~TIM_IT_CC2
;
805 timerConfig
->edgeCallback
[1]->fn(timerConfig
->edgeCallback
[1], tim
->CCR2
);
807 if (tim_status
& (int)TIM_IT_CC3
) {
808 tim
->SR
= ~TIM_IT_CC3
;
809 timerConfig
->edgeCallback
[2]->fn(timerConfig
->edgeCallback
[2], tim
->CCR3
);
811 if (tim_status
& (int)TIM_IT_CC4
) {
812 tim
->SR
= ~TIM_IT_CC4
;
813 timerConfig
->edgeCallback
[3]->fn(timerConfig
->edgeCallback
[3], tim
->CCR4
);
818 static inline void timUpdateHandler(TIM_TypeDef
*tim
, timerConfig_t
*timerConfig
)
822 tim_status
= tim
->SR
& tim
->DIER
;
824 // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
825 // currrent order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
826 unsigned bit
= __builtin_clz(tim_status
);
827 unsigned mask
= ~(0x80000000 >> bit
);
831 case __builtin_clz(TIM_IT_UPDATE
): {
833 if (timerConfig
->forcedOverflowTimerValue
!= 0) {
834 capture
= timerConfig
->forcedOverflowTimerValue
- 1;
835 timerConfig
->forcedOverflowTimerValue
= 0;
840 timerOvrHandlerRec_t
*cb
= timerConfig
->overflowCallbackActive
;
851 // handler for shared interrupts when both timers need to check status bits
852 #define _TIM_IRQ_HANDLER2(name, i, j) \
855 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
856 timCCxHandler(TIM ## j, &timerConfig[TIMER_INDEX(j)]); \
859 #define _TIM_IRQ_HANDLER(name, i) \
862 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
865 #define _TIM_IRQ_HANDLER_UPDATE_ONLY(name, i) \
868 timUpdateHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
871 #if USED_TIMERS & TIM_N(1)
872 _TIM_IRQ_HANDLER(TIM1_CC_IRQHandler
, 1);
873 # if defined(STM32H7)
874 _TIM_IRQ_HANDLER(TIM1_UP_IRQHandler
, 1);
875 # elif defined(STM32G4)
876 # if USED_TIMERS & TIM_N(16)
877 _TIM_IRQ_HANDLER2(TIM1_UP_TIM16_IRQHandler
, 1, 16); // both timers are in use
879 _TIM_IRQ_HANDLER(TIM1_UP_TIM16_IRQHandler
, 1); // timer16 is not used timers are in use
882 # if USED_TIMERS & TIM_N(10)
883 _TIM_IRQ_HANDLER2(TIM1_UP_TIM10_IRQHandler
, 1, 10); // both timers are in use
885 _TIM_IRQ_HANDLER(TIM1_UP_TIM10_IRQHandler
, 1); // timer10 is not used
890 #if USED_TIMERS & TIM_N(2)
891 _TIM_IRQ_HANDLER(TIM2_IRQHandler
, 2);
893 #if USED_TIMERS & TIM_N(3)
894 _TIM_IRQ_HANDLER(TIM3_IRQHandler
, 3);
896 #if USED_TIMERS & TIM_N(4)
897 _TIM_IRQ_HANDLER(TIM4_IRQHandler
, 4);
899 #if USED_TIMERS & TIM_N(5)
900 _TIM_IRQ_HANDLER(TIM5_IRQHandler
, 5);
903 #if USED_TIMERS & TIM_N(6)
904 # if !(defined(USE_PID_AUDIO) && (defined(STM32H7) || defined(STM32F7)))
905 _TIM_IRQ_HANDLER_UPDATE_ONLY(TIM6_DAC_IRQHandler
, 6);
908 #if USED_TIMERS & TIM_N(7)
909 // The USB VCP_HAL driver conflicts with TIM7, see TIMx_IRQHandler in usbd_cdc_interface.h
910 # if !(defined(USE_VCP) && (defined(STM32F4) || defined(STM32G4) || defined(STM32H7) || defined(STM32F7)))
911 # if defined(STM32G4)
912 _TIM_IRQ_HANDLER_UPDATE_ONLY(TIM7_DAC_IRQHandler
, 7);
914 _TIM_IRQ_HANDLER_UPDATE_ONLY(TIM7_IRQHandler
, 7);
919 #if USED_TIMERS & TIM_N(8)
920 _TIM_IRQ_HANDLER(TIM8_CC_IRQHandler
, 8);
921 # if defined(STM32G4)
922 _TIM_IRQ_HANDLER(TIM8_UP_IRQHandler
, 8);
925 # if USED_TIMERS & TIM_N(13)
926 _TIM_IRQ_HANDLER2(TIM8_UP_TIM13_IRQHandler
, 8, 13); // both timers are in use
928 _TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler
, 8); // timer13 is not used
932 #if USED_TIMERS & TIM_N(9)
933 _TIM_IRQ_HANDLER(TIM1_BRK_TIM9_IRQHandler
, 9);
935 # if USED_TIMERS & TIM_N(11)
936 _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM11_IRQHandler
, 11);
938 #if USED_TIMERS & TIM_N(12)
939 _TIM_IRQ_HANDLER(TIM8_BRK_TIM12_IRQHandler
, 12);
941 #if defined(STM32H7) && (USED_TIMERS & TIM_N(14))
942 _TIM_IRQ_HANDLER(TIM8_TRG_COM_TIM14_IRQHandler
, 14);
944 #if USED_TIMERS & TIM_N(15)
945 # if defined(STM32H7)
946 _TIM_IRQ_HANDLER(TIM15_IRQHandler
, 15);
948 _TIM_IRQ_HANDLER(TIM1_BRK_TIM15_IRQHandler
, 15);
951 #if defined(STM32H7) && (USED_TIMERS & TIM_N(16))
952 _TIM_IRQ_HANDLER(TIM16_IRQHandler
, 16);
954 #if defined(STM32F303xC) && ((USED_TIMERS & (TIM_N(1)|TIM_N(16))) == (TIM_N(16)))
955 _TIM_IRQ_HANDLER(TIM1_UP_TIM16_IRQHandler
, 16); // only timer16 is used, not timer1
957 #if USED_TIMERS & TIM_N(17)
958 # if defined(STM32H7)
959 _TIM_IRQ_HANDLER(TIM17_IRQHandler
, 17);
961 _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM17_IRQHandler
, 17);
964 #if USED_TIMERS & TIM_N(20)
965 _TIM_IRQ_HANDLER(TIM20_CC_IRQHandler
, 20);
970 memset(timerConfig
, 0, sizeof(timerConfig
));
972 #if USED_TIMERS & TIM_N(1)
973 __HAL_RCC_TIM1_CLK_ENABLE();
975 #if USED_TIMERS & TIM_N(2)
976 __HAL_RCC_TIM2_CLK_ENABLE();
978 #if USED_TIMERS & TIM_N(3)
979 __HAL_RCC_TIM3_CLK_ENABLE();
981 #if USED_TIMERS & TIM_N(4)
982 __HAL_RCC_TIM4_CLK_ENABLE();
984 #if USED_TIMERS & TIM_N(5)
985 __HAL_RCC_TIM5_CLK_ENABLE();
987 #if USED_TIMERS & TIM_N(6)
988 __HAL_RCC_TIM6_CLK_ENABLE();
990 #if USED_TIMERS & TIM_N(7)
991 __HAL_RCC_TIM7_CLK_ENABLE();
993 #if USED_TIMERS & TIM_N(8)
994 __HAL_RCC_TIM8_CLK_ENABLE();
996 #if !defined(STM32H7)
997 #if USED_TIMERS & TIM_N(9)
998 __HAL_RCC_TIM9_CLK_ENABLE();
1000 #if USED_TIMERS & TIM_N(10)
1001 __HAL_RCC_TIM10_CLK_ENABLE();
1003 #if USED_TIMERS & TIM_N(11)
1004 __HAL_RCC_TIM11_CLK_ENABLE();
1007 #if USED_TIMERS & TIM_N(12)
1008 __HAL_RCC_TIM12_CLK_ENABLE();
1010 #if USED_TIMERS & TIM_N(13)
1011 __HAL_RCC_TIM13_CLK_ENABLE();
1013 #if USED_TIMERS & TIM_N(14)
1014 __HAL_RCC_TIM14_CLK_ENABLE();
1016 #if USED_TIMERS & TIM_N(15)
1017 __HAL_RCC_TIM15_CLK_ENABLE();
1019 #if USED_TIMERS & TIM_N(16)
1020 __HAL_RCC_TIM16_CLK_ENABLE();
1022 #if USED_TIMERS & TIM_N(17)
1023 __HAL_RCC_TIM17_CLK_ENABLE();
1025 #if USED_TIMERS & TIM_N(20)
1026 __HAL_RCC_TIM20_CLK_ENABLE();
1029 /* enable the timer peripherals */
1030 for (int i
= 0; i
< TIMER_CHANNEL_COUNT
; i
++) {
1031 RCC_ClockCmd(timerRCC(TIMER_HARDWARE
[i
].tim
), ENABLE
);
1034 #if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
1035 for (unsigned timerIndex
= 0; timerIndex
< TIMER_CHANNEL_COUNT
; timerIndex
++) {
1036 const timerHardware_t
*timerHardwarePtr
= &TIMER_HARDWARE
[timerIndex
];
1037 if (timerHardwarePtr
->usageFlags
== TIM_USE_NONE
) {
1040 // XXX IOConfigGPIOAF in timerInit should eventually go away.
1041 IOConfigGPIOAF(IOGetByTag(timerHardwarePtr
->tag
), IOCFG_AF_PP
, timerHardwarePtr
->alternateFunction
);
1045 /* enable the timer peripherals */
1046 for (unsigned i
= 0; i
< TIMER_CHANNEL_COUNT
; i
++) {
1047 RCC_ClockCmd(timerRCC(TIMER_HARDWARE
[i
].tim
), ENABLE
);
1050 // initialize timer channel structures
1051 for (unsigned i
= 0; i
< TIMER_CHANNEL_COUNT
; i
++) {
1052 timerChannelInfo
[i
].type
= TYPE_FREE
;
1055 for (unsigned i
= 0; i
< USED_TIMER_COUNT
; i
++) {
1056 timerInfo
[i
].priority
= ~0;
1060 // finish configuring timers after allocation phase
1062 // TODO - Work in progress - initialization routine must be modified/verified to start correctly without timers
1063 void timerStart(void)
1066 for (unsigned timer
= 0; timer
< USED_TIMER_COUNT
; timer
++) {
1069 for (unsigned hwc
= 0; hwc
< TIMER_CHANNEL_COUNT
; hwc
++) {
1070 if ((timerChannelInfo
[hwc
].type
!= TYPE_FREE
) && (TIMER_HARDWARE
[hwc
].tim
== usedTimers
[timer
])) {
1071 // TODO - move IRQ to timer info
1072 irq
= TIMER_HARDWARE
[hwc
].irq
;
1075 // TODO - aggregate required timer paramaters
1076 configTimeBase(usedTimers
[timer
], 0, 1);
1077 TIM_Cmd(usedTimers
[timer
], ENABLE
);
1078 if (priority
>= 0) { // maybe none of the channels was configured
1079 NVIC_InitTypeDef NVIC_InitStructure
;
1081 NVIC_InitStructure
.NVIC_IRQChannel
= irq
;
1082 NVIC_InitStructure
.NVIC_IRQChannelPreemptionPriority
= NVIC_SPLIT_PRIORITY_BASE(priority
);
1083 NVIC_InitStructure
.NVIC_IRQChannelSubPriority
= NVIC_SPLIT_PRIORITY_SUB(priority
);
1084 NVIC_InitStructure
.NVIC_IRQChannelCmd
= ENABLE
;
1085 NVIC_Init(&NVIC_InitStructure
);
1092 * Force an overflow for a given timer.
1093 * Saves the current value of the counter in the relevant timerConfig's forcedOverflowTimerValue variable.
1094 * @param TIM_Typedef *tim The timer to overflow
1097 void timerForceOverflow(TIM_TypeDef
*tim
)
1099 uint8_t timerIndex
= lookupTimerIndex((const TIM_TypeDef
*)tim
);
1101 ATOMIC_BLOCK(NVIC_PRIO_TIMER
) {
1102 // Save the current count so that PPM reading will work on the same timer that was forced to overflow
1103 timerConfig
[timerIndex
].forcedOverflowTimerValue
= tim
->CNT
+ 1;
1105 // Force an overflow by setting the UG bit
1106 tim
->EGR
|= TIM_EGR_UG
;
1111 uint16_t timerDmaIndex(uint8_t channel
)
1115 return TIM_DMA_ID_CC1
;
1117 return TIM_DMA_ID_CC2
;
1119 return TIM_DMA_ID_CC3
;
1121 return TIM_DMA_ID_CC4
;
1127 uint16_t timerDmaSource(uint8_t channel
)
1142 uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef
*tim
, uint16_t mhz
)
1144 return timerGetPrescalerByDesiredHertz(tim
, MHZ_TO_HZ(mhz
));
1147 uint16_t timerGetPeriodByPrescaler(TIM_TypeDef
*tim
, uint16_t prescaler
, uint32_t hz
)
1149 return (uint16_t)((timerClock(tim
) / (prescaler
+ 1)) / hz
);
1152 uint16_t timerGetPrescalerByDesiredHertz(TIM_TypeDef
*tim
, uint32_t hz
)
1154 // protection here for desired hertz > SystemCoreClock???
1155 if (hz
> timerClock(tim
)) {
1158 return (uint16_t)((timerClock(tim
) + hz
/ 2) / hz
) - 1;
1161 HAL_StatusTypeDef
TIM_DMACmd(TIM_HandleTypeDef
*htim
, uint32_t Channel
, FunctionalState NewState
)
1164 case TIM_CHANNEL_1
: {
1165 if (NewState
!= DISABLE
) {
1166 /* Enable the TIM Capture/Compare 1 DMA request */
1167 __HAL_TIM_ENABLE_DMA(htim
, TIM_DMA_CC1
);
1169 /* Disable the TIM Capture/Compare 1 DMA request */
1170 __HAL_TIM_DISABLE_DMA(htim
, TIM_DMA_CC1
);
1175 case TIM_CHANNEL_2
: {
1176 if (NewState
!= DISABLE
) {
1177 /* Enable the TIM Capture/Compare 2 DMA request */
1178 __HAL_TIM_ENABLE_DMA(htim
, TIM_DMA_CC2
);
1180 /* Disable the TIM Capture/Compare 2 DMA request */
1181 __HAL_TIM_DISABLE_DMA(htim
, TIM_DMA_CC2
);
1186 case TIM_CHANNEL_3
: {
1187 if (NewState
!= DISABLE
) {
1188 /* Enable the TIM Capture/Compare 3 DMA request */
1189 __HAL_TIM_ENABLE_DMA(htim
, TIM_DMA_CC3
);
1191 /* Disable the TIM Capture/Compare 3 DMA request */
1192 __HAL_TIM_DISABLE_DMA(htim
, TIM_DMA_CC3
);
1197 case TIM_CHANNEL_4
: {
1198 if (NewState
!= DISABLE
) {
1199 /* Enable the TIM Capture/Compare 4 DMA request */
1200 __HAL_TIM_ENABLE_DMA(htim
, TIM_DMA_CC4
);
1202 /* Disable the TIM Capture/Compare 4 DMA request */
1203 __HAL_TIM_DISABLE_DMA(htim
, TIM_DMA_CC4
);
1211 /* Change the htim state */
1212 htim
->State
= HAL_TIM_STATE_READY
;
1213 /* Return function status */
1217 HAL_StatusTypeDef
DMA_SetCurrDataCounter(TIM_HandleTypeDef
*htim
, uint32_t Channel
, uint32_t *pData
, uint16_t Length
)
1219 if ((htim
->State
== HAL_TIM_STATE_BUSY
)) {
1221 } else if ((htim
->State
== HAL_TIM_STATE_READY
)) {
1222 if (((uint32_t) pData
== 0) && (Length
> 0)) {
1225 htim
->State
= HAL_TIM_STATE_BUSY
;
1229 case TIM_CHANNEL_1
: {
1230 /* Set the DMA Period elapsed callback */
1231 htim
->hdma
[TIM_DMA_ID_CC1
]->XferCpltCallback
= HAL_TIM_DMADelayPulseCplt
;
1233 /* Set the DMA error callback */
1234 htim
->hdma
[TIM_DMA_ID_CC1
]->XferErrorCallback
= HAL_TIM_DMAError
;
1236 /* Enable the DMA Stream */
1237 HAL_DMA_Start_IT(htim
->hdma
[TIM_DMA_ID_CC1
], (uint32_t) pData
, (uint32_t) & htim
->Instance
->CCR1
, Length
);
1241 case TIM_CHANNEL_2
: {
1242 /* Set the DMA Period elapsed callback */
1243 htim
->hdma
[TIM_DMA_ID_CC2
]->XferCpltCallback
= HAL_TIM_DMADelayPulseCplt
;
1245 /* Set the DMA error callback */
1246 htim
->hdma
[TIM_DMA_ID_CC2
]->XferErrorCallback
= HAL_TIM_DMAError
;
1248 /* Enable the DMA Stream */
1249 HAL_DMA_Start_IT(htim
->hdma
[TIM_DMA_ID_CC2
], (uint32_t) pData
, (uint32_t) & htim
->Instance
->CCR2
, Length
);
1253 case TIM_CHANNEL_3
: {
1254 /* Set the DMA Period elapsed callback */
1255 htim
->hdma
[TIM_DMA_ID_CC3
]->XferCpltCallback
= HAL_TIM_DMADelayPulseCplt
;
1257 /* Set the DMA error callback */
1258 htim
->hdma
[TIM_DMA_ID_CC3
]->XferErrorCallback
= HAL_TIM_DMAError
;
1260 /* Enable the DMA Stream */
1261 HAL_DMA_Start_IT(htim
->hdma
[TIM_DMA_ID_CC3
], (uint32_t) pData
, (uint32_t) & htim
->Instance
->CCR3
, Length
);
1265 case TIM_CHANNEL_4
: {
1266 /* Set the DMA Period elapsed callback */
1267 htim
->hdma
[TIM_DMA_ID_CC4
]->XferCpltCallback
= HAL_TIM_DMADelayPulseCplt
;
1269 /* Set the DMA error callback */
1270 htim
->hdma
[TIM_DMA_ID_CC4
]->XferErrorCallback
= HAL_TIM_DMAError
;
1272 /* Enable the DMA Stream */
1273 HAL_DMA_Start_IT(htim
->hdma
[TIM_DMA_ID_CC4
], (uint32_t) pData
, (uint32_t) & htim
->Instance
->CCR4
, Length
);
1280 /* Return function status */