Merge remote-tracking branch 'refs/remotes/upstream/master' into feature-timer
[betaflight.git] / src / main / drivers / timer.c
blobc7b01d204ebab459b8d5cdb5c2e47dd39dec7bb5
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 <stdlib.h>
21 #include <string.h>
23 #include "platform.h"
24 #include "common/utils.h"
25 #include "common/atomic.h"
27 #include "nvic.h"
29 #include "gpio.h"
30 #include "system.h"
32 #include "timer.h"
33 #include "timer_impl.h"
35 #define TIM_N(n) (1 << (n))
37 /* FreeFlight/Naze32 timer layout
38 TIM2_CH1 RC1 PWM1
39 TIM2_CH2 RC2 PWM2
40 TIM2_CH3 RC3/UA2_TX PWM3
41 TIM2_CH4 RC4/UA2_RX PWM4
42 TIM3_CH1 RC5 PWM5
43 TIM3_CH2 RC6 PWM6
44 TIM3_CH3 RC7 PWM7
45 TIM3_CH4 RC8 PWM8
46 TIM1_CH1 PWM1 PWM9
47 TIM1_CH4 PWM2 PWM10
48 TIM4_CH1 PWM3 PWM11
49 TIM4_CH2 PWM4 PWM12
50 TIM4_CH3 PWM5 PWM13
51 TIM4_CH4 PWM6 PWM14
53 RX1 TIM2_CH1 PA0 [also PPM] [also used for throttle calibration]
54 RX2 TIM2_CH2 PA1
55 RX3 TIM2_CH3 PA2 [also UART2_TX]
56 RX4 TIM2_CH4 PA3 [also UART2_RX]
57 RX5 TIM3_CH1 PA6 [also ADC_IN6]
58 RX6 TIM3_CH2 PA7 [also ADC_IN7]
59 RX7 TIM3_CH3 PB0 [also ADC_IN8]
60 RX8 TIM3_CH4 PB1 [also ADC_IN9]
62 Outputs
63 PWM1 TIM1_CH1 PA8
64 PWM2 TIM1_CH4 PA11
65 PWM3 TIM4_CH1 PB6 [also I2C1_SCL]
66 PWM4 TIM4_CH2 PB7 [also I2C1_SDA]
67 PWM5 TIM4_CH3 PB8
68 PWM6 TIM4_CH4 PB9
70 Groups that allow running different period (ex 50Hz servos + 400Hz throttle + etc):
71 TIM2 4 channels
72 TIM3 4 channels
73 TIM1 2 channels
74 TIM4 4 channels
77 #if defined(CJMCU) || defined(EUSTM32F103RC) || defined(NAZE) || defined(OLIMEXINO) || defined(PORT103R)
78 const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
79 { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD}, // PWM1
80 { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD}, // PWM2
81 { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_IPD}, // PWM3
82 { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_IPD}, // PWM4
83 { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, Mode_IPD}, // PWM5
84 { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD}, // PWM6
85 { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD}, // PWM7
86 { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD}, // PWM8
87 { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_IPD}, // PWM9
88 { TIM1, GPIOA, Pin_11, TIM_Channel_4, TIM1_CC_IRQn, 1, Mode_IPD}, // PWM10
89 { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD}, // PWM11
90 { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, Mode_IPD}, // PWM12
91 { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, Mode_IPD}, // PWM13
92 { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, Mode_IPD} // PWM14
95 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
97 #define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
98 #define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB)
99 #endif
101 #ifdef CC3D
102 const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
103 { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD}, // S1_IN
104 { TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD}, // S2_IN - GPIO_PartialRemap_TIM3
105 { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD}, // S3_IN - SoftSerial RX
106 { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD}, // S4_IN - SoftSerial TX
107 { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD}, // S5_IN
108 { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD}, // S6_IN
110 { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, GPIO_Mode_AF_PP}, // S1_OUT
111 { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, GPIO_Mode_AF_PP}, // S2_OUT
112 { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 1, GPIO_Mode_AF_PP}, // S3_OUT
113 { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, GPIO_Mode_AF_PP}, // S4_OUT
114 { TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 1, GPIO_Mode_AF_PP}, // S5_OUT - GPIO_PartialRemap_TIM3 - LED Strip
115 { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, GPIO_Mode_AF_PP}, // S6_OUT
118 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
120 #define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
121 #define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB)
122 #endif
124 #if defined(STM32F3DISCOVERY) && !(defined(CHEBUZZF3))
125 const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
126 { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_6}, // PWM1 - PA8
127 { TIM16, GPIOB, Pin_8, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_1}, // PWM2 - PB8
128 { TIM17, GPIOB, Pin_9, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource9, GPIO_AF_1}, // PWM3 - PB9
129 { TIM8, GPIOC, Pin_6, TIM_Channel_1, TIM8_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource6, GPIO_AF_4}, // PWM4 - PC6
130 { TIM8, GPIOC, Pin_7, TIM_Channel_2, TIM8_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource7, GPIO_AF_4}, // PWM5 - PC7
131 { TIM8, GPIOC, Pin_8, TIM_Channel_3, TIM8_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_4}, // PWM6 - PC8
132 { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource1, GPIO_AF_2}, // PWM7 - PB1
133 { TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource4, GPIO_AF_2}, // PWM8 - PA2
134 { TIM4, GPIOD, Pin_12, TIM_Channel_1, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource12, GPIO_AF_2}, // PWM9 - PD12
135 { TIM4, GPIOD, Pin_13, TIM_Channel_2, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource13, GPIO_AF_2}, // PWM10 - PD13
136 { TIM4, GPIOD, Pin_14, TIM_Channel_3, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource14, GPIO_AF_2}, // PWM11 - PD14
137 { TIM4, GPIOD, Pin_15, TIM_Channel_4, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource15, GPIO_AF_2}, // PWM12 - PD15
138 { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // PWM13 - PA1
139 { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_1} // PWM14 - PA2
142 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(16) | TIM_N(17))
144 #define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
145 #define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
146 #define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB | RCC_AHBPeriph_GPIOC | RCC_AHBPeriph_GPIOD)
148 #endif
150 #ifdef CHEBUZZF3
151 const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
152 // INPUTS CH1-8
153 { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_6}, // PWM1 - PA8
154 { TIM16, GPIOB, Pin_8, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_1}, // PWM2 - PB8
155 { TIM17, GPIOB, Pin_9, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource9, GPIO_AF_1}, // PWM3 - PB9
156 { TIM8, GPIOC, Pin_6, TIM_Channel_1, TIM8_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource6, GPIO_AF_4}, // PWM4 - PC6
157 { TIM8, GPIOC, Pin_7, TIM_Channel_2, TIM8_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource7, GPIO_AF_4}, // PWM5 - PC7
158 { TIM8, GPIOC, Pin_8, TIM_Channel_3, TIM8_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_4}, // PWM6 - PC8
159 { TIM15, GPIOF, Pin_9, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource9, GPIO_AF_3}, // PWM7 - PF9
160 { TIM15, GPIOF, Pin_10, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource10, GPIO_AF_3}, // PWM8 - PF10
162 // OUTPUTS CH1-10
163 { TIM4, GPIOD, Pin_12, TIM_Channel_1, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource12, GPIO_AF_2}, // PWM9 - PD12
164 { TIM4, GPIOD, Pin_13, TIM_Channel_2, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource13, GPIO_AF_2}, // PWM10 - PD13
165 { TIM4, GPIOD, Pin_14, TIM_Channel_3, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource14, GPIO_AF_2}, // PWM11 - PD14
166 { TIM4, GPIOD, Pin_15, TIM_Channel_4, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource15, GPIO_AF_2}, // PWM12 - PD15
167 { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // PWM13 - PA1
168 { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_1}, // PWM14 - PA2
169 { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_1}, // PWM15 - PA3
170 { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // PWM16 - PB0
171 { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // PWM17 - PB1
172 { TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2} // PWM18 - PA4
175 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17))
177 #define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
178 #define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
179 #define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB | RCC_AHBPeriph_GPIOC | RCC_AHBPeriph_GPIOD | RCC_AHBPeriph_GPIOF)
181 #endif
183 #ifdef NAZE32PRO
184 const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
185 { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_6}, // PA8 - AF6
186 { TIM1, GPIOA, Pin_9, TIM_Channel_2, TIM1_CC_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource9, GPIO_AF_6}, // PA9 - AF6
187 { TIM1, GPIOA, Pin_10, TIM_Channel_3, TIM1_CC_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource10, GPIO_AF_6}, // PA10 - AF6
188 { TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource4, GPIO_AF_2}, // PB4 - AF2
189 { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource6, GPIO_AF_2}, // PB6 - AF2 - not working yet
190 { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource7, GPIO_AF_2}, // PB7 - AF2 - not working yet
191 { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_2}, // PB8 - AF2
192 { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource9, GPIO_AF_2}, // PB9 - AF2
194 { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // PA0 - untested
195 { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // PA1 - untested
196 { TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9}, // PA2 - untested
197 { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9}, // PA3 - untested
198 { TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1}, // PA6 - untested
199 { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1}, // PA7 - untested
202 #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17))
204 #define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
205 #define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
206 #define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)
208 #endif
210 #define USED_TIMER_COUNT BITCOUNT(USED_TIMERS)
211 #define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4
213 #define TIM_IT_CCx(ch) (TIM_IT_CC1 << ((ch) / 4))
215 typedef struct timerConfig_s {
216 timerCCHandlerRec_t *edgeCallback[CC_CHANNELS_PER_TIMER];
217 timerOvrHandlerRec_t *overflowCallback[CC_CHANNELS_PER_TIMER];
218 timerOvrHandlerRec_t *overflowCallbackActive; // null-terminated linkded list of active overflow callbacks
219 } timerConfig_t;
220 timerConfig_t timerConfig[USED_TIMER_COUNT];
222 typedef struct {
223 channelType_t type;
224 } timerChannelInfo_t;
225 timerChannelInfo_t timerChannelInfo[USABLE_TIMER_CHANNEL_COUNT];
227 typedef struct {
228 uint8_t priority;
229 } timerInfo_t;
230 timerInfo_t timerInfo[USED_TIMER_COUNT];
232 // return index of timer in timer table. Lowest timer has index 0
233 #define TIMER_INDEX(i) BITCOUNT((TIM_N(i) - 1) & USED_TIMERS)
235 static uint8_t lookupTimerIndex(const TIM_TypeDef *tim)
237 #define _CASE_SHF 10 // amount we can safely shift timer address to the right. gcc will throw error if some timers overlap
238 #define _CASE_(tim, index) case ((unsigned)tim >> _CASE_SHF): return index; break
239 #define _CASE(i) _CASE_(TIM##i##_BASE, TIMER_INDEX(i))
241 // let gcc do the work, switch should be quite optimized
242 switch((unsigned)tim >> _CASE_SHF) {
243 #if USED_TIMERS & TIM_N(1)
244 _CASE(1);
245 #endif
246 #if USED_TIMERS & TIM_N(2)
247 _CASE(2);
248 #endif
249 #if USED_TIMERS & TIM_N(3)
250 _CASE(3);
251 #endif
252 #if USED_TIMERS & TIM_N(4)
253 _CASE(4);
254 #endif
255 #if USED_TIMERS & TIM_N(8)
256 _CASE(8);
257 #endif
258 #if USED_TIMERS & TIM_N(15)
259 _CASE(15);
260 #endif
261 #if USED_TIMERS & TIM_N(16)
262 _CASE(16);
263 #endif
264 #if USED_TIMERS & TIM_N(17)
265 _CASE(17);
266 #endif
267 default: return ~1; // make sure final index is out of range
269 #undef _CASE
270 #undef _CASE_
273 TIM_TypeDef * const usedTimers[USED_TIMER_COUNT] = {
274 #define _DEF(i) TIM##i
276 #if USED_TIMERS & TIM_N(1)
277 _DEF(1),
278 #endif
279 #if USED_TIMERS & TIM_N(2)
280 _DEF(2),
281 #endif
282 #if USED_TIMERS & TIM_N(3)
283 _DEF(3),
284 #endif
285 #if USED_TIMERS & TIM_N(4)
286 _DEF(4),
287 #endif
288 #if USED_TIMERS & TIM_N(8)
289 _DEF(8),
290 #endif
291 #if USED_TIMERS & TIM_N(15)
292 _DEF(15),
293 #endif
294 #if USED_TIMERS & TIM_N(16)
295 _DEF(16),
296 #endif
297 #if USED_TIMERS & TIM_N(17)
298 _DEF(17),
299 #endif
300 #undef _DEF
303 static inline uint8_t lookupChannelIndex(const uint16_t channel)
305 return channel >> 2;
308 void timerNVICConfigure(uint8_t irq)
310 NVIC_InitTypeDef NVIC_InitStructure;
312 NVIC_InitStructure.NVIC_IRQChannel = irq;
313 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_TIMER);
314 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_TIMER);
315 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
316 NVIC_Init(&NVIC_InitStructure);
319 void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
321 TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
323 TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
324 TIM_TimeBaseStructure.TIM_Period = period - 1; // AKA TIMx_ARR
326 // "The counter clock frequency (CK_CNT) is equal to f CK_PSC / (PSC[15:0] + 1)." - STM32F10x Reference Manual 14.4.11
327 // Thus for 1Mhz: 72000000 / 1000000 = 72, 72 - 1 = 71 = TIM_Prescaler
328 TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
330 TIM_TimeBaseStructure.TIM_ClockDivision = 0;
331 TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
332 TIM_TimeBaseInit(tim, &TIM_TimeBaseStructure);
335 // old interface for PWM inputs. It should be replaced
336 void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, uint8_t mhz)
338 configTimeBase(timerHardwarePtr->tim, period, mhz);
339 TIM_Cmd(timerHardwarePtr->tim, ENABLE);
340 timerNVICConfigure(timerHardwarePtr->irq);
343 // allocate and configure timer channel. Timer priority is set to highest priority of its channels
344 void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriority)
346 unsigned channel = timHw - timerHardware;
347 if(channel >= USABLE_TIMER_CHANNEL_COUNT)
348 return;
350 timerChannelInfo[channel].type = type;
351 unsigned timer = lookupTimerIndex(timHw->tim);
352 if(timer >= USED_TIMER_COUNT)
353 return;
354 if(irqPriority < timerInfo[timer].priority) {
355 // it would be better to set priority in the end, but current startup sequence is not ready
356 configTimeBase(usedTimers[timer], 0, 1);
357 TIM_Cmd(usedTimers[timer], ENABLE);
359 NVIC_InitTypeDef NVIC_InitStructure;
361 NVIC_InitStructure.NVIC_IRQChannel = timHw->irq;
362 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(irqPriority);
363 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(irqPriority);
364 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
365 NVIC_Init(&NVIC_InitStructure);
367 timerInfo[timer].priority = irqPriority;
371 void timerChCCHandlerInit(timerCCHandlerRec_t *self, timerCCHandlerCallback *fn)
373 self->fn = fn;
376 void timerChOvrHandlerInit(timerOvrHandlerRec_t *self, timerOvrHandlerCallback *fn)
378 self->fn = fn;
379 self->next = NULL;
382 // update overflow callback list
383 // some synchronization mechanism is neccesary to avoid disturbing other channels (BASEPRI used now)
384 static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, TIM_TypeDef* tim) {
385 timerOvrHandlerRec_t **chain = &cfg->overflowCallbackActive;
386 ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
387 for(int i = 0; i < CC_CHANNELS_PER_TIMER; i++)
388 if(cfg->overflowCallback[i]) {
389 *chain = cfg->overflowCallback[i];
390 chain = &cfg->overflowCallback[i]->next;
392 *chain = NULL;
394 // enable or disable IRQ
395 TIM_ITConfig(tim, TIM_IT_Update, cfg->overflowCallbackActive ? ENABLE : DISABLE);
398 // config edge and overflow callback for channel. Try to avoid overflowCallback, it is a bit expensive
399 void timerChConfigCallbacks(const timerHardware_t* timHw, timerCCHandlerRec_t *edgeCallback, timerOvrHandlerRec_t *overflowCallback)
401 uint8_t timerIndex = lookupTimerIndex(timHw->tim);
402 if (timerIndex >= USED_TIMER_COUNT) {
403 return;
405 uint8_t channelIndex = lookupChannelIndex(timHw->channel);
406 if(edgeCallback == NULL) // disable irq before changing callback to NULL
407 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), DISABLE);
408 // setup callback info
409 timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallback;
410 timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback;
411 // enable channel IRQ
412 if(edgeCallback)
413 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), ENABLE);
415 timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim);
418 // configure callbacks for pair of channels (1+2 or 3+4).
419 // Hi(2,4) and Lo(1,3) callbacks are specified, it is not important which timHw channel is used.
420 // This is intended for dual capture mode (each channel handles one transition)
421 void timerChConfigCallbacksDual(const timerHardware_t* timHw, timerCCHandlerRec_t *edgeCallbackLo, timerCCHandlerRec_t *edgeCallbackHi, timerOvrHandlerRec_t *overflowCallback)
423 uint8_t timerIndex = lookupTimerIndex(timHw->tim);
424 if (timerIndex >= USED_TIMER_COUNT) {
425 return;
427 uint16_t chLo = timHw->channel & ~TIM_Channel_2; // lower channel
428 uint16_t chHi = timHw->channel | TIM_Channel_2; // upper channel
429 uint8_t channelIndex = lookupChannelIndex(chLo); // get index of lower channel
431 if(edgeCallbackLo == NULL) // disable irq before changing setting callback to NULL
432 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chLo), DISABLE);
433 if(edgeCallbackHi == NULL) // disable irq before changing setting callback to NULL
434 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chHi), DISABLE);
436 // setup callback info
437 timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallbackLo;
438 timerConfig[timerIndex].edgeCallback[channelIndex + 1] = edgeCallbackHi;
439 timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback;
440 timerConfig[timerIndex].overflowCallback[channelIndex + 1] = NULL;
442 // enable channel IRQs
443 if(edgeCallbackLo) {
444 TIM_ClearFlag(timHw->tim, TIM_IT_CCx(chLo));
445 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chLo), ENABLE);
447 if(edgeCallbackHi) {
448 TIM_ClearFlag(timHw->tim, TIM_IT_CCx(chHi));
449 TIM_ITConfig(timHw->tim, TIM_IT_CCx(chHi), ENABLE);
452 timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim);
455 // enable/disable IRQ for low channel in dual configuration
456 void timerChITConfigDualLo(const timerHardware_t* timHw, FunctionalState newState) {
457 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel&~TIM_Channel_2), newState);
460 // enable or disable IRQ
461 void timerChITConfig(const timerHardware_t* timHw, FunctionalState newState)
463 TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel), newState);
466 // clear Compare/Capture flag for channel
467 void timerChClearCCFlag(const timerHardware_t* timHw)
469 TIM_ClearFlag(timHw->tim, TIM_IT_CCx(timHw->channel));
472 // configure timer channel GPIO mode
473 void timerChConfigGPIO(const timerHardware_t* timHw, GPIO_Mode mode)
475 gpio_config_t cfg;
477 cfg.pin = timHw->pin;
478 cfg.mode = mode;
479 cfg.speed = Speed_2MHz;
480 gpioInit(timHw->gpio, &cfg);
483 // calculate input filter constant
484 // TODO - we should probably setup DTS to higher value to allow reasonable input filtering
485 // - notice that prescaler[0] does use DTS for sampling - the sequence won't be monotonous anymore
486 static unsigned getFilter(unsigned ticks)
488 static const unsigned ftab[16] = {
489 1*1, // fDTS !
490 1*2, 1*4, 1*8, // fCK_INT
491 2*6, 2*8, // fDTS/2
492 4*6, 4*8,
493 8*6, 8*8,
494 16*5, 16*6, 16*8,
495 32*5, 32*6, 32*8
497 for(unsigned i = 1; i < ARRAYLEN(ftab); i++)
498 if(ftab[i] > ticks)
499 return i - 1;
500 return 0x0f;
503 // Configure input captupre
504 void timerChConfigIC(const timerHardware_t* timHw, bool polarityRising, unsigned inputFilterTicks)
506 TIM_ICInitTypeDef TIM_ICInitStructure;
508 TIM_ICStructInit(&TIM_ICInitStructure);
509 TIM_ICInitStructure.TIM_Channel = timHw->channel;
510 TIM_ICInitStructure.TIM_ICPolarity = polarityRising ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling;
511 TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
512 TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
513 TIM_ICInitStructure.TIM_ICFilter = getFilter(inputFilterTicks);
515 TIM_ICInit(timHw->tim, &TIM_ICInitStructure);
518 // configure dual channel input channel for capture
519 // polarity is for Low channel (capture order is always Lo - Hi)
520 void timerChConfigICDual(const timerHardware_t* timHw, bool polarityRising, unsigned inputFilterTicks)
522 TIM_ICInitTypeDef TIM_ICInitStructure;
523 bool directRising = (timHw->channel & TIM_Channel_2) ? !polarityRising : polarityRising;
524 // configure direct channel
525 TIM_ICStructInit(&TIM_ICInitStructure);
527 TIM_ICInitStructure.TIM_Channel = timHw->channel;
528 TIM_ICInitStructure.TIM_ICPolarity = directRising ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling;
529 TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
530 TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
531 TIM_ICInitStructure.TIM_ICFilter = getFilter(inputFilterTicks);
532 TIM_ICInit(timHw->tim, &TIM_ICInitStructure);
533 // configure indirect channel
534 TIM_ICInitStructure.TIM_Channel = timHw->channel ^ TIM_Channel_2; // get opposite channel no
535 TIM_ICInitStructure.TIM_ICPolarity = directRising ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising;
536 TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_IndirectTI;
537 TIM_ICInit(timHw->tim, &TIM_ICInitStructure);
542 void timerChICPolarity(const timerHardware_t* timHw, bool polarityRising)
544 timCCER_t tmpccer = timHw->tim->CCER;
545 tmpccer &= ~(TIM_CCER_CC1P << timHw->channel);
546 tmpccer |= polarityRising ? (TIM_ICPolarity_Rising << timHw->channel) : (TIM_ICPolarity_Falling << timHw->channel);
547 timHw->tim->CCER = tmpccer;
550 volatile timCCR_t* timerChCCRHi(const timerHardware_t* timHw)
552 return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + (timHw->channel | TIM_Channel_2));
555 volatile timCCR_t* timerChCCRLo(const timerHardware_t* timHw)
557 return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + (timHw->channel & ~TIM_Channel_2));
562 volatile timCCR_t* timerChCCR(const timerHardware_t* timHw)
564 return (volatile timCCR_t*)((volatile char*)&timHw->tim->CCR1 + timHw->channel);
567 void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHigh)
569 TIM_OCInitTypeDef TIM_OCInitStructure;
571 TIM_OCStructInit(&TIM_OCInitStructure);
572 if(outEnable) {
573 TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Inactive;
574 TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
575 TIM_OCInitStructure.TIM_OCPolarity = stateHigh ? TIM_OCPolarity_High : TIM_OCPolarity_Low;
576 } else {
577 TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Timing;
580 switch (timHw->channel) {
581 case TIM_Channel_1:
582 TIM_OC1Init(timHw->tim, &TIM_OCInitStructure);
583 TIM_OC1PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
584 break;
585 case TIM_Channel_2:
586 TIM_OC2Init(timHw->tim, &TIM_OCInitStructure);
587 TIM_OC2PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
588 break;
589 case TIM_Channel_3:
590 TIM_OC3Init(timHw->tim, &TIM_OCInitStructure);
591 TIM_OC3PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
592 break;
593 case TIM_Channel_4:
594 TIM_OC4Init(timHw->tim, &TIM_OCInitStructure);
595 TIM_OC4PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
596 break;
602 static void timCCxHandler(TIM_TypeDef *tim, timerConfig_t* timerConfig)
604 uint16_t capture;
605 unsigned tim_status;
606 tim_status = tim->SR & tim->DIER;
607 #if 1
608 while(tim_status) {
609 // flags will be cleared by reading CCR in dual capture, make sure we call handler correctly
610 // currrent order is highest bit first. Code should not rely on specific order (it will introduce race conditions anyway)
611 unsigned bit = __builtin_clz(tim_status);
612 unsigned mask = ~(0x80000000 >> bit);
613 tim->SR = mask;
614 tim_status &= mask;
615 switch(bit) {
616 case __builtin_clz(TIM_IT_Update):
617 capture = tim->ARR;
618 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
619 while(cb) {
620 cb->fn(cb, capture);
621 cb = cb->next;
623 break;
624 case __builtin_clz(TIM_IT_CC1):
625 timerConfig->edgeCallback[0]->fn(timerConfig->edgeCallback[0], tim->CCR1);
626 break;
627 case __builtin_clz(TIM_IT_CC2):
628 timerConfig->edgeCallback[1]->fn(timerConfig->edgeCallback[1], tim->CCR2);
629 break;
630 case __builtin_clz(TIM_IT_CC3):
631 timerConfig->edgeCallback[2]->fn(timerConfig->edgeCallback[2], tim->CCR3);
632 break;
633 case __builtin_clz(TIM_IT_CC4):
634 timerConfig->edgeCallback[3]->fn(timerConfig->edgeCallback[3], tim->CCR4);
635 break;
638 #else
639 if (tim_status & (int)TIM_IT_Update) {
640 tim->SR = ~TIM_IT_Update;
641 capture = tim->ARR;
642 timerOvrHandlerRec_t *cb = timerConfig->overflowCallbackActive;
643 while(cb) {
644 cb->fn(cb, capture);
645 cb = cb->next;
648 if (tim_status & (int)TIM_IT_CC1) {
649 tim->SR = ~TIM_IT_CC1;
650 timerConfig->edgeCallback[0]->fn(timerConfig->edgeCallback[0], tim->CCR1);
652 if (tim_status & (int)TIM_IT_CC2) {
653 tim->SR = ~TIM_IT_CC2;
654 timerConfig->edgeCallback[2]->fn(timerConfig->edgeCallback[1], tim->CCR2);
656 if (tim_status & (int)TIM_IT_CC3) {
657 tim->SR = ~TIM_IT_CC3;
658 timerConfig->edgeCallback[2]->fn(timerConfig->edgeCallback[2], tim->CCR3);
660 if (tim_status & (int)TIM_IT_CC4) {
661 tim->SR = ~TIM_IT_CC4;
662 timerConfig->edgeCallback[3]->fn(timerConfig->edgeCallback[3], tim->CCR4);
664 #endif
667 // handler for shared interrupts when both timers need to check status bits
668 #define _TIM_IRQ_HANDLER2(name, i, j) \
669 void name(void) \
671 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
672 timCCxHandler(TIM ## j, &timerConfig[TIMER_INDEX(j)]); \
673 } struct dummy
675 #define _TIM_IRQ_HANDLER(name, i) \
676 void name(void) \
678 timCCxHandler(TIM ## i, &timerConfig[TIMER_INDEX(i)]); \
679 } struct dummy
681 #if USED_TIMERS & TIM_N(1)
682 _TIM_IRQ_HANDLER(TIM1_CC_IRQHandler, 1);
683 # if defined(STM32F10X)
684 _TIM_IRQ_HANDLER(TIM1_UP_IRQHandler, 1); // timer can't be shared
685 # endif
686 # ifdef STM32F303xC
687 # if USED_TIMERS & TIM_N(16)
688 _TIM_IRQ_HANDLER2(TIM1_UP_TIM16_IRQHandler, 1, 16); // both timers are in use
689 # else
690 _TIM_IRQ_HANDLER(TIM1_UP_TIM16_IRQHandler, 1); // timer16 is not used
691 # endif
692 # endif
693 #endif
694 #if USED_TIMERS & TIM_N(2)
695 _TIM_IRQ_HANDLER(TIM2_IRQHandler, 2);
696 #endif
697 #if USED_TIMERS & TIM_N(3)
698 _TIM_IRQ_HANDLER(TIM3_IRQHandler, 3);
699 #endif
700 #if USED_TIMERS & TIM_N(4)
701 _TIM_IRQ_HANDLER(TIM4_IRQHandler, 4);
702 #endif
703 #if USED_TIMERS & TIM_N(8)
704 _TIM_IRQ_HANDLER(TIM8_CC_IRQHandler, 8);
705 # if defined(STM32F10X_XL)
706 _TIM_IRQ_HANDLER(TIM8_UP_TIM13_IRQHandler, 8);
707 # else // f10x_hd, f30x
708 _TIM_IRQ_HANDLER(TIM8_UP_IRQHandler, 8);
709 # endif
710 #endif
711 #if USED_TIMERS & TIM_N(15)
712 _TIM_IRQ_HANDLER(TIM1_BRK_TIM15_IRQHandler, 15);
713 #endif
714 #if defined(STM32F303xC) && ((USED_TIMERS & (TIM_N(1)|TIM_N(16))) == (TIM_N(16)))
715 _TIM_IRQ_HANDLER(TIM1_UP_TIM16_IRQHandler, 16); // only timer16 is used, not timer1
716 #endif
717 #if USED_TIMERS & TIM_N(17)
718 _TIM_IRQ_HANDLER(TIM1_TRG_COM_TIM17_IRQHandler, 17);
719 #endif
721 void timerInit(void)
723 memset(timerConfig, 0, sizeof (timerConfig));
725 #ifdef CC3D
726 GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE);
727 #endif
729 #ifdef TIMER_APB1_PERIPHERALS
730 RCC_APB1PeriphClockCmd(TIMER_APB1_PERIPHERALS, ENABLE);
731 #endif
733 #ifdef TIMER_APB2_PERIPHERALS
734 RCC_APB2PeriphClockCmd(TIMER_APB2_PERIPHERALS, ENABLE);
735 #endif
737 #ifdef TIMER_AHB_PERIPHERALS
738 RCC_AHBPeriphClockCmd(TIMER_AHB_PERIPHERALS, ENABLE);
739 #endif
741 #ifdef STM32F303xC
742 for (uint8_t timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
743 const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
744 GPIO_PinAFConfig(timerHardwarePtr->gpio, (uint16_t)timerHardwarePtr->gpioPinSource, timerHardwarePtr->alternateFunction);
746 #endif
748 #if 0
749 #if defined(STMF3DISCOVERY) || defined(NAZE32PRO)
750 // FIXME move these where they are needed.
751 GPIO_PinAFConfig(GPIOB, GPIO_PinSource0, GPIO_AF_2);
752 GPIO_PinAFConfig(GPIOB, GPIO_PinSource1, GPIO_AF_2);
753 #endif
754 #endif
756 // initialize timer channel structures
757 for(int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
758 timerChannelInfo[i].type = TYPE_FREE;
760 for(int i = 0; i < USED_TIMER_COUNT; i++) {
761 timerInfo[i].priority = ~0;
765 // finish configuring timers after allocation phase
766 // start timers
767 // TODO - Work in progress - initialization routine must be modified/verified to start correctly without timers
768 void timerStart(void)
770 #if 0
771 for(unsigned timer = 0; timer < USED_TIMER_COUNT; timer++) {
772 int priority = -1;
773 int irq = -1;
774 for(unsigned hwc = 0; hwc < USABLE_TIMER_CHANNEL_COUNT; hwc++)
775 if((timerChannelInfo[hwc].type != TYPE_FREE) && (timerHardware[hwc].tim == usedTimers[timer])) {
776 // TODO - move IRQ to timer info
777 irq = timerHardware[hwc].irq;
779 // TODO - aggregate required timer paramaters
780 configTimeBase(usedTimers[timer], 0, 1);
781 TIM_Cmd(usedTimers[timer], ENABLE);
782 if(priority >= 0) { // maybe none of the channels was configured
783 NVIC_InitTypeDef NVIC_InitStructure;
785 NVIC_InitStructure.NVIC_IRQChannel = irq;
786 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_SPLIT_PRIORITY_BASE(priority);
787 NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_SPLIT_PRIORITY_SUB(priority);
788 NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
789 NVIC_Init(&NVIC_InitStructure);
792 #endif