2 * This file is part of Betaflight.
4 * Betaflight is free software. You can redistribute this software
5 * and/or modify this software under the terms of the GNU General
6 * Public License as published by the Free Software Foundation,
7 * either version 3 of the License, or (at your option) any later
10 * Betaflight is distributed in the hope that it will be useful,
11 * but WITHOUT ANY WARRANTY; without even the implied warranty of
12 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
14 * See the GNU General Public License for more details.
16 * You should have received a copy of the GNU General Public
17 * License along with this software.
19 * If not, see <http://www.gnu.org/licenses/>.
31 #include "build/atomic.h"
33 #include "common/utils.h"
35 #include "drivers/nvic.h"
37 #include "drivers/io.h"
38 #include "drivers/dma.h"
40 #include "drivers/rcc.h"
42 #include "drivers/timer.h"
43 #include "drivers/timer_impl.h"
45 #define TIM_N(n) (1 << (n))
48 Groups that allow running different period (ex 50Hz servos + 400Hz throttle + etc):
55 /// TODO: DAL in a lot af calls lookupTimerIndex is used. Instead of passing the timer instance the index should be passed.
56 #define USED_TIMER_COUNT BITCOUNT(USED_TIMERS)
58 #define TIM_IT_CCx(ch) (TMR_IT_CC1 << ((ch) / 4))
60 typedef struct timerConfig_s
{
62 timerOvrHandlerRec_t
*updateCallback
;
65 timerCCHandlerRec_t
*edgeCallback
[CC_CHANNELS_PER_TIMER
];
66 timerOvrHandlerRec_t
*overflowCallback
[CC_CHANNELS_PER_TIMER
];
69 timerOvrHandlerRec_t
*overflowCallbackActive
; // null-terminated linkded list of active overflow callbacks
70 uint32_t forcedOverflowTimerValue
;
72 timerConfig_t timerConfig
[USED_TIMER_COUNT
+ 1];
77 timerChannelInfo_t timerChannelInfo
[TIMER_CHANNEL_COUNT
];
82 timerInfo_t timerInfo
[USED_TIMER_COUNT
+ 1];
85 TMR_HandleTypeDef Handle
;
87 timerHandle_t timerHandle
[USED_TIMER_COUNT
+ 1];
89 // return index of timer in timer table. Lowest timer has index 0
90 #define TIMER_INDEX(i) BITCOUNT((TIM_N(i) - 1) & USED_TIMERS)
92 static uint8_t lookupTimerIndex(const TMR_TypeDef
*tim
)
94 #define _CASE_SHF 10 // amount we can safely shift timer address to the right. gcc will throw error if some timers overlap
95 #define _CASE_(tim, index) case ((unsigned)tim >> _CASE_SHF): return index; break
96 #define _CASE(i) _CASE_(TMR##i##_BASE, TIMER_INDEX(i))
98 // let gcc do the work, switch should be quite optimized
99 switch ((unsigned)tim
>> _CASE_SHF
) {
100 #if USED_TIMERS & TIM_N(1)
103 #if USED_TIMERS & TIM_N(2)
106 #if USED_TIMERS & TIM_N(3)
109 #if USED_TIMERS & TIM_N(4)
112 #if USED_TIMERS & TIM_N(5)
115 #if USED_TIMERS & TIM_N(6)
118 #if USED_TIMERS & TIM_N(7)
121 #if USED_TIMERS & TIM_N(8)
124 #if USED_TIMERS & TIM_N(9)
127 #if USED_TIMERS & TIM_N(10)
130 #if USED_TIMERS & TIM_N(11)
133 #if USED_TIMERS & TIM_N(12)
136 #if USED_TIMERS & TIM_N(13)
139 #if USED_TIMERS & TIM_N(14)
142 #if USED_TIMERS & TIM_N(15)
145 #if USED_TIMERS & TIM_N(16)
148 #if USED_TIMERS & TIM_N(17)
151 #if USED_TIMERS & TIM_N(20)
154 default: return ~1; // make sure final index is out of range
160 TMR_TypeDef
* const usedTimers
[USED_TIMER_COUNT
] = {
161 #define _DEF(i) TMR##i
163 #if USED_TIMERS & TIM_N(1)
166 #if USED_TIMERS & TIM_N(2)
169 #if USED_TIMERS & TIM_N(3)
172 #if USED_TIMERS & TIM_N(4)
175 #if USED_TIMERS & TIM_N(5)
178 #if USED_TIMERS & TIM_N(6)
181 #if USED_TIMERS & TIM_N(7)
184 #if USED_TIMERS & TIM_N(8)
187 #if USED_TIMERS & TIM_N(9)
190 #if USED_TIMERS & TIM_N(10)
193 #if USED_TIMERS & TIM_N(11)
196 #if USED_TIMERS & TIM_N(12)
199 #if USED_TIMERS & TIM_N(13)
202 #if USED_TIMERS & TIM_N(14)
205 #if USED_TIMERS & TIM_N(15)
208 #if USED_TIMERS & TIM_N(16)
211 #if USED_TIMERS & TIM_N(17)
217 // Map timer index to timer number (Straight copy of usedTimers array)
218 const int8_t timerNumbers
[USED_TIMER_COUNT
] = {
221 #if USED_TIMERS & TIM_N(1)
224 #if USED_TIMERS & TIM_N(2)
227 #if USED_TIMERS & TIM_N(3)
230 #if USED_TIMERS & TIM_N(4)
233 #if USED_TIMERS & TIM_N(5)
236 #if USED_TIMERS & TIM_N(6)
239 #if USED_TIMERS & TIM_N(7)
242 #if USED_TIMERS & TIM_N(8)
245 #if USED_TIMERS & TIM_N(9)
248 #if USED_TIMERS & TIM_N(10)
251 #if USED_TIMERS & TIM_N(11)
254 #if USED_TIMERS & TIM_N(12)
257 #if USED_TIMERS & TIM_N(13)
260 #if USED_TIMERS & TIM_N(14)
263 #if USED_TIMERS & TIM_N(15)
266 #if USED_TIMERS & TIM_N(16)
269 #if USED_TIMERS & TIM_N(17)
272 #if USED_TIMERS & TIM_N(20)
278 int8_t timerGetNumberByIndex(uint8_t index
)
280 if (index
< USED_TIMER_COUNT
) {
281 return timerNumbers
[index
];
287 int8_t timerGetTIMNumber(const TMR_TypeDef
*tim
)
289 uint8_t index
= lookupTimerIndex(tim
);
291 return timerGetNumberByIndex(index
);
294 static inline uint8_t lookupChannelIndex(const uint16_t channel
)
299 uint8_t timerLookupChannelIndex(const uint16_t channel
)
301 return lookupChannelIndex(channel
);
304 rccPeriphTag_t
timerRCC(const TMR_TypeDef
*tim
)
306 for (int i
= 0; i
< HARDWARE_TIMER_DEFINITION_COUNT
; i
++) {
307 if (timerDefinitions
[i
].TIMx
== tim
) {
308 return timerDefinitions
[i
].rcc
;
314 uint8_t timerInputIrq(const TMR_TypeDef
*tim
)
316 for (int i
= 0; i
< HARDWARE_TIMER_DEFINITION_COUNT
; i
++) {
317 if (timerDefinitions
[i
].TIMx
== tim
) {
318 return timerDefinitions
[i
].inputIrq
;
324 void timerNVICConfigure(uint8_t irq
)
326 DAL_NVIC_SetPriority(irq
, NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER
), NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER
));
327 DAL_NVIC_EnableIRQ(irq
);
330 TMR_HandleTypeDef
* timerFindTimerHandle(TMR_TypeDef
*tim
)
332 uint8_t timerIndex
= lookupTimerIndex(tim
);
333 if (timerIndex
>= USED_TIMER_COUNT
)
336 return &timerHandle
[timerIndex
].Handle
;
339 void timerReconfigureTimeBase(TMR_TypeDef
*tim
, uint16_t period
, uint32_t hz
)
341 TMR_HandleTypeDef
* handle
= timerFindTimerHandle(tim
);
342 if (handle
== NULL
) return;
344 handle
->Init
.Period
= (period
- 1) & 0xffff; // AKA TIMx_ARR
345 handle
->Init
.Prescaler
= (timerClock(tim
) / hz
) - 1;
347 TMR_Base_SetConfig(handle
->Instance
, &handle
->Init
);
350 void configTimeBase(TMR_TypeDef
*tim
, uint16_t period
, uint32_t hz
)
352 TMR_HandleTypeDef
* handle
= timerFindTimerHandle(tim
);
353 if (handle
== NULL
) return;
355 if (handle
->Instance
== tim
) {
356 // already configured
360 handle
->Instance
= tim
;
362 handle
->Init
.Period
= (period
- 1) & 0xffff; // AKA TIMx_ARR
363 handle
->Init
.Prescaler
= (timerClock(tim
) / hz
) - 1;
365 handle
->Init
.ClockDivision
= TMR_CLOCKDIVISION_DIV1
;
366 handle
->Init
.CounterMode
= TMR_COUNTERMODE_UP
;
367 handle
->Init
.RepetitionCounter
= 0x0000;
369 DAL_TMR_Base_Init(handle
);
370 if (tim
== TMR1
|| tim
== TMR2
|| tim
== TMR3
|| tim
== TMR4
|| tim
== TMR5
|| tim
== TMR8
|| tim
== TMR9
)
372 TMR_ClockConfigTypeDef sClockSourceConfig
;
373 memset(&sClockSourceConfig
, 0, sizeof(sClockSourceConfig
));
374 sClockSourceConfig
.ClockSource
= TMR_CLOCKSOURCE_INTERNAL
;
375 if (DAL_TMR_ConfigClockSource(handle
, &sClockSourceConfig
) != DAL_OK
) {
379 if (tim
== TMR1
|| tim
== TMR2
|| tim
== TMR3
|| tim
== TMR4
|| tim
== TMR5
|| tim
== TMR8
) {
380 TMR_MasterConfigTypeDef sMasterConfig
;
381 memset(&sMasterConfig
, 0, sizeof(sMasterConfig
));
382 sMasterConfig
.MasterSlaveMode
= TMR_MASTERSLAVEMODE_DISABLE
;
383 if (DAL_TMREx_MasterConfigSynchronization(handle
, &sMasterConfig
) != DAL_OK
) {
389 // old interface for PWM inputs. It should be replaced
390 void timerConfigure(const timerHardware_t
*timerHardwarePtr
, uint16_t period
, uint32_t hz
)
392 uint8_t timerIndex
= lookupTimerIndex(timerHardwarePtr
->tim
);
393 if (timerIndex
>= USED_TIMER_COUNT
) {
397 configTimeBase(timerHardwarePtr
->tim
, period
, hz
);
398 DAL_TMR_Base_Start(&timerHandle
[timerIndex
].Handle
);
400 uint8_t irq
= timerInputIrq(timerHardwarePtr
->tim
);
401 timerNVICConfigure(irq
);
402 // HACK - enable second IRQ on timers that need it
406 timerNVICConfigure(TMR1_UP_TMR10_IRQn
);
409 timerNVICConfigure(TMR8_UP_TMR13_IRQn
);
415 // allocate and configure timer channel. Timer priority is set to highest priority of its channels
416 void timerChInit(const timerHardware_t
*timHw
, channelType_t type
, int irqPriority
, uint8_t irq
)
418 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
419 if (timerIndex
>= USED_TIMER_COUNT
) {
422 unsigned channel
= timHw
- TIMER_HARDWARE
;
423 if (channel
>= TIMER_CHANNEL_COUNT
)
426 timerChannelInfo
[channel
].type
= type
;
427 unsigned timer
= lookupTimerIndex(timHw
->tim
);
428 if (timer
>= USED_TIMER_COUNT
)
430 if (irqPriority
< timerInfo
[timer
].priority
) {
431 // it would be better to set priority in the end, but current startup sequence is not ready
432 configTimeBase(usedTimers
[timer
], 0, 1);
433 DAL_TMR_Base_Start(&timerHandle
[timerIndex
].Handle
);
435 DAL_NVIC_SetPriority(irq
, NVIC_PRIORITY_BASE(irqPriority
), NVIC_PRIORITY_SUB(irqPriority
));
436 DAL_NVIC_EnableIRQ(irq
);
438 timerInfo
[timer
].priority
= irqPriority
;
442 void timerChCCHandlerInit(timerCCHandlerRec_t
*self
, timerCCHandlerCallback
*fn
)
447 void timerChOvrHandlerInit(timerOvrHandlerRec_t
*self
, timerOvrHandlerCallback
*fn
)
453 // update overflow callback list
454 // some synchronization mechanism is neccesary to avoid disturbing other channels (BASEPRI used now)
455 static void timerChConfig_UpdateOverflow(timerConfig_t
*cfg
, const TMR_TypeDef
*tim
)
457 uint8_t timerIndex
= lookupTimerIndex(tim
);
458 if (timerIndex
>= USED_TIMER_COUNT
) {
462 timerOvrHandlerRec_t
**chain
= &cfg
->overflowCallbackActive
;
463 ATOMIC_BLOCK(NVIC_PRIO_TIMER
) {
465 if (cfg
->updateCallback
) {
466 *chain
= cfg
->updateCallback
;
467 chain
= &cfg
->updateCallback
->next
;
470 for (int i
= 0; i
< CC_CHANNELS_PER_TIMER
; i
++)
471 if (cfg
->overflowCallback
[i
]) {
472 *chain
= cfg
->overflowCallback
[i
];
473 chain
= &cfg
->overflowCallback
[i
]->next
;
477 // enable or disable IRQ
478 if (cfg
->overflowCallbackActive
)
479 __DAL_TMR_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TMR_IT_UPDATE
);
481 __DAL_TMR_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TMR_IT_UPDATE
);
484 // config edge and overflow callback for channel. Try to avoid overflowCallback, it is a bit expensive
485 void timerChConfigCallbacks(const timerHardware_t
*timHw
, timerCCHandlerRec_t
*edgeCallback
, timerOvrHandlerRec_t
*overflowCallback
)
487 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
488 if (timerIndex
>= USED_TIMER_COUNT
) {
491 uint8_t channelIndex
= lookupChannelIndex(timHw
->channel
);
492 if (edgeCallback
== NULL
) // disable irq before changing callback to NULL
493 __DAL_TMR_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
));
494 // setup callback info
495 timerConfig
[timerIndex
].edgeCallback
[channelIndex
] = edgeCallback
;
496 timerConfig
[timerIndex
].overflowCallback
[channelIndex
] = overflowCallback
;
497 // enable channel IRQ
499 __DAL_TMR_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
));
501 timerChConfig_UpdateOverflow(&timerConfig
[timerIndex
], timHw
->tim
);
504 void timerConfigUpdateCallback(const TMR_TypeDef
*tim
, timerOvrHandlerRec_t
*updateCallback
)
506 uint8_t timerIndex
= lookupTimerIndex(tim
);
507 if (timerIndex
>= USED_TIMER_COUNT
) {
510 timerConfig
[timerIndex
].updateCallback
= updateCallback
;
511 timerChConfig_UpdateOverflow(&timerConfig
[timerIndex
], tim
);
514 // configure callbacks for pair of channels (1+2 or 3+4).
515 // Hi(2,4) and Lo(1,3) callbacks are specified, it is not important which timHw channel is used.
516 // This is intended for dual capture mode (each channel handles one transition)
517 void timerChConfigCallbacksDual(const timerHardware_t
*timHw
, timerCCHandlerRec_t
*edgeCallbackLo
, timerCCHandlerRec_t
*edgeCallbackHi
, timerOvrHandlerRec_t
*overflowCallback
)
519 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
520 if (timerIndex
>= USED_TIMER_COUNT
) {
523 uint16_t chLo
= timHw
->channel
& ~TMR_CHANNEL_2
; // lower channel
524 uint16_t chHi
= timHw
->channel
| TMR_CHANNEL_2
; // upper channel
525 uint8_t channelIndex
= lookupChannelIndex(chLo
); // get index of lower channel
527 if (edgeCallbackLo
== NULL
) // disable irq before changing setting callback to NULL
528 __DAL_TMR_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chLo
));
529 if (edgeCallbackHi
== NULL
) // disable irq before changing setting callback to NULL
530 __DAL_TMR_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chHi
));
532 // setup callback info
533 timerConfig
[timerIndex
].edgeCallback
[channelIndex
] = edgeCallbackLo
;
534 timerConfig
[timerIndex
].edgeCallback
[channelIndex
+ 1] = edgeCallbackHi
;
535 timerConfig
[timerIndex
].overflowCallback
[channelIndex
] = overflowCallback
;
536 timerConfig
[timerIndex
].overflowCallback
[channelIndex
+ 1] = NULL
;
538 // enable channel IRQs
539 if (edgeCallbackLo
) {
540 __DAL_TMR_CLEAR_FLAG(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chLo
));
541 __DAL_TMR_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chLo
));
543 if (edgeCallbackHi
) {
544 __DAL_TMR_CLEAR_FLAG(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chHi
));
545 __DAL_TMR_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(chHi
));
548 timerChConfig_UpdateOverflow(&timerConfig
[timerIndex
], timHw
->tim
);
551 // enable/disable IRQ for low channel in dual configuration
552 //void timerChITConfigDualLo(const timerHardware_t *timHw, FunctionalState newState) {
553 // TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel&~TIM_Channel_2), newState);
555 // enable/disable IRQ for low channel in dual configuration
556 void timerChITConfigDualLo(const timerHardware_t
*timHw
, FunctionalState newState
)
558 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
559 if (timerIndex
>= USED_TIMER_COUNT
) {
564 __DAL_TMR_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
& ~TMR_CHANNEL_2
));
566 __DAL_TMR_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
& ~TMR_CHANNEL_2
));
569 //// enable or disable IRQ
570 //void timerChITConfig(const timerHardware_t *timHw, FunctionalState newState)
572 // TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), newState);
574 // enable or disable IRQ
575 void timerChITConfig(const timerHardware_t
*timHw
, FunctionalState newState
)
577 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
578 if (timerIndex
>= USED_TIMER_COUNT
) {
583 __DAL_TMR_ENABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
));
585 __DAL_TMR_DISABLE_IT(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
));
588 // clear Compare/Capture flag for channel
589 //void timerChClearCCFlag(const timerHardware_t *timHw)
591 // TIM_ClearFlag(timHw->tim, TIM_IT_CCx(timHw->channel));
593 // clear Compare/Capture flag for channel
594 void timerChClearCCFlag(const timerHardware_t
*timHw
)
596 uint8_t timerIndex
= lookupTimerIndex(timHw
->tim
);
597 if (timerIndex
>= USED_TIMER_COUNT
) {
601 __DAL_TMR_CLEAR_FLAG(&timerHandle
[timerIndex
].Handle
, TIM_IT_CCx(timHw
->channel
));
604 // configure timer channel GPIO mode
605 void timerChConfigGPIO(const timerHardware_t
* timHw
, ioConfig_t mode
)
607 IOInit(IOGetByTag(timHw
->tag
), OWNER_TIMER
, 0);
608 IOConfigGPIO(IOGetByTag(timHw
->tag
), mode
);
611 // calculate input filter constant
612 // TODO - we should probably setup DTS to higher value to allow reasonable input filtering
613 // - notice that prescaler[0] does use DTS for sampling - the sequence won't be monotonous anymore
614 static unsigned getFilter(unsigned ticks
)
616 static const unsigned ftab
[16] = {
618 1*2, 1*4, 1*8, // fCK_INT
625 for (unsigned i
= 1; i
< ARRAYLEN(ftab
); i
++)
631 // Configure input captupre
632 void timerChConfigIC(const timerHardware_t
*timHw
, bool polarityRising
, unsigned inputFilterTicks
)
634 unsigned timer
= lookupTimerIndex(timHw
->tim
);
635 if (timer
>= USED_TIMER_COUNT
)
638 TMR_IC_InitTypeDef TIM_ICInitStructure
;
640 TIM_ICInitStructure
.ICPolarity
= polarityRising
? TMR_ICPOLARITY_RISING
: TMR_ICPOLARITY_FALLING
;
641 TIM_ICInitStructure
.ICSelection
= TMR_ICSELECTION_DIRECTTI
;
642 TIM_ICInitStructure
.ICPrescaler
= TMR_ICPSC_DIV1
;
643 TIM_ICInitStructure
.ICFilter
= getFilter(inputFilterTicks
);
644 DAL_TMR_IC_ConfigChannel(&timerHandle
[timer
].Handle
, &TIM_ICInitStructure
, timHw
->channel
);
647 // configure dual channel input channel for capture
648 // polarity is for Low channel (capture order is always Lo - Hi)
649 void timerChConfigICDual(const timerHardware_t
*timHw
, bool polarityRising
, unsigned inputFilterTicks
)
651 unsigned timer
= lookupTimerIndex(timHw
->tim
);
652 if (timer
>= USED_TIMER_COUNT
)
655 TMR_IC_InitTypeDef TIM_ICInitStructure
;
656 bool directRising
= (timHw
->channel
& TMR_CHANNEL_2
) ? !polarityRising
: polarityRising
;
658 // configure direct channel
659 TIM_ICInitStructure
.ICPolarity
= directRising
? TMR_ICPOLARITY_RISING
: TMR_ICPOLARITY_FALLING
;
660 TIM_ICInitStructure
.ICSelection
= TMR_ICSELECTION_DIRECTTI
;
661 TIM_ICInitStructure
.ICPrescaler
= TMR_ICPSC_DIV1
;
662 TIM_ICInitStructure
.ICFilter
= getFilter(inputFilterTicks
);
663 DAL_TMR_IC_ConfigChannel(&timerHandle
[timer
].Handle
, &TIM_ICInitStructure
, timHw
->channel
);
665 // configure indirect channel
666 TIM_ICInitStructure
.ICPolarity
= directRising
? TMR_ICPOLARITY_FALLING
: TMR_ICPOLARITY_RISING
;
667 TIM_ICInitStructure
.ICSelection
= TMR_ICSELECTION_INDIRECTTI
;
668 DAL_TMR_IC_ConfigChannel(&timerHandle
[timer
].Handle
, &TIM_ICInitStructure
, timHw
->channel
^ TMR_CHANNEL_2
);
671 void timerChICPolarity(const timerHardware_t
*timHw
, bool polarityRising
)
673 timCCER_t tmpccer
= timHw
->tim
->CCEN
;
674 tmpccer
&= ~(TMR_CCEN_CC1POL
<< timHw
->channel
);
675 tmpccer
|= polarityRising
? (TMR_ICPOLARITY_RISING
<< timHw
->channel
) : (TMR_ICPOLARITY_FALLING
<< timHw
->channel
);
676 timHw
->tim
->CCEN
= tmpccer
;
679 volatile timCCR_t
* timerChCCRHi(const timerHardware_t
*timHw
)
681 return (volatile timCCR_t
*)((volatile char*)&timHw
->tim
->CC1
+ (timHw
->channel
| TMR_CHANNEL_2
));
684 volatile timCCR_t
* timerChCCRLo(const timerHardware_t
*timHw
)
686 return (volatile timCCR_t
*)((volatile char*)&timHw
->tim
->CC1
+ (timHw
->channel
& ~TMR_CHANNEL_2
));
689 volatile timCCR_t
* timerChCCR(const timerHardware_t
*timHw
)
691 return (volatile timCCR_t
*)((volatile char*)&timHw
->tim
->CC1
+ timHw
->channel
);
694 void timerChConfigOC(const timerHardware_t
* timHw
, bool outEnable
, bool stateHigh
)
696 unsigned timer
= lookupTimerIndex(timHw
->tim
);
697 if (timer
>= USED_TIMER_COUNT
)
700 TMR_OC_InitTypeDef TIM_OCInitStructure
;
702 TIM_OCInitStructure
.OCMode
= TMR_OCMODE_INACTIVE
;
703 TIM_OCInitStructure
.Pulse
= 0x00000000;
704 TIM_OCInitStructure
.OCPolarity
= stateHigh
? TMR_OCPOLARITY_HIGH
: TMR_OCPOLARITY_LOW
;
705 TIM_OCInitStructure
.OCNPolarity
= TMR_OCPOLARITY_HIGH
;
706 TIM_OCInitStructure
.OCIdleState
= TMR_OCIDLESTATE_RESET
;
707 TIM_OCInitStructure
.OCNIdleState
= TMR_OCNIDLESTATE_RESET
;
709 DAL_TMR_OC_ConfigChannel(&timerHandle
[timer
].Handle
, &TIM_OCInitStructure
, timHw
->channel
);
712 TIM_OCInitStructure
.OCMode
= TMR_OCMODE_INACTIVE
;
713 DAL_TMR_OC_ConfigChannel(&timerHandle
[timer
].Handle
, &TIM_OCInitStructure
, timHw
->channel
);
714 DAL_TMR_OC_Start(&timerHandle
[timer
].Handle
, timHw
->channel
);
716 TIM_OCInitStructure
.OCMode
= TMR_OCMODE_TIMING
;
717 DAL_TMR_OC_ConfigChannel(&timerHandle
[timer
].Handle
, &TIM_OCInitStructure
, timHw
->channel
);
718 DAL_TMR_OC_Start_IT(&timerHandle
[timer
].Handle
, timHw
->channel
);
722 static void timCCxHandler(TMR_TypeDef
*tim
, timerConfig_t
*timerConfig
)
726 tim_status
= tim
->STS
& tim
->DIEN
;
729 // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
730 // currrent order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
731 unsigned bit
= __builtin_clz(tim_status
);
732 unsigned mask
= ~(0x80000000 >> bit
);
736 case __builtin_clz(TMR_IT_UPDATE
): {
738 if (timerConfig
->forcedOverflowTimerValue
!= 0) {
739 capture
= timerConfig
->forcedOverflowTimerValue
- 1;
740 timerConfig
->forcedOverflowTimerValue
= 0;
742 capture
= tim
->AUTORLD
;
745 timerOvrHandlerRec_t
*cb
= timerConfig
->overflowCallbackActive
;
752 case __builtin_clz(TMR_IT_CC1
):
753 if (timerConfig
->edgeCallback
[0]) {
754 timerConfig
->edgeCallback
[0]->fn(timerConfig
->edgeCallback
[0], tim
->CC1
);
757 case __builtin_clz(TMR_IT_CC2
):
758 if (timerConfig
->edgeCallback
[1]) {
759 timerConfig
->edgeCallback
[1]->fn(timerConfig
->edgeCallback
[1], tim
->CC2
);
762 case __builtin_clz(TMR_IT_CC3
):
763 if (timerConfig
->edgeCallback
[2]) {
764 timerConfig
->edgeCallback
[2]->fn(timerConfig
->edgeCallback
[2], tim
->CC3
);
767 case __builtin_clz(TMR_IT_CC4
):
768 if (timerConfig
->edgeCallback
[3]) {
769 timerConfig
->edgeCallback
[3]->fn(timerConfig
->edgeCallback
[3], tim
->CC4
);
775 if (tim_status
& (int)TIM_IT_Update
) {
776 tim
->SR
= ~TIM_IT_Update
;
778 timerOvrHandlerRec_t
*cb
= timerConfig
->overflowCallbackActive
;
784 if (tim_status
& (int)TIM_IT_CC1
) {
785 tim
->SR
= ~TIM_IT_CC1
;
786 timerConfig
->edgeCallback
[0]->fn(timerConfig
->edgeCallback
[0], tim
->CCR1
);
788 if (tim_status
& (int)TIM_IT_CC2
) {
789 tim
->SR
= ~TIM_IT_CC2
;
790 timerConfig
->edgeCallback
[1]->fn(timerConfig
->edgeCallback
[1], tim
->CCR2
);
792 if (tim_status
& (int)TIM_IT_CC3
) {
793 tim
->SR
= ~TIM_IT_CC3
;
794 timerConfig
->edgeCallback
[2]->fn(timerConfig
->edgeCallback
[2], tim
->CCR3
);
796 if (tim_status
& (int)TIM_IT_CC4
) {
797 tim
->SR
= ~TIM_IT_CC4
;
798 timerConfig
->edgeCallback
[3]->fn(timerConfig
->edgeCallback
[3], tim
->CCR4
);
803 static inline void timUpdateHandler(TMR_TypeDef
*tim
, timerConfig_t
*timerConfig
)
807 tim_status
= tim
->STS
& tim
->DIEN
;
809 // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
810 // currrent order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
811 unsigned bit
= __builtin_clz(tim_status
);
812 unsigned mask
= ~(0x80000000 >> bit
);
816 case __builtin_clz(TMR_IT_UPDATE
): {
818 if (timerConfig
->forcedOverflowTimerValue
!= 0) {
819 capture
= timerConfig
->forcedOverflowTimerValue
- 1;
820 timerConfig
->forcedOverflowTimerValue
= 0;
822 capture
= tim
->AUTORLD
;
825 timerOvrHandlerRec_t
*cb
= timerConfig
->overflowCallbackActive
;
836 // handler for shared interrupts when both timers need to check status bits
837 #define _TIM_IRQ_HANDLER2(name, i, j) \
840 timCCxHandler(TMR ## i, &timerConfig[TIMER_INDEX(i)]); \
841 timCCxHandler(TMR ## j, &timerConfig[TIMER_INDEX(j)]); \
844 #define _TIM_IRQ_HANDLER(name, i) \
847 timCCxHandler(TMR ## i, &timerConfig[TIMER_INDEX(i)]); \
850 #define _TIM_IRQ_HANDLER_UPDATE_ONLY(name, i) \
853 timUpdateHandler(TMR ## i, &timerConfig[TIMER_INDEX(i)]); \
856 #if USED_TIMERS & TIM_N(1)
857 _TIM_IRQ_HANDLER(TMR1_CC_IRQHandler
, 1);
858 # if USED_TIMERS & TIM_N(10)
859 _TIM_IRQ_HANDLER2(TMR1_UP_TMR10_IRQHandler
, 1, 10); // both timers are in use
861 _TIM_IRQ_HANDLER(TMR1_UP_TMR10_IRQHandler
, 1); // timer10 is not used
865 #if USED_TIMERS & TIM_N(2)
866 _TIM_IRQ_HANDLER(TMR2_IRQHandler
, 2);
868 #if USED_TIMERS & TIM_N(3)
869 _TIM_IRQ_HANDLER(TMR3_IRQHandler
, 3);
871 #if USED_TIMERS & TIM_N(4)
872 _TIM_IRQ_HANDLER(TMR4_IRQHandler
, 4);
874 #if USED_TIMERS & TIM_N(5)
875 _TIM_IRQ_HANDLER(TMR5_IRQHandler
, 5);
878 #if USED_TIMERS & TIM_N(6)
879 # if !(defined(USE_PID_AUDIO))
881 //_TIM_IRQ_HANDLER_UPDATE_ONLY(TMR6_DAC_IRQHandler, 6);
884 #if USED_TIMERS & TIM_N(7)
885 // The USB VCP_DAL driver conflicts with TIM7, see TIMx_IRQHandler in usbd_cdc_interface.h
886 # if !(defined(USE_VCP) && (defined(APM32F4)))
887 _TIM_IRQ_HANDLER_UPDATE_ONLY(TIM7_IRQHandler
, 7);
891 #if USED_TIMERS & TIM_N(8)
892 _TIM_IRQ_HANDLER(TMR8_CC_IRQHandler
, 8);
894 # if USED_TIMERS & TIM_N(13)
895 _TIM_IRQ_HANDLER2(TMR8_UP_TMR13_IRQHandler
, 8, 13); // both timers are in use
897 _TIM_IRQ_HANDLER(TMR8_UP_TMR13_IRQHandler
, 8); // timer13 is not used
901 #if USED_TIMERS & TIM_N(9)
902 _TIM_IRQ_HANDLER(TMR1_BRK_TMR9_IRQHandler
, 9);
904 # if USED_TIMERS & TIM_N(11)
905 _TIM_IRQ_HANDLER(TMR1_TRG_COM_TMR11_IRQHandler
, 11);
907 #if USED_TIMERS & TIM_N(12)
908 _TIM_IRQ_HANDLER(TMR8_BRK_TMR12_IRQHandler
, 12);
910 #if USED_TIMERS & TIM_N(14)
911 _TIM_IRQ_HANDLER(TMR8_TRG_COM_TMR14_IRQHandler
, 14);
913 #if USED_TIMERS & TIM_N(15)
914 _TIM_IRQ_HANDLER(TMR1_BRK_TMR15_IRQHandler
, 15);
916 #if USED_TIMERS & TIM_N(17)
917 _TIM_IRQ_HANDLER(TMR1_TRG_COM_TMR17_IRQHandler
, 17);
922 memset(timerConfig
, 0, sizeof(timerConfig
));
924 #if USED_TIMERS & TIM_N(1)
925 __DAL_RCM_TMR1_CLK_ENABLE();
927 #if USED_TIMERS & TIM_N(2)
928 __DAL_RCM_TMR2_CLK_ENABLE();
930 #if USED_TIMERS & TIM_N(3)
931 __DAL_RCM_TMR3_CLK_ENABLE();
933 #if USED_TIMERS & TIM_N(4)
934 __DAL_RCM_TMR4_CLK_ENABLE();
936 #if USED_TIMERS & TIM_N(5)
937 __DAL_RCM_TMR5_CLK_ENABLE();
939 #if USED_TIMERS & TIM_N(6)
940 __DAL_RCM_TMR6_CLK_ENABLE();
942 #if USED_TIMERS & TIM_N(7)
943 __DAL_RCM_TMR7_CLK_ENABLE();
945 #if USED_TIMERS & TIM_N(8)
946 __DAL_RCM_TMR8_CLK_ENABLE();
948 #if USED_TIMERS & TIM_N(9)
949 __DAL_RCM_TMR9_CLK_ENABLE();
951 #if USED_TIMERS & TIM_N(10)
952 __DAL_RCM_TMR10_CLK_ENABLE();
954 #if USED_TIMERS & TIM_N(11)
955 __DAL_RCM_TMR11_CLK_ENABLE();
957 #if USED_TIMERS & TIM_N(12)
958 __DAL_RCM_TMR12_CLK_ENABLE();
960 #if USED_TIMERS & TIM_N(13)
961 __DAL_RCM_TMR13_CLK_ENABLE();
963 #if USED_TIMERS & TIM_N(14)
964 __DAL_RCM_TMR14_CLK_ENABLE();
966 #if USED_TIMERS & TIM_N(15)
967 __DAL_RCM_TMR15_CLK_ENABLE();
969 #if USED_TIMERS & TIM_N(16)
970 __DAL_RCM_TMR16_CLK_ENABLE();
972 #if USED_TIMERS & TIM_N(17)
973 __DAL_RCM_TMR17_CLK_ENABLE();
975 #if USED_TIMERS & TIM_N(20)
976 __DAL_RCM_TMR20_CLK_ENABLE();
979 /* enable the timer peripherals */
980 for (int i
= 0; i
< TIMER_CHANNEL_COUNT
; i
++) {
981 RCC_ClockCmd(timerRCC(TIMER_HARDWARE
[i
].tim
), ENABLE
);
984 /* enable the timer peripherals */
985 for (unsigned i
= 0; i
< TIMER_CHANNEL_COUNT
; i
++) {
986 RCC_ClockCmd(timerRCC(TIMER_HARDWARE
[i
].tim
), ENABLE
);
989 // initialize timer channel structures
990 for (unsigned i
= 0; i
< TIMER_CHANNEL_COUNT
; i
++) {
991 timerChannelInfo
[i
].type
= TYPE_FREE
;
994 for (unsigned i
= 0; i
< USED_TIMER_COUNT
; i
++) {
995 timerInfo
[i
].priority
= ~0;
999 void timerStart(TMR_TypeDef
*tim
)
1001 TMR_HandleTypeDef
* handle
= timerFindTimerHandle(tim
);
1002 if (handle
== NULL
) return;
1004 __DAL_TMR_ENABLE(handle
);
1008 * Force an overflow for a given timer.
1009 * Saves the current value of the counter in the relevant timerConfig's forcedOverflowTimerValue variable.
1010 * @param TMR_Typedef *tim The timer to overflow
1013 void timerForceOverflow(TMR_TypeDef
*tim
)
1015 uint8_t timerIndex
= lookupTimerIndex((const TMR_TypeDef
*)tim
);
1017 ATOMIC_BLOCK(NVIC_PRIO_TIMER
) {
1018 // Save the current count so that PPM reading will work on the same timer that was forced to overflow
1019 timerConfig
[timerIndex
].forcedOverflowTimerValue
= tim
->CNT
+ 1;
1021 // Force an overflow by setting the UG bit
1022 tim
->CEG
|= TMR_CEG_UEG
;
1026 // DMA_Handle_index --TODO STD对应文件无该函数
1027 uint16_t timerDmaIndex(uint8_t channel
)
1031 return TMR_DMA_ID_CC1
;
1033 return TMR_DMA_ID_CC2
;
1035 return TMR_DMA_ID_CC3
;
1037 return TMR_DMA_ID_CC4
;
1043 uint16_t timerDmaSource(uint8_t channel
)
1058 uint16_t timerGetPrescalerByDesiredMhz(TMR_TypeDef
*tim
, uint16_t mhz
)
1060 return timerGetPrescalerByDesiredHertz(tim
, MHZ_TO_HZ(mhz
));
1063 uint16_t timerGetPeriodByPrescaler(TMR_TypeDef
*tim
, uint16_t prescaler
, uint32_t hz
)
1065 return (uint16_t)((timerClock(tim
) / (prescaler
+ 1)) / hz
);
1068 uint16_t timerGetPrescalerByDesiredHertz(TMR_TypeDef
*tim
, uint32_t hz
)
1070 // protection here for desired hertz > SystemCoreClock???
1071 if (hz
> timerClock(tim
)) {
1074 return (uint16_t)((timerClock(tim
) + hz
/ 2) / hz
) - 1;
1077 DAL_StatusTypeDef
TIM_DMACmd(TMR_HandleTypeDef
*htim
, uint32_t Channel
, FunctionalState NewState
)
1080 case TMR_CHANNEL_1
: {
1081 if (NewState
!= DISABLE
) {
1082 /* Enable the TIM Capture/Compare 1 DMA request */
1083 __DAL_TMR_ENABLE_DMA(htim
, TMR_DMA_CC1
);
1085 /* Disable the TIM Capture/Compare 1 DMA request */
1086 __DAL_TMR_DISABLE_DMA(htim
, TMR_DMA_CC1
);
1091 case TMR_CHANNEL_2
: {
1092 if (NewState
!= DISABLE
) {
1093 /* Enable the TIM Capture/Compare 2 DMA request */
1094 __DAL_TMR_ENABLE_DMA(htim
, TMR_DMA_CC2
);
1096 /* Disable the TIM Capture/Compare 2 DMA request */
1097 __DAL_TMR_DISABLE_DMA(htim
, TMR_DMA_CC2
);
1102 case TMR_CHANNEL_3
: {
1103 if (NewState
!= DISABLE
) {
1104 /* Enable the TIM Capture/Compare 3 DMA request */
1105 __DAL_TMR_ENABLE_DMA(htim
, TMR_DMA_CC3
);
1107 /* Disable the TIM Capture/Compare 3 DMA request */
1108 __DAL_TMR_DISABLE_DMA(htim
, TMR_DMA_CC3
);
1113 case TMR_CHANNEL_4
: {
1114 if (NewState
!= DISABLE
) {
1115 /* Enable the TIM Capture/Compare 4 DMA request */
1116 __DAL_TMR_ENABLE_DMA(htim
, TMR_DMA_CC4
);
1118 /* Disable the TIM Capture/Compare 4 DMA request */
1119 __DAL_TMR_DISABLE_DMA(htim
, TMR_DMA_CC4
);
1127 /* Change the htim state */
1128 htim
->State
= DAL_TMR_STATE_READY
;
1129 /* Return function status */
1133 DAL_StatusTypeDef
DMA_SetCurrDataCounter(TMR_HandleTypeDef
*htim
, uint32_t Channel
, uint32_t *pData
, uint16_t Length
)
1135 if ((htim
->State
== DAL_TMR_STATE_BUSY
)) {
1137 } else if ((htim
->State
== DAL_TMR_STATE_READY
)) {
1138 if (((uint32_t) pData
== 0) && (Length
> 0)) {
1141 htim
->State
= DAL_TMR_STATE_BUSY
;
1145 case TMR_CHANNEL_1
: {
1146 /* Set the DMA Period elapsed callback */
1147 htim
->hdma
[TMR_DMA_ID_CC1
]->XferCpltCallback
= TMR_DMADelayPulseCplt
;
1149 /* Set the DMA error callback */
1150 htim
->hdma
[TMR_DMA_ID_CC1
]->XferErrorCallback
= TMR_DMAError
;
1152 /* Enable the DMA Stream */
1153 DAL_DMA_Start_IT(htim
->hdma
[TMR_DMA_ID_CC1
], (uint32_t) pData
, (uint32_t) & htim
->Instance
->CC1
, Length
);
1157 case TMR_CHANNEL_2
: {
1158 /* Set the DMA Period elapsed callback */
1159 htim
->hdma
[TMR_DMA_ID_CC2
]->XferCpltCallback
= TMR_DMADelayPulseCplt
;
1161 /* Set the DMA error callback */
1162 htim
->hdma
[TMR_DMA_ID_CC2
]->XferErrorCallback
= TMR_DMAError
;
1164 /* Enable the DMA Stream */
1165 DAL_DMA_Start_IT(htim
->hdma
[TMR_DMA_ID_CC2
], (uint32_t) pData
, (uint32_t) & htim
->Instance
->CC2
, Length
);
1169 case TMR_CHANNEL_3
: {
1170 /* Set the DMA Period elapsed callback */
1171 htim
->hdma
[TMR_DMA_ID_CC3
]->XferCpltCallback
= TMR_DMADelayPulseCplt
;
1173 /* Set the DMA error callback */
1174 htim
->hdma
[TMR_DMA_ID_CC3
]->XferErrorCallback
= TMR_DMAError
;
1176 /* Enable the DMA Stream */
1177 DAL_DMA_Start_IT(htim
->hdma
[TMR_DMA_ID_CC3
], (uint32_t) pData
, (uint32_t) & htim
->Instance
->CC3
, Length
);
1181 case TMR_CHANNEL_4
: {
1182 /* Set the DMA Period elapsed callback */
1183 htim
->hdma
[TMR_DMA_ID_CC4
]->XferCpltCallback
= TMR_DMADelayPulseCplt
;
1185 /* Set the DMA error callback */
1186 htim
->hdma
[TMR_DMA_ID_CC4
]->XferErrorCallback
= TMR_DMAError
;
1188 /* Enable the DMA Stream */
1189 DAL_DMA_Start_IT(htim
->hdma
[TMR_DMA_ID_CC4
], (uint32_t) pData
, (uint32_t) & htim
->Instance
->CC4
, Length
);
1196 /* Return function status */