Auto updated submodule references [18-01-2025]
[betaflight.git] / src / platform / APM32 / timer_apm32.c
blobdf3aff9adb78a8c23121986e4aeb797141cfd24a
1 /*
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
8 * version.
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/>.
22 #include <stdbool.h>
23 #include <stdint.h>
24 #include <string.h>
25 #include <math.h>
27 #include "platform.h"
29 #ifdef USE_TIMER
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):
49 TIM1 2 channels
50 TIM2 4 channels
51 TIM3 4 channels
52 TIM4 4 channels
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 {
61 // per-timer
62 timerOvrHandlerRec_t *updateCallback;
64 // per-channel
65 timerCCHandlerRec_t *edgeCallback[CC_CHANNELS_PER_TIMER];
66 timerOvrHandlerRec_t *overflowCallback[CC_CHANNELS_PER_TIMER];
68 // state
69 timerOvrHandlerRec_t *overflowCallbackActive; // null-terminated linkded list of active overflow callbacks
70 uint32_t forcedOverflowTimerValue;
71 } timerConfig_t;
72 timerConfig_t timerConfig[USED_TIMER_COUNT + 1];
74 typedef struct {
75 channelType_t type;
76 } timerChannelInfo_t;
77 timerChannelInfo_t timerChannelInfo[TIMER_CHANNEL_COUNT];
79 typedef struct {
80 uint8_t priority;
81 } timerInfo_t;
82 timerInfo_t timerInfo[USED_TIMER_COUNT + 1];
84 typedef struct {
85 TMR_HandleTypeDef Handle;
86 } timerHandle_t;
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)
101 _CASE(1);
102 #endif
103 #if USED_TIMERS & TIM_N(2)
104 _CASE(2);
105 #endif
106 #if USED_TIMERS & TIM_N(3)
107 _CASE(3);
108 #endif
109 #if USED_TIMERS & TIM_N(4)
110 _CASE(4);
111 #endif
112 #if USED_TIMERS & TIM_N(5)
113 _CASE(5);
114 #endif
115 #if USED_TIMERS & TIM_N(6)
116 _CASE(6);
117 #endif
118 #if USED_TIMERS & TIM_N(7)
119 _CASE(7);
120 #endif
121 #if USED_TIMERS & TIM_N(8)
122 _CASE(8);
123 #endif
124 #if USED_TIMERS & TIM_N(9)
125 _CASE(9);
126 #endif
127 #if USED_TIMERS & TIM_N(10)
128 _CASE(10);
129 #endif
130 #if USED_TIMERS & TIM_N(11)
131 _CASE(11);
132 #endif
133 #if USED_TIMERS & TIM_N(12)
134 _CASE(12);
135 #endif
136 #if USED_TIMERS & TIM_N(13)
137 _CASE(13);
138 #endif
139 #if USED_TIMERS & TIM_N(14)
140 _CASE(14);
141 #endif
142 #if USED_TIMERS & TIM_N(15)
143 _CASE(15);
144 #endif
145 #if USED_TIMERS & TIM_N(16)
146 _CASE(16);
147 #endif
148 #if USED_TIMERS & TIM_N(17)
149 _CASE(17);
150 #endif
151 #if USED_TIMERS & TIM_N(20)
152 _CASE(20);
153 #endif
154 default: return ~1; // make sure final index is out of range
156 #undef _CASE
157 #undef _CASE_
160 TMR_TypeDef * const usedTimers[USED_TIMER_COUNT] = {
161 #define _DEF(i) TMR##i
163 #if USED_TIMERS & TIM_N(1)
164 _DEF(1),
165 #endif
166 #if USED_TIMERS & TIM_N(2)
167 _DEF(2),
168 #endif
169 #if USED_TIMERS & TIM_N(3)
170 _DEF(3),
171 #endif
172 #if USED_TIMERS & TIM_N(4)
173 _DEF(4),
174 #endif
175 #if USED_TIMERS & TIM_N(5)
176 _DEF(5),
177 #endif
178 #if USED_TIMERS & TIM_N(6)
179 _DEF(6),
180 #endif
181 #if USED_TIMERS & TIM_N(7)
182 _DEF(7),
183 #endif
184 #if USED_TIMERS & TIM_N(8)
185 _DEF(8),
186 #endif
187 #if USED_TIMERS & TIM_N(9)
188 _DEF(9),
189 #endif
190 #if USED_TIMERS & TIM_N(10)
191 _DEF(10),
192 #endif
193 #if USED_TIMERS & TIM_N(11)
194 _DEF(11),
195 #endif
196 #if USED_TIMERS & TIM_N(12)
197 _DEF(12),
198 #endif
199 #if USED_TIMERS & TIM_N(13)
200 _DEF(13),
201 #endif
202 #if USED_TIMERS & TIM_N(14)
203 _DEF(14),
204 #endif
205 #if USED_TIMERS & TIM_N(15)
206 _DEF(15),
207 #endif
208 #if USED_TIMERS & TIM_N(16)
209 _DEF(16),
210 #endif
211 #if USED_TIMERS & TIM_N(17)
212 _DEF(17),
213 #endif
214 #undef _DEF
217 // Map timer index to timer number (Straight copy of usedTimers array)
218 const int8_t timerNumbers[USED_TIMER_COUNT] = {
219 #define _DEF(i) i
221 #if USED_TIMERS & TIM_N(1)
222 _DEF(1),
223 #endif
224 #if USED_TIMERS & TIM_N(2)
225 _DEF(2),
226 #endif
227 #if USED_TIMERS & TIM_N(3)
228 _DEF(3),
229 #endif
230 #if USED_TIMERS & TIM_N(4)
231 _DEF(4),
232 #endif
233 #if USED_TIMERS & TIM_N(5)
234 _DEF(5),
235 #endif
236 #if USED_TIMERS & TIM_N(6)
237 _DEF(6),
238 #endif
239 #if USED_TIMERS & TIM_N(7)
240 _DEF(7),
241 #endif
242 #if USED_TIMERS & TIM_N(8)
243 _DEF(8),
244 #endif
245 #if USED_TIMERS & TIM_N(9)
246 _DEF(9),
247 #endif
248 #if USED_TIMERS & TIM_N(10)
249 _DEF(10),
250 #endif
251 #if USED_TIMERS & TIM_N(11)
252 _DEF(11),
253 #endif
254 #if USED_TIMERS & TIM_N(12)
255 _DEF(12),
256 #endif
257 #if USED_TIMERS & TIM_N(13)
258 _DEF(13),
259 #endif
260 #if USED_TIMERS & TIM_N(14)
261 _DEF(14),
262 #endif
263 #if USED_TIMERS & TIM_N(15)
264 _DEF(15),
265 #endif
266 #if USED_TIMERS & TIM_N(16)
267 _DEF(16),
268 #endif
269 #if USED_TIMERS & TIM_N(17)
270 _DEF(17),
271 #endif
272 #if USED_TIMERS & TIM_N(20)
273 _DEF(20),
274 #endif
275 #undef _DEF
278 int8_t timerGetNumberByIndex(uint8_t index)
280 if (index < USED_TIMER_COUNT) {
281 return timerNumbers[index];
282 } else {
283 return 0;
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)
296 return channel >> 2;
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;
311 return 0;
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;
321 return 0;
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)
334 return NULL;
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
357 return;
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) {
376 return;
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) {
384 return;
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) {
394 return;
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
403 switch (irq) {
405 case TMR1_CC_IRQn:
406 timerNVICConfigure(TMR1_UP_TMR10_IRQn);
407 break;
408 case TMR8_CC_IRQn:
409 timerNVICConfigure(TMR8_UP_TMR13_IRQn);
410 break;
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) {
420 return;
422 unsigned channel = timHw - TIMER_HARDWARE;
423 if (channel >= TIMER_CHANNEL_COUNT)
424 return;
426 timerChannelInfo[channel].type = type;
427 unsigned timer = lookupTimerIndex(timHw->tim);
428 if (timer >= USED_TIMER_COUNT)
429 return;
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)
444 self->fn = fn;
447 void timerChOvrHandlerInit(timerOvrHandlerRec_t *self, timerOvrHandlerCallback *fn)
449 self->fn = fn;
450 self->next = NULL;
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) {
459 return;
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;
475 *chain = NULL;
477 // enable or disable IRQ
478 if (cfg->overflowCallbackActive)
479 __DAL_TMR_ENABLE_IT(&timerHandle[timerIndex].Handle, TMR_IT_UPDATE);
480 else
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) {
489 return;
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
498 if (edgeCallback)
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) {
508 return;
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) {
521 return;
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) {
560 return;
563 if (newState)
564 __DAL_TMR_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel & ~TMR_CHANNEL_2));
565 else
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) {
579 return;
582 if (newState)
583 __DAL_TMR_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel));
584 else
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) {
598 return;
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] = {
617 1*1, // fDTS !
618 1*2, 1*4, 1*8, // fCK_INT
619 2*6, 2*8, // fDTS/2
620 4*6, 4*8,
621 8*6, 8*8,
622 16*5, 16*6, 16*8,
623 32*5, 32*6, 32*8
625 for (unsigned i = 1; i < ARRAYLEN(ftab); i++)
626 if (ftab[i] > ticks)
627 return i - 1;
628 return 0x0f;
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)
636 return;
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)
653 return;
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)
698 return;
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);
711 if (outEnable) {
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);
715 } else {
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)
724 uint16_t capture;
725 unsigned tim_status;
726 tim_status = tim->STS & tim->DIEN;
727 #if 1
728 while (tim_status) {
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);
733 tim->STS = mask;
734 tim_status &= mask;
735 switch (bit) {
736 case __builtin_clz(TMR_IT_UPDATE): {
738 if (timerConfig->forcedOverflowTimerValue != 0) {
739 capture = timerConfig->forcedOverflowTimerValue - 1;
740 timerConfig->forcedOverflowTimerValue = 0;
741 } else {
742 capture = tim->AUTORLD;
745 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
746 while (cb) {
747 cb->fn(cb, capture);
748 cb = cb->next;
750 break;
752 case __builtin_clz(TMR_IT_CC1):
753 if (timerConfig->edgeCallback[0]) {
754 timerConfig->edgeCallback[0]->fn(timerConfig->edgeCallback[0], tim->CC1);
756 break;
757 case __builtin_clz(TMR_IT_CC2):
758 if (timerConfig->edgeCallback[1]) {
759 timerConfig->edgeCallback[1]->fn(timerConfig->edgeCallback[1], tim->CC2);
761 break;
762 case __builtin_clz(TMR_IT_CC3):
763 if (timerConfig->edgeCallback[2]) {
764 timerConfig->edgeCallback[2]->fn(timerConfig->edgeCallback[2], tim->CC3);
766 break;
767 case __builtin_clz(TMR_IT_CC4):
768 if (timerConfig->edgeCallback[3]) {
769 timerConfig->edgeCallback[3]->fn(timerConfig->edgeCallback[3], tim->CC4);
771 break;
774 #else
775 if (tim_status & (int)TIM_IT_Update) {
776 tim->SR = ~TIM_IT_Update;
777 capture = tim->ARR;
778 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
779 while (cb) {
780 cb->fn(cb, capture);
781 cb = cb->next;
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);
800 #endif
803 static inline void timUpdateHandler(TMR_TypeDef *tim, timerConfig_t *timerConfig)
805 uint16_t capture;
806 unsigned tim_status;
807 tim_status = tim->STS & tim->DIEN;
808 while (tim_status) {
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);
813 tim->STS = mask;
814 tim_status &= mask;
815 switch (bit) {
816 case __builtin_clz(TMR_IT_UPDATE): {
818 if (timerConfig->forcedOverflowTimerValue != 0) {
819 capture = timerConfig->forcedOverflowTimerValue - 1;
820 timerConfig->forcedOverflowTimerValue = 0;
821 } else {
822 capture = tim->AUTORLD;
825 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
826 while (cb) {
827 cb->fn(cb, capture);
828 cb = cb->next;
830 break;
836 // handler for shared interrupts when both timers need to check status bits
837 #define _TIM_IRQ_HANDLER2(name, i, j) \
838 void name(void) \
840 timCCxHandler(TMR ## i, &timerConfig[TIMER_INDEX(i)]); \
841 timCCxHandler(TMR ## j, &timerConfig[TIMER_INDEX(j)]); \
842 } struct dummy
844 #define _TIM_IRQ_HANDLER(name, i) \
845 void name(void) \
847 timCCxHandler(TMR ## i, &timerConfig[TIMER_INDEX(i)]); \
848 } struct dummy
850 #define _TIM_IRQ_HANDLER_UPDATE_ONLY(name, i) \
851 void name(void) \
853 timUpdateHandler(TMR ## i, &timerConfig[TIMER_INDEX(i)]); \
854 } struct dummy
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
860 # else
861 _TIM_IRQ_HANDLER(TMR1_UP_TMR10_IRQHandler, 1); // timer10 is not used
862 # endif
863 #endif
865 #if USED_TIMERS & TIM_N(2)
866 _TIM_IRQ_HANDLER(TMR2_IRQHandler, 2);
867 #endif
868 #if USED_TIMERS & TIM_N(3)
869 _TIM_IRQ_HANDLER(TMR3_IRQHandler, 3);
870 #endif
871 #if USED_TIMERS & TIM_N(4)
872 _TIM_IRQ_HANDLER(TMR4_IRQHandler, 4);
873 #endif
874 #if USED_TIMERS & TIM_N(5)
875 _TIM_IRQ_HANDLER(TMR5_IRQHandler, 5);
876 #endif
878 #if USED_TIMERS & TIM_N(6)
879 # if !(defined(USE_PID_AUDIO))
880 //not for APM32F4
881 //_TIM_IRQ_HANDLER_UPDATE_ONLY(TMR6_DAC_IRQHandler, 6);
882 # endif
883 #endif
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);
888 # endif
889 #endif
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
896 # else
897 _TIM_IRQ_HANDLER(TMR8_UP_TMR13_IRQHandler, 8); // timer13 is not used
898 # endif
899 #endif
901 #if USED_TIMERS & TIM_N(9)
902 _TIM_IRQ_HANDLER(TMR1_BRK_TMR9_IRQHandler, 9);
903 #endif
904 # if USED_TIMERS & TIM_N(11)
905 _TIM_IRQ_HANDLER(TMR1_TRG_COM_TMR11_IRQHandler, 11);
906 # endif
907 #if USED_TIMERS & TIM_N(12)
908 _TIM_IRQ_HANDLER(TMR8_BRK_TMR12_IRQHandler, 12);
909 #endif
910 #if USED_TIMERS & TIM_N(14)
911 _TIM_IRQ_HANDLER(TMR8_TRG_COM_TMR14_IRQHandler, 14);
912 #endif
913 #if USED_TIMERS & TIM_N(15)
914 _TIM_IRQ_HANDLER(TMR1_BRK_TMR15_IRQHandler, 15);
915 #endif
916 #if USED_TIMERS & TIM_N(17)
917 _TIM_IRQ_HANDLER(TMR1_TRG_COM_TMR17_IRQHandler, 17);
918 #endif
920 void timerInit(void)
922 memset(timerConfig, 0, sizeof(timerConfig));
924 #if USED_TIMERS & TIM_N(1)
925 __DAL_RCM_TMR1_CLK_ENABLE();
926 #endif
927 #if USED_TIMERS & TIM_N(2)
928 __DAL_RCM_TMR2_CLK_ENABLE();
929 #endif
930 #if USED_TIMERS & TIM_N(3)
931 __DAL_RCM_TMR3_CLK_ENABLE();
932 #endif
933 #if USED_TIMERS & TIM_N(4)
934 __DAL_RCM_TMR4_CLK_ENABLE();
935 #endif
936 #if USED_TIMERS & TIM_N(5)
937 __DAL_RCM_TMR5_CLK_ENABLE();
938 #endif
939 #if USED_TIMERS & TIM_N(6)
940 __DAL_RCM_TMR6_CLK_ENABLE();
941 #endif
942 #if USED_TIMERS & TIM_N(7)
943 __DAL_RCM_TMR7_CLK_ENABLE();
944 #endif
945 #if USED_TIMERS & TIM_N(8)
946 __DAL_RCM_TMR8_CLK_ENABLE();
947 #endif
948 #if USED_TIMERS & TIM_N(9)
949 __DAL_RCM_TMR9_CLK_ENABLE();
950 #endif
951 #if USED_TIMERS & TIM_N(10)
952 __DAL_RCM_TMR10_CLK_ENABLE();
953 #endif
954 #if USED_TIMERS & TIM_N(11)
955 __DAL_RCM_TMR11_CLK_ENABLE();
956 #endif
957 #if USED_TIMERS & TIM_N(12)
958 __DAL_RCM_TMR12_CLK_ENABLE();
959 #endif
960 #if USED_TIMERS & TIM_N(13)
961 __DAL_RCM_TMR13_CLK_ENABLE();
962 #endif
963 #if USED_TIMERS & TIM_N(14)
964 __DAL_RCM_TMR14_CLK_ENABLE();
965 #endif
966 #if USED_TIMERS & TIM_N(15)
967 __DAL_RCM_TMR15_CLK_ENABLE();
968 #endif
969 #if USED_TIMERS & TIM_N(16)
970 __DAL_RCM_TMR16_CLK_ENABLE();
971 #endif
972 #if USED_TIMERS & TIM_N(17)
973 __DAL_RCM_TMR17_CLK_ENABLE();
974 #endif
975 #if USED_TIMERS & TIM_N(20)
976 __DAL_RCM_TMR20_CLK_ENABLE();
977 #endif
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
1011 * @return void
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)
1029 switch (channel) {
1030 case TMR_CHANNEL_1:
1031 return TMR_DMA_ID_CC1;
1032 case TMR_CHANNEL_2:
1033 return TMR_DMA_ID_CC2;
1034 case TMR_CHANNEL_3:
1035 return TMR_DMA_ID_CC3;
1036 case TMR_CHANNEL_4:
1037 return TMR_DMA_ID_CC4;
1039 return 0;
1042 // TIM_DMA_sources
1043 uint16_t timerDmaSource(uint8_t channel)
1045 switch (channel) {
1046 case TMR_CHANNEL_1:
1047 return TMR_DMA_CC1;
1048 case TMR_CHANNEL_2:
1049 return TMR_DMA_CC2;
1050 case TMR_CHANNEL_3:
1051 return TMR_DMA_CC3;
1052 case TMR_CHANNEL_4:
1053 return TMR_DMA_CC4;
1055 return 0;
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)) {
1072 return 0;
1074 return (uint16_t)((timerClock(tim) + hz / 2) / hz) - 1;
1077 DAL_StatusTypeDef TIM_DMACmd(TMR_HandleTypeDef *htim, uint32_t Channel, FunctionalState NewState)
1079 switch (Channel) {
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);
1084 } else {
1085 /* Disable the TIM Capture/Compare 1 DMA request */
1086 __DAL_TMR_DISABLE_DMA(htim, TMR_DMA_CC1);
1089 break;
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);
1095 } else {
1096 /* Disable the TIM Capture/Compare 2 DMA request */
1097 __DAL_TMR_DISABLE_DMA(htim, TMR_DMA_CC2);
1100 break;
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);
1106 } else {
1107 /* Disable the TIM Capture/Compare 3 DMA request */
1108 __DAL_TMR_DISABLE_DMA(htim, TMR_DMA_CC3);
1111 break;
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);
1117 } else {
1118 /* Disable the TIM Capture/Compare 4 DMA request */
1119 __DAL_TMR_DISABLE_DMA(htim, TMR_DMA_CC4);
1122 break;
1124 default:
1125 break;
1127 /* Change the htim state */
1128 htim->State = DAL_TMR_STATE_READY;
1129 /* Return function status */
1130 return DAL_OK;
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)) {
1136 return DAL_BUSY;
1137 } else if ((htim->State == DAL_TMR_STATE_READY)) {
1138 if (((uint32_t) pData == 0) && (Length > 0)) {
1139 return DAL_ERROR;
1140 } else {
1141 htim->State = DAL_TMR_STATE_BUSY;
1144 switch (Channel) {
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);
1155 break;
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);
1167 break;
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);
1179 break;
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);
1191 break;
1193 default:
1194 break;
1196 /* Return function status */
1197 return DAL_OK;
1199 #endif