Merge remote-tracking branch 'upstream/master' into abo_RTH_sanity_fix
[inav.git] / src / main / drivers / timer.c
blob4418e9ad2c5e856ae161aea7ef7801aaeb57a801
1 /*
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/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <string.h>
21 #include <math.h>
23 #include "platform.h"
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];
41 // return index of timer in timer table. Lowest timer has index 0
42 uint8_t lookupTimerIndex(const TIM_TypeDef *tim)
44 int i;
46 // let gcc do the work, switch should be quite optimized
47 for (i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
48 if (tim == timerDefinitions[i].tim) {
49 return i;
53 // make sure final index is out of range
54 return ~1;
57 void timerConfigBase(TCH_t * tch, uint16_t period, uint32_t hz)
59 if (tch == NULL) {
60 return;
63 impl_timerConfigBase(tch, period, hz);
66 // old interface for PWM inputs. It should be replaced
67 void timerConfigure(TCH_t * tch, uint16_t period, uint32_t hz)
69 if (tch == NULL) {
70 return;
73 impl_timerConfigBase(tch, period, hz);
74 impl_timerNVICConfigure(tch, NVIC_PRIO_TIMER);
75 impl_enableTimer(tch);
78 TCH_t * timerGetTCH(const timerHardware_t * timHw)
80 const int timerIndex = lookupTimerIndex(timHw->tim);
82 if (timerIndex >= HARDWARE_TIMER_DEFINITION_COUNT) {
83 LOG_E(TIMER, "Can't find hardware timer definition");
84 return NULL;
87 // If timer context does not exist - allocate memory
88 if (timerCtx[timerIndex] == NULL) {
89 timerCtx[timerIndex] = memAllocate(sizeof(timHardwareContext_t), OWNER_TIMER);
91 // Check for OOM
92 if (timerCtx[timerIndex] == NULL) {
93 LOG_E(TIMER, "Can't allocate TCH object");
94 return NULL;
97 // Initialize parent object
98 memset(timerCtx[timerIndex], 0, sizeof(timHardwareContext_t));
99 timerCtx[timerIndex]->timDef = &timerDefinitions[timerIndex];
100 timerCtx[timerIndex]->ch[0].timCtx = timerCtx[timerIndex];
101 timerCtx[timerIndex]->ch[1].timCtx = timerCtx[timerIndex];
102 timerCtx[timerIndex]->ch[2].timCtx = timerCtx[timerIndex];
103 timerCtx[timerIndex]->ch[3].timCtx = timerCtx[timerIndex];
105 // Implementation-specific init
106 impl_timerInitContext(timerCtx[timerIndex]);
109 // Initialize timer channel object
110 timerCtx[timerIndex]->ch[timHw->channelIndex].timHw = timHw;
111 timerCtx[timerIndex]->ch[timHw->channelIndex].dma = NULL;
112 timerCtx[timerIndex]->ch[timHw->channelIndex].cb = NULL;
113 timerCtx[timerIndex]->ch[timHw->channelIndex].dmaState = TCH_DMA_IDLE;
115 return &timerCtx[timerIndex]->ch[timHw->channelIndex];
118 // config edge and overflow callback for channel. Try to avoid overflowCallback, it is a bit expensive
119 void timerChInitCallbacks(timerCallbacks_t * cb, void * callbackParam, timerCallbackFn * edgeCallback, timerCallbackFn * overflowCallback)
121 cb->callbackParam = callbackParam;
122 cb->callbackEdge = edgeCallback;
123 cb->callbackOvr = overflowCallback;
126 void timerChConfigCallbacks(TCH_t * tch, timerCallbacks_t * cb)
128 if (tch == NULL) {
129 return;
132 if (cb->callbackEdge == NULL) {
133 impl_timerDisableIT(tch, TIM_IT_CCx(tch->timHw->channelIndex));
136 if (cb->callbackOvr == NULL) {
137 impl_timerDisableIT(tch, IMPL_TIM_IT_UPDATE_INTERRUPT);
140 tch->cb = cb;
142 if (cb->callbackEdge) {
143 impl_timerEnableIT(tch, TIM_IT_CCx(tch->timHw->channelIndex));
146 if (cb->callbackOvr) {
147 impl_timerEnableIT(tch, IMPL_TIM_IT_UPDATE_INTERRUPT);
151 // Configure input captupre
152 void timerChConfigIC(TCH_t * tch, bool polarityRising, unsigned inputFilterSamples)
154 impl_timerChConfigIC(tch, polarityRising, inputFilterSamples);
157 uint16_t timerGetPeriod(TCH_t * tch)
159 return tch->timHw->tim->ARR;
162 void timerInit(void)
164 memset(timerCtx, 0, sizeof (timerCtx));
166 /* enable the timer peripherals */
167 for (int i = 0; i < timerHardwareCount; i++) {
168 unsigned timer = lookupTimerIndex(timerHardware[i].tim);
169 RCC_ClockCmd(timerDefinitions[timer].rcc, ENABLE);
172 /* Before 2.0 timer outputs were initialized to IOCFG_AF_PP_PD even if not used */
173 /* To keep compatibility make sure all timer output pins are mapped to INPUT with weak pull-down */
174 for (int i = 0; i < timerHardwareCount; i++) {
175 const timerHardware_t *timerHardwarePtr = &timerHardware[i];
176 IOConfigGPIO(IOGetByTag(timerHardwarePtr->tag), IOCFG_IPD);
180 const timerHardware_t * timerGetByTag(ioTag_t tag, timerUsageFlag_e flag)
182 if (!tag) {
183 return NULL;
186 for (int i = 0; i < timerHardwareCount; i++) {
187 if (timerHardware[i].tag == tag) {
188 if (timerHardware[i].usageFlags & flag || flag == 0) {
189 return &timerHardware[i];
193 return NULL;
196 const timerHardware_t * timerGetByUsageFlag(timerUsageFlag_e flag)
198 for (int i = 0; i < timerHardwareCount; i++) {
199 if (timerHardware[i].usageFlags & flag) {
200 return &timerHardware[i];
203 return NULL;
206 void timerPWMConfigChannel(TCH_t * tch, uint16_t value)
208 impl_timerPWMConfigChannel(tch, value);
211 void timerEnable(TCH_t * tch)
213 impl_enableTimer(tch);
216 void timerPWMStart(TCH_t * tch)
218 impl_timerPWMStart(tch);
221 volatile timCCR_t *timerCCR(TCH_t * tch)
223 return impl_timerCCR(tch);
226 void timerChCaptureEnable(TCH_t * tch)
228 impl_timerChCaptureCompareEnable(tch, true);
231 void timerChCaptureDisable(TCH_t * tch)
233 impl_timerChCaptureCompareEnable(tch, false);
236 uint32_t timerGetBaseClock(TCH_t * tch)
238 return timerGetBaseClockHW(tch->timHw);
241 uint32_t timerGetBaseClockHW(const timerHardware_t * timHw)
243 return timerClock(timHw->tim);
246 bool timerPWMConfigChannelDMA(TCH_t * tch, void * dmaBuffer, uint8_t dmaBufferElementSize, uint32_t dmaBufferElementCount)
248 return impl_timerPWMConfigChannelDMA(tch, dmaBuffer, dmaBufferElementSize, dmaBufferElementCount);
251 void timerPWMPrepareDMA(TCH_t * tch, uint32_t dmaBufferElementCount)
253 impl_timerPWMPrepareDMA(tch, dmaBufferElementCount);
256 void timerPWMStartDMA(TCH_t * tch)
258 impl_timerPWMStartDMA(tch);
261 void timerPWMStopDMA(TCH_t * tch)
263 impl_timerPWMStopDMA(tch);
266 bool timerPWMDMAInProgress(TCH_t * tch)
268 return tch->dmaState != TCH_DMA_IDLE;