2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
25 #include "build/atomic.h"
27 #include "common/log.h"
28 #include "common/memory.h"
29 #include "common/utils.h"
31 #include "drivers/io.h"
32 #include "drivers/rcc.h"
33 #include "drivers/time.h"
34 #include "drivers/nvic.h"
36 #include "drivers/timer.h"
37 #include "drivers/timer_impl.h"
39 timHardwareContext_t
* timerCtx
[HARDWARE_TIMER_DEFINITION_COUNT
];
42 uint8_t timer2id(const HAL_Timer_t
*tim
)
44 for (int i
= 0; i
< HARDWARE_TIMER_DEFINITION_COUNT
; ++i
) {
45 if (timerDefinitions
[i
].tim
== tim
) return i
;
52 uint8_t lookupTimerIndex(const HAL_Timer_t
*tim
)
56 // let gcc do the work, switch should be quite optimized
57 for (i
= 0; i
< HARDWARE_TIMER_DEFINITION_COUNT
; i
++) {
58 if (tim
== timerDefinitions
[i
].tim
) {
62 // make sure final index is out of range
66 // return index of timer in timer table. Lowest timer has index 0
67 uint8_t lookupTimerIndex(const HAL_Timer_t
*tim
)
71 // let gcc do the work, switch should be quite optimized
72 for (i
= 0; i
< HARDWARE_TIMER_DEFINITION_COUNT
; i
++) {
73 if (tim
== timerDefinitions
[i
].tim
) {
78 // make sure final index is out of range
83 void timerConfigBase(TCH_t
* tch
, uint16_t period
, uint32_t hz
)
89 impl_timerConfigBase(tch
, period
, hz
);
92 // old interface for PWM inputs. It should be replaced
93 void timerConfigure(TCH_t
* tch
, uint16_t period
, uint32_t hz
)
99 impl_timerConfigBase(tch
, period
, hz
);
100 impl_timerNVICConfigure(tch
, NVIC_PRIO_TIMER
);
101 impl_enableTimer(tch
);
104 TCH_t
* timerGetTCH(const timerHardware_t
* timHw
)
106 const int timerIndex
= lookupTimerIndex(timHw
->tim
);
108 if (timerIndex
>= HARDWARE_TIMER_DEFINITION_COUNT
) {
109 LOG_ERROR(TIMER
, "Can't find hardware timer definition");
113 // If timer context does not exist - allocate memory
114 if (timerCtx
[timerIndex
] == NULL
) {
115 timerCtx
[timerIndex
] = memAllocate(sizeof(timHardwareContext_t
), OWNER_TIMER
);
118 if (timerCtx
[timerIndex
] == NULL
) {
119 LOG_ERROR(TIMER
, "Can't allocate TCH object");
123 // Initialize parent object
124 memset(timerCtx
[timerIndex
], 0, sizeof(timHardwareContext_t
));
125 timerCtx
[timerIndex
]->timDef
= &timerDefinitions
[timerIndex
];
126 timerCtx
[timerIndex
]->ch
[0].timCtx
= timerCtx
[timerIndex
];
127 timerCtx
[timerIndex
]->ch
[1].timCtx
= timerCtx
[timerIndex
];
128 timerCtx
[timerIndex
]->ch
[2].timCtx
= timerCtx
[timerIndex
];
129 timerCtx
[timerIndex
]->ch
[3].timCtx
= timerCtx
[timerIndex
];
131 // Implementation-specific init
132 impl_timerInitContext(timerCtx
[timerIndex
]);
135 // Initialize timer channel object
136 timerCtx
[timerIndex
]->ch
[timHw
->channelIndex
].timHw
= timHw
;
137 timerCtx
[timerIndex
]->ch
[timHw
->channelIndex
].dma
= NULL
;
138 timerCtx
[timerIndex
]->ch
[timHw
->channelIndex
].cb
= NULL
;
139 timerCtx
[timerIndex
]->ch
[timHw
->channelIndex
].dmaState
= TCH_DMA_IDLE
;
141 return &timerCtx
[timerIndex
]->ch
[timHw
->channelIndex
];
144 // config edge and overflow callback for channel. Try to avoid overflowCallback, it is a bit expensive
145 void timerChInitCallbacks(timerCallbacks_t
* cb
, void * callbackParam
, timerCallbackFn
* edgeCallback
, timerCallbackFn
* overflowCallback
)
147 cb
->callbackParam
= callbackParam
;
148 cb
->callbackEdge
= edgeCallback
;
149 cb
->callbackOvr
= overflowCallback
;
152 void timerChConfigCallbacks(TCH_t
* tch
, timerCallbacks_t
* cb
)
158 if (cb
->callbackEdge
== NULL
) {
159 impl_timerDisableIT(tch
, TIM_IT_CCx(tch
->timHw
->channelIndex
));
162 if (cb
->callbackOvr
== NULL
) {
163 impl_timerDisableIT(tch
, IMPL_TIM_IT_UPDATE_INTERRUPT
);
168 if (cb
->callbackEdge
) {
169 impl_timerEnableIT(tch
, TIM_IT_CCx(tch
->timHw
->channelIndex
));
172 if (cb
->callbackOvr
) {
173 impl_timerEnableIT(tch
, IMPL_TIM_IT_UPDATE_INTERRUPT
);
177 // Configure input captupre
178 void timerChConfigIC(TCH_t
* tch
, bool polarityRising
, unsigned inputFilterSamples
)
180 impl_timerChConfigIC(tch
, polarityRising
, inputFilterSamples
);
183 uint16_t timerGetPeriod(TCH_t
* tch
)
185 #if defined(AT32F43x)
186 return tch
->timHw
->tim
->pr
; //tmr pr registe
188 return tch
->timHw
->tim
->ARR
;
191 //timerHardware target.c
194 memset(timerCtx
, 0, sizeof (timerCtx
));
196 /* enable the timer peripherals */
197 for (int i
= 0; i
< timerHardwareCount
; i
++) {
198 unsigned timer
= lookupTimerIndex(timerHardware
[i
].tim
);
199 RCC_ClockCmd(timerDefinitions
[timer
].rcc
, ENABLE
);
202 /* Before 2.0 timer outputs were initialized to IOCFG_AF_PP_PD even if not used */
203 /* To keep compatibility make sure all timer output pins are mapped to INPUT with weak pull-down */
204 for (int i
= 0; i
< timerHardwareCount
; i
++) {
205 const timerHardware_t
*timerHardwarePtr
= &timerHardware
[i
];
206 IOConfigGPIO(IOGetByTag(timerHardwarePtr
->tag
), IOCFG_IPD
);
210 const timerHardware_t
* timerGetByTag(ioTag_t tag
, timerUsageFlag_e flag
)
216 for (int i
= 0; i
< timerHardwareCount
; i
++) {
217 if (timerHardware
[i
].tag
== tag
) {
218 if (timerHardware
[i
].usageFlags
& flag
|| flag
== 0) {
219 return &timerHardware
[i
];
226 const timerHardware_t
* timerGetByUsageFlag(timerUsageFlag_e flag
)
228 for (int i
= 0; i
< timerHardwareCount
; i
++) {
229 if (timerHardware
[i
].usageFlags
& flag
) {
230 return &timerHardware
[i
];
236 void timerPWMConfigChannel(TCH_t
* tch
, uint16_t value
)
238 impl_timerPWMConfigChannel(tch
, value
);
241 void timerEnable(TCH_t
* tch
)
243 impl_enableTimer(tch
);
246 void timerPWMStart(TCH_t
* tch
)
248 impl_timerPWMStart(tch
);
251 volatile timCCR_t
*timerCCR(TCH_t
* tch
)
253 return impl_timerCCR(tch
);
256 void timerChCaptureEnable(TCH_t
* tch
)
258 impl_timerChCaptureCompareEnable(tch
, true);
261 void timerChCaptureDisable(TCH_t
* tch
)
263 impl_timerChCaptureCompareEnable(tch
, false);
266 uint32_t timerGetBaseClock(TCH_t
* tch
)
268 return timerGetBaseClockHW(tch
->timHw
);
271 uint32_t timerGetBaseClockHW(const timerHardware_t
* timHw
)
273 return timerClock(timHw
->tim
);
276 bool timerPWMConfigChannelDMA(TCH_t
* tch
, void * dmaBuffer
, uint8_t dmaBufferElementSize
, uint32_t dmaBufferElementCount
)
278 return impl_timerPWMConfigChannelDMA(tch
, dmaBuffer
, dmaBufferElementSize
, dmaBufferElementCount
);
281 void timerPWMPrepareDMA(TCH_t
* tch
, uint32_t dmaBufferElementCount
)
283 impl_timerPWMPrepareDMA(tch
, dmaBufferElementCount
);
286 void timerPWMStartDMA(TCH_t
* tch
)
288 impl_timerPWMStartDMA(tch
);
291 void timerPWMStopDMA(TCH_t
* tch
)
293 impl_timerPWMStopDMA(tch
);
296 bool timerPWMDMAInProgress(TCH_t
* tch
)
298 return tch
->dmaState
!= TCH_DMA_IDLE
;
301 #ifdef USE_DSHOT_DMAR
302 bool timerPWMConfigDMABurst(burstDmaTimer_t
*burstDmaTimer
, TCH_t
* tch
, void * dmaBuffer
, uint8_t dmaBufferElementSize
, uint32_t dmaBufferElementCount
)
304 return impl_timerPWMConfigDMABurst(burstDmaTimer
, tch
, dmaBuffer
, dmaBufferElementSize
, dmaBufferElementCount
);
307 void pwmBurstDMAStart(burstDmaTimer_t
* burstDmaTimer
, uint32_t BurstLength
)
309 impl_pwmBurstDMAStart(burstDmaTimer
, BurstLength
);