Merge pull request #11297 from SteveCEvans/baro_state
[betaflight.git] / src / main / drivers / timer_hal.c
blob5740a445db2dfefcd67780b3a17db3abc22b34d7
1 /*
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)
8 * any later version.
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/>.
21 #include <stdbool.h>
22 #include <stdint.h>
23 #include <string.h>
24 #include <math.h>
26 #include "platform.h"
28 #ifdef USE_TIMER
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"
39 #include "rcc.h"
41 #include "timer.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):
48 TIM1 2 channels
49 TIM2 4 channels
50 TIM3 4 channels
51 TIM4 4 channels
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 {
60 // per-timer
61 timerOvrHandlerRec_t *updateCallback;
63 // per-channel
64 timerCCHandlerRec_t *edgeCallback[CC_CHANNELS_PER_TIMER];
65 timerOvrHandlerRec_t *overflowCallback[CC_CHANNELS_PER_TIMER];
67 // state
68 timerOvrHandlerRec_t *overflowCallbackActive; // null-terminated linkded list of active overflow callbacks
69 uint32_t forcedOverflowTimerValue;
70 } timerConfig_t;
71 timerConfig_t timerConfig[USED_TIMER_COUNT + 1];
73 typedef struct {
74 channelType_t type;
75 } timerChannelInfo_t;
76 timerChannelInfo_t timerChannelInfo[TIMER_CHANNEL_COUNT];
78 typedef struct {
79 uint8_t priority;
80 } timerInfo_t;
81 timerInfo_t timerInfo[USED_TIMER_COUNT + 1];
83 typedef struct {
84 TIM_HandleTypeDef Handle;
85 } timerHandle_t;
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)
100 _CASE(1);
101 #endif
102 #if USED_TIMERS & TIM_N(2)
103 _CASE(2);
104 #endif
105 #if USED_TIMERS & TIM_N(3)
106 _CASE(3);
107 #endif
108 #if USED_TIMERS & TIM_N(4)
109 _CASE(4);
110 #endif
111 #if USED_TIMERS & TIM_N(5)
112 _CASE(5);
113 #endif
114 #if USED_TIMERS & TIM_N(6)
115 _CASE(6);
116 #endif
117 #if USED_TIMERS & TIM_N(7)
118 _CASE(7);
119 #endif
120 #if USED_TIMERS & TIM_N(8)
121 _CASE(8);
122 #endif
123 #if USED_TIMERS & TIM_N(9)
124 _CASE(9);
125 #endif
126 #if USED_TIMERS & TIM_N(10)
127 _CASE(10);
128 #endif
129 #if USED_TIMERS & TIM_N(11)
130 _CASE(11);
131 #endif
132 #if USED_TIMERS & TIM_N(12)
133 _CASE(12);
134 #endif
135 #if USED_TIMERS & TIM_N(13)
136 _CASE(13);
137 #endif
138 #if USED_TIMERS & TIM_N(14)
139 _CASE(14);
140 #endif
141 #if USED_TIMERS & TIM_N(15)
142 _CASE(15);
143 #endif
144 #if USED_TIMERS & TIM_N(16)
145 _CASE(16);
146 #endif
147 #if USED_TIMERS & TIM_N(17)
148 _CASE(17);
149 #endif
150 #if USED_TIMERS & TIM_N(20)
151 _CASE(20);
152 #endif
153 default: return ~1; // make sure final index is out of range
155 #undef _CASE
156 #undef _CASE_
159 TIM_TypeDef * const usedTimers[USED_TIMER_COUNT] = {
160 #define _DEF(i) TIM##i
162 #if USED_TIMERS & TIM_N(1)
163 _DEF(1),
164 #endif
165 #if USED_TIMERS & TIM_N(2)
166 _DEF(2),
167 #endif
168 #if USED_TIMERS & TIM_N(3)
169 _DEF(3),
170 #endif
171 #if USED_TIMERS & TIM_N(4)
172 _DEF(4),
173 #endif
174 #if USED_TIMERS & TIM_N(5)
175 _DEF(5),
176 #endif
177 #if USED_TIMERS & TIM_N(6)
178 _DEF(6),
179 #endif
180 #if USED_TIMERS & TIM_N(7)
181 _DEF(7),
182 #endif
183 #if USED_TIMERS & TIM_N(8)
184 _DEF(8),
185 #endif
186 #if !(defined(STM32H7) || defined(STM32G4))
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 #endif
197 #if !defined(STM32G4)
198 #if USED_TIMERS & TIM_N(12)
199 _DEF(12),
200 #endif
201 #if USED_TIMERS & TIM_N(13)
202 _DEF(13),
203 #endif
204 #if USED_TIMERS & TIM_N(14)
205 _DEF(14),
206 #endif
207 #endif
208 #if USED_TIMERS & TIM_N(15)
209 _DEF(15),
210 #endif
211 #if USED_TIMERS & TIM_N(16)
212 _DEF(16),
213 #endif
214 #if USED_TIMERS & TIM_N(17)
215 _DEF(17),
216 #endif
217 #if defined(STM32G4)
218 #if USED_TIMERS & TIM_N(20)
219 _DEF(20),
220 #endif
221 #endif
222 #undef _DEF
225 // Map timer index to timer number (Straight copy of usedTimers array)
226 const int8_t timerNumbers[USED_TIMER_COUNT] = {
227 #define _DEF(i) i
229 #if USED_TIMERS & TIM_N(1)
230 _DEF(1),
231 #endif
232 #if USED_TIMERS & TIM_N(2)
233 _DEF(2),
234 #endif
235 #if USED_TIMERS & TIM_N(3)
236 _DEF(3),
237 #endif
238 #if USED_TIMERS & TIM_N(4)
239 _DEF(4),
240 #endif
241 #if USED_TIMERS & TIM_N(5)
242 _DEF(5),
243 #endif
244 #if USED_TIMERS & TIM_N(6)
245 _DEF(6),
246 #endif
247 #if USED_TIMERS & TIM_N(7)
248 _DEF(7),
249 #endif
250 #if USED_TIMERS & TIM_N(8)
251 _DEF(8),
252 #endif
253 #if USED_TIMERS & TIM_N(9)
254 _DEF(9),
255 #endif
256 #if USED_TIMERS & TIM_N(10)
257 _DEF(10),
258 #endif
259 #if USED_TIMERS & TIM_N(11)
260 _DEF(11),
261 #endif
262 #if USED_TIMERS & TIM_N(12)
263 _DEF(12),
264 #endif
265 #if USED_TIMERS & TIM_N(13)
266 _DEF(13),
267 #endif
268 #if USED_TIMERS & TIM_N(14)
269 _DEF(14),
270 #endif
271 #if USED_TIMERS & TIM_N(15)
272 _DEF(15),
273 #endif
274 #if USED_TIMERS & TIM_N(16)
275 _DEF(16),
276 #endif
277 #if USED_TIMERS & TIM_N(17)
278 _DEF(17),
279 #endif
280 #if USED_TIMERS & TIM_N(20)
281 _DEF(20),
282 #endif
283 #undef _DEF
286 int8_t timerGetNumberByIndex(uint8_t index)
288 if (index < USED_TIMER_COUNT) {
289 return timerNumbers[index];
290 } else {
291 return 0;
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)
304 return channel >> 2;
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;
319 return 0;
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;
329 return 0;
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)
342 return NULL;
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
365 return;
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))
380 || tim == TIM9
381 #endif
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) {
387 return;
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) {
395 return;
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) {
405 return;
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
414 switch (irq) {
416 case TIM1_CC_IRQn:
417 #if defined(STM32F7)
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);
423 #else
424 // Empty
425 #endif
426 break;
427 case TIM8_CC_IRQn:
428 #if defined(STM32G4)
429 timerNVICConfigure(TIM8_UP_IRQn);
430 #else
431 timerNVICConfigure(TIM8_UP_TIM13_IRQn);
432 #endif
433 break;
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) {
443 return;
445 unsigned channel = timHw - TIMER_HARDWARE;
446 if (channel >= TIMER_CHANNEL_COUNT)
447 return;
449 timerChannelInfo[channel].type = type;
450 unsigned timer = lookupTimerIndex(timHw->tim);
451 if (timer >= USED_TIMER_COUNT)
452 return;
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)
467 self->fn = fn;
470 void timerChOvrHandlerInit(timerOvrHandlerRec_t *self, timerOvrHandlerCallback *fn)
472 self->fn = fn;
473 self->next = NULL;
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) {
482 return;
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;
498 *chain = NULL;
500 // enable or disable IRQ
501 if (cfg->overflowCallbackActive)
502 __HAL_TIM_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_UPDATE);
503 else
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) {
512 return;
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
521 if (edgeCallback)
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) {
531 return;
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) {
544 return;
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) {
583 return;
586 if (newState)
587 __HAL_TIM_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel & ~TIM_CHANNEL_2));
588 else
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) {
602 return;
605 if (newState)
606 __HAL_TIM_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel));
607 else
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) {
621 return;
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] = {
640 1*1, // fDTS !
641 1*2, 1*4, 1*8, // fCK_INT
642 2*6, 2*8, // fDTS/2
643 4*6, 4*8,
644 8*6, 8*8,
645 16*5, 16*6, 16*8,
646 32*5, 32*6, 32*8
648 for (unsigned i = 1; i < ARRAYLEN(ftab); i++)
649 if (ftab[i] > ticks)
650 return i - 1;
651 return 0x0f;
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)
659 return;
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)
676 return;
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)
721 return;
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);
734 if (outEnable) {
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);
738 } else {
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)
747 uint16_t capture;
748 unsigned tim_status;
749 tim_status = tim->SR & tim->DIER;
750 #if 1
751 while (tim_status) {
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);
756 tim->SR = mask;
757 tim_status &= mask;
758 switch (bit) {
759 case __builtin_clz(TIM_IT_UPDATE): {
761 if (timerConfig->forcedOverflowTimerValue != 0) {
762 capture = timerConfig->forcedOverflowTimerValue - 1;
763 timerConfig->forcedOverflowTimerValue = 0;
764 } else {
765 capture = tim->ARR;
768 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
769 while (cb) {
770 cb->fn(cb, capture);
771 cb = cb->next;
773 break;
775 case __builtin_clz(TIM_IT_CC1):
776 timerConfig->edgeCallback[0]->fn(timerConfig->edgeCallback[0], tim->CCR1);
777 break;
778 case __builtin_clz(TIM_IT_CC2):
779 timerConfig->edgeCallback[1]->fn(timerConfig->edgeCallback[1], tim->CCR2);
780 break;
781 case __builtin_clz(TIM_IT_CC3):
782 timerConfig->edgeCallback[2]->fn(timerConfig->edgeCallback[2], tim->CCR3);
783 break;
784 case __builtin_clz(TIM_IT_CC4):
785 timerConfig->edgeCallback[3]->fn(timerConfig->edgeCallback[3], tim->CCR4);
786 break;
789 #else
790 if (tim_status & (int)TIM_IT_Update) {
791 tim->SR = ~TIM_IT_Update;
792 capture = tim->ARR;
793 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
794 while (cb) {
795 cb->fn(cb, capture);
796 cb = cb->next;
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);
815 #endif
818 static inline void timUpdateHandler(TIM_TypeDef *tim, timerConfig_t *timerConfig)
820 uint16_t capture;
821 unsigned tim_status;
822 tim_status = tim->SR & tim->DIER;
823 while (tim_status) {
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);
828 tim->SR = mask;
829 tim_status &= mask;
830 switch (bit) {
831 case __builtin_clz(TIM_IT_UPDATE): {
833 if (timerConfig->forcedOverflowTimerValue != 0) {
834 capture = timerConfig->forcedOverflowTimerValue - 1;
835 timerConfig->forcedOverflowTimerValue = 0;
836 } else {
837 capture = tim->ARR;
840 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
841 while (cb) {
842 cb->fn(cb, capture);
843 cb = cb->next;
845 break;
851 // handler for shared interrupts when both timers need to check status bits
852 #define _TIM_IRQ_HANDLER2(name, i, j) \
853 void name(void) \
855 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
856 timCCxHandler(TIM ## j, &timerConfig[TIMER_INDEX(j)]); \
857 } struct dummy
859 #define _TIM_IRQ_HANDLER(name, i) \
860 void name(void) \
862 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
863 } struct dummy
865 #define _TIM_IRQ_HANDLER_UPDATE_ONLY(name, i) \
866 void name(void) \
868 timUpdateHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
869 } struct dummy
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
878 # else
879 _TIM_IRQ_HANDLER(TIM1_UP_TIM16_IRQHandler, 1); // timer16 is not used timers are in use
880 # endif
881 # else
882 # if USED_TIMERS & TIM_N(10)
883 _TIM_IRQ_HANDLER2(TIM1_UP_TIM10_IRQHandler, 1, 10); // both timers are in use
884 # else
885 _TIM_IRQ_HANDLER(TIM1_UP_TIM10_IRQHandler, 1); // timer10 is not used
886 # endif
887 # endif
888 #endif
890 #if USED_TIMERS & TIM_N(2)
891 _TIM_IRQ_HANDLER(TIM2_IRQHandler, 2);
892 #endif
893 #if USED_TIMERS & TIM_N(3)
894 _TIM_IRQ_HANDLER(TIM3_IRQHandler, 3);
895 #endif
896 #if USED_TIMERS & TIM_N(4)
897 _TIM_IRQ_HANDLER(TIM4_IRQHandler, 4);
898 #endif
899 #if USED_TIMERS & TIM_N(5)
900 _TIM_IRQ_HANDLER(TIM5_IRQHandler, 5);
901 #endif
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);
906 # endif
907 #endif
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);
913 # else
914 _TIM_IRQ_HANDLER_UPDATE_ONLY(TIM7_IRQHandler, 7);
915 # endif
916 # endif
917 #endif
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);
923 # endif
925 # if USED_TIMERS & TIM_N(13)
926 _TIM_IRQ_HANDLER2(TIM8_UP_TIM13_IRQHandler, 8, 13); // both timers are in use
927 # else
928 _TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler, 8); // timer13 is not used
929 # endif
930 #endif
932 #if USED_TIMERS & TIM_N(9)
933 _TIM_IRQ_HANDLER(TIM1_BRK_TIM9_IRQHandler, 9);
934 #endif
935 # if USED_TIMERS & TIM_N(11)
936 _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM11_IRQHandler, 11);
937 # endif
938 #if USED_TIMERS & TIM_N(12)
939 _TIM_IRQ_HANDLER(TIM8_BRK_TIM12_IRQHandler, 12);
940 #endif
941 #if defined(STM32H7) && (USED_TIMERS & TIM_N(14))
942 _TIM_IRQ_HANDLER(TIM8_TRG_COM_TIM14_IRQHandler, 14);
943 #endif
944 #if USED_TIMERS & TIM_N(15)
945 # if defined(STM32H7)
946 _TIM_IRQ_HANDLER(TIM15_IRQHandler, 15);
947 # else
948 _TIM_IRQ_HANDLER(TIM1_BRK_TIM15_IRQHandler, 15);
949 # endif
950 #endif
951 #if defined(STM32H7) && (USED_TIMERS & TIM_N(16))
952 _TIM_IRQ_HANDLER(TIM16_IRQHandler, 16);
953 #endif
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
956 #endif
957 #if USED_TIMERS & TIM_N(17)
958 # if defined(STM32H7)
959 _TIM_IRQ_HANDLER(TIM17_IRQHandler, 17);
960 # else
961 _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM17_IRQHandler, 17);
962 # endif
963 #endif
964 #if USED_TIMERS & TIM_N(20)
965 _TIM_IRQ_HANDLER(TIM20_CC_IRQHandler, 20);
966 #endif
968 void timerInit(void)
970 memset(timerConfig, 0, sizeof(timerConfig));
972 #if USED_TIMERS & TIM_N(1)
973 __HAL_RCC_TIM1_CLK_ENABLE();
974 #endif
975 #if USED_TIMERS & TIM_N(2)
976 __HAL_RCC_TIM2_CLK_ENABLE();
977 #endif
978 #if USED_TIMERS & TIM_N(3)
979 __HAL_RCC_TIM3_CLK_ENABLE();
980 #endif
981 #if USED_TIMERS & TIM_N(4)
982 __HAL_RCC_TIM4_CLK_ENABLE();
983 #endif
984 #if USED_TIMERS & TIM_N(5)
985 __HAL_RCC_TIM5_CLK_ENABLE();
986 #endif
987 #if USED_TIMERS & TIM_N(6)
988 __HAL_RCC_TIM6_CLK_ENABLE();
989 #endif
990 #if USED_TIMERS & TIM_N(7)
991 __HAL_RCC_TIM7_CLK_ENABLE();
992 #endif
993 #if USED_TIMERS & TIM_N(8)
994 __HAL_RCC_TIM8_CLK_ENABLE();
995 #endif
996 #if !defined(STM32H7)
997 #if USED_TIMERS & TIM_N(9)
998 __HAL_RCC_TIM9_CLK_ENABLE();
999 #endif
1000 #if USED_TIMERS & TIM_N(10)
1001 __HAL_RCC_TIM10_CLK_ENABLE();
1002 #endif
1003 #if USED_TIMERS & TIM_N(11)
1004 __HAL_RCC_TIM11_CLK_ENABLE();
1005 #endif
1006 #endif
1007 #if USED_TIMERS & TIM_N(12)
1008 __HAL_RCC_TIM12_CLK_ENABLE();
1009 #endif
1010 #if USED_TIMERS & TIM_N(13)
1011 __HAL_RCC_TIM13_CLK_ENABLE();
1012 #endif
1013 #if USED_TIMERS & TIM_N(14)
1014 __HAL_RCC_TIM14_CLK_ENABLE();
1015 #endif
1016 #if USED_TIMERS & TIM_N(15)
1017 __HAL_RCC_TIM15_CLK_ENABLE();
1018 #endif
1019 #if USED_TIMERS & TIM_N(16)
1020 __HAL_RCC_TIM16_CLK_ENABLE();
1021 #endif
1022 #if USED_TIMERS & TIM_N(17)
1023 __HAL_RCC_TIM17_CLK_ENABLE();
1024 #endif
1025 #if USED_TIMERS & TIM_N(20)
1026 __HAL_RCC_TIM20_CLK_ENABLE();
1027 #endif
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) {
1038 continue;
1040 // XXX IOConfigGPIOAF in timerInit should eventually go away.
1041 IOConfigGPIOAF(IOGetByTag(timerHardwarePtr->tag), IOCFG_AF_PP, timerHardwarePtr->alternateFunction);
1043 #endif
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
1061 // start timers
1062 // TODO - Work in progress - initialization routine must be modified/verified to start correctly without timers
1063 void timerStart(void)
1065 #if 0
1066 for (unsigned timer = 0; timer < USED_TIMER_COUNT; timer++) {
1067 int priority = -1;
1068 int irq = -1;
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);
1088 #endif
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
1095 * @return void
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;
1110 // DMA_Handle_index
1111 uint16_t timerDmaIndex(uint8_t channel)
1113 switch (channel) {
1114 case TIM_CHANNEL_1:
1115 return TIM_DMA_ID_CC1;
1116 case TIM_CHANNEL_2:
1117 return TIM_DMA_ID_CC2;
1118 case TIM_CHANNEL_3:
1119 return TIM_DMA_ID_CC3;
1120 case TIM_CHANNEL_4:
1121 return TIM_DMA_ID_CC4;
1123 return 0;
1126 // TIM_DMA_sources
1127 uint16_t timerDmaSource(uint8_t channel)
1129 switch (channel) {
1130 case TIM_CHANNEL_1:
1131 return TIM_DMA_CC1;
1132 case TIM_CHANNEL_2:
1133 return TIM_DMA_CC2;
1134 case TIM_CHANNEL_3:
1135 return TIM_DMA_CC3;
1136 case TIM_CHANNEL_4:
1137 return TIM_DMA_CC4;
1139 return 0;
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)) {
1156 return 0;
1158 return (uint16_t)((timerClock(tim) + hz / 2) / hz) - 1;
1161 HAL_StatusTypeDef TIM_DMACmd(TIM_HandleTypeDef *htim, uint32_t Channel, FunctionalState NewState)
1163 switch (Channel) {
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);
1168 } else {
1169 /* Disable the TIM Capture/Compare 1 DMA request */
1170 __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC1);
1173 break;
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);
1179 } else {
1180 /* Disable the TIM Capture/Compare 2 DMA request */
1181 __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC2);
1184 break;
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);
1190 } else {
1191 /* Disable the TIM Capture/Compare 3 DMA request */
1192 __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC3);
1195 break;
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);
1201 } else {
1202 /* Disable the TIM Capture/Compare 4 DMA request */
1203 __HAL_TIM_DISABLE_DMA(htim, TIM_DMA_CC4);
1206 break;
1208 default:
1209 break;
1211 /* Change the htim state */
1212 htim->State = HAL_TIM_STATE_READY;
1213 /* Return function status */
1214 return HAL_OK;
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)) {
1220 return HAL_BUSY;
1221 } else if ((htim->State == HAL_TIM_STATE_READY)) {
1222 if (((uint32_t) pData == 0) && (Length > 0)) {
1223 return HAL_ERROR;
1224 } else {
1225 htim->State = HAL_TIM_STATE_BUSY;
1228 switch (Channel) {
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);
1239 break;
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);
1251 break;
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);
1263 break;
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);
1275 break;
1277 default:
1278 break;
1280 /* Return function status */
1281 return HAL_OK;
1283 #endif