Paparazzi UAS  v5.10_stable-5-g83a0da5-dirty
Paparazzi is a free software Unmanned Aircraft System.
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
pwm_input_arch.c
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2014 Gautier Hattenberger
3  *
4  * This file is part of paparazzi.
5  *
6  * paparazzi is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2, or (at your option)
9  * any later version.
10  *
11  * paparazzi is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU General Public License for more details.
15  *
16  * You should have received a copy of the GNU General Public License
17  * along with paparazzi; see the file COPYING. If not, write to
18  * the Free Software Foundation, 59 Temple Place - Suite 330,
19  * Boston, MA 02111-1307, USA.
20  */
21 
28 #include "mcu_periph/pwm_input.h"
29 
30 #include BOARD_CONFIG
31 #include "generated/airframe.h"
32 
33 #include <libopencm3/stm32/rcc.h>
34 #include <libopencm3/stm32/gpio.h>
35 #include <libopencm3/stm32/timer.h>
36 #include <libopencm3/cm3/nvic.h>
37 
38 #include "mcu_periph/sys_time.h"
39 #include "mcu_periph/gpio.h"
40 
41 // for timer_get_frequency
42 #include "mcu_arch.h"
43 
44 #define ONE_MHZ_CLK 1000000
45 #ifdef NVIC_TIM_IRQ_PRIO
46 #define PWM_INPUT_IRQ_PRIO NVIC_TIM_IRQ_PRIO
47 #else
48 #define PWM_INPUT_IRQ_PRIO 2
49 #endif
50 
54 };
55 
56 static inline void pwm_input_set_timer(uint32_t tim, uint32_t ticks_per_usec)
57 {
58  timer_reset(tim);
59  timer_set_mode(tim, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
60  timer_set_period(tim, 0xFFFF);
61  uint32_t timer_clk = timer_get_frequency(tim);
62  timer_set_prescaler(tim, (timer_clk / (ticks_per_usec * ONE_MHZ_CLK)) - 1);
63  timer_enable_counter(tim);
64 }
65 
66 void pwm_input_init(void)
67 {
68  int i;
69  // initialize the arrays to 0
70  for (i = 0; i < PWM_INPUT_NB; i++) {
71  pwm_input_duty_tics[i] = 0;
72  pwm_input_duty_valid[i] = 0;
73  pwm_input_period_tics[i] = 0;
75  }
76 
82 #if USE_PWM_INPUT_TIM1
83  rcc_periph_clock_enable(RCC_TIM1);
84  pwm_input_set_timer(TIM1, TIM1_TICKS_PER_USEC);
85 #endif
86 #if USE_PWM_INPUT_TIM2
87  rcc_periph_clock_enable(RCC_TIM2);
88  pwm_input_set_timer(TIM2, TIM2_TICKS_PER_USEC);
89 #endif
90 #if USE_PWM_INPUT_TIM3
91  rcc_periph_clock_enable(RCC_TIM3);
92  pwm_input_set_timer(TIM3, TIM3_TICKS_PER_USEC);
93 #endif
94 #if USE_PWM_INPUT_TIM4
95  rcc_periph_clock_enable(RCC_TIM4);
96  pwm_input_set_timer(TIM4, TIM4_TICKS_PER_USEC);
97 #endif
98 #if USE_PWM_INPUT_TIM5
99  rcc_periph_clock_enable(RCC_TIM5);
100  pwm_input_set_timer(TIM5, TIM5_TICKS_PER_USEC);
101 #endif
102 #if USE_PWM_INPUT_TIM8
103  rcc_periph_clock_enable(RCC_TIM8);
104  pwm_input_set_timer(TIM8, TIM8_TICKS_PER_USEC);
105 #endif
106 #if USE_PWM_INPUT_TIM9
107  rcc_periph_clock_enable(RCC_TIM9);
108  pwm_input_set_timer(TIM9, TIM9_TICKS_PER_USEC);
109 #endif
110 
111 #ifdef USE_PWM_INPUT1
112  /* GPIO configuration as input capture for timer */
114 
120 #if USE_PWM_INPUT1 == PWM_PULSE_TYPE_ACTIVE_LOW
121  timer_ic_set_polarity(PWM_INPUT1_TIMER, PWM_INPUT1_CHANNEL_PERIOD, TIM_IC_RISING);
122  timer_ic_set_polarity(PWM_INPUT1_TIMER, PWM_INPUT1_CHANNEL_DUTY, TIM_IC_FALLING);
123 #elif USE_PWM_INPUT1 == PWM_PULSE_TYPE_ACTIVE_HIGH
124  timer_ic_set_polarity(PWM_INPUT1_TIMER, PWM_INPUT1_CHANNEL_PERIOD, TIM_IC_FALLING);
125  timer_ic_set_polarity(PWM_INPUT1_TIMER, PWM_INPUT1_CHANNEL_DUTY, TIM_IC_RISING);
126 #endif
127 
128  /* Select the valid trigger input */
129  timer_slave_set_trigger(PWM_INPUT1_TIMER, PWM_INPUT1_SLAVE_TRIG);
130  /* Configure the slave mode controller in reset mode */
131  timer_slave_set_mode(PWM_INPUT1_TIMER, TIM_SMCR_SMS_RM);
132 
133  /* Enable timer Interrupt(s). */
134  nvic_set_priority(PWM_INPUT1_IRQ, PWM_INPUT_IRQ_PRIO);
135  nvic_enable_irq(PWM_INPUT1_IRQ);
136 #ifdef PWM_INPUT1_IRQ2
137  nvic_set_priority(PWM_INPUT1_IRQ2, PWM_INPUT_IRQ_PRIO);
138  nvic_enable_irq(PWM_INPUT1_IRQ2);
139 #endif
140 
141  /* Enable the Capture/Compare and Update interrupt requests. */
142  timer_enable_irq(PWM_INPUT1_TIMER, (PWM_INPUT1_CC_IE | TIM_DIER_UIE));
143 
144  /* Enable capture channel. */
146  timer_ic_enable(PWM_INPUT1_TIMER, PWM_INPUT1_CHANNEL_DUTY);
147 #endif
148 
149 #ifdef USE_PWM_INPUT2
150  /* GPIO configuration as input capture for timer */
152 
158 #if USE_PWM_INPUT2 == PWM_PULSE_TYPE_ACTIVE_LOW
159  timer_ic_set_polarity(PWM_INPUT2_TIMER, PWM_INPUT2_CHANNEL_PERIOD, TIM_IC_RISING);
160  timer_ic_set_polarity(PWM_INPUT2_TIMER, PWM_INPUT2_CHANNEL_DUTY, TIM_IC_FALLING);
161 #elif USE_PWM_INPUT2 == PWM_PULSE_TYPE_ACTIVE_HIGH
162  timer_ic_set_polarity(PWM_INPUT2_TIMER, PWM_INPUT2_CHANNEL_PERIOD, TIM_IC_FALLING);
163  timer_ic_set_polarity(PWM_INPUT2_TIMER, PWM_INPUT2_CHANNEL_DUTY, TIM_IC_RISING);
164 #endif
165 
166  /* Select the valid trigger input */
167  timer_slave_set_trigger(PWM_INPUT2_TIMER, PWM_INPUT2_SLAVE_TRIG);
168  /* Configure the slave mode controller in reset mode */
169  timer_slave_set_mode(PWM_INPUT2_TIMER, TIM_SMCR_SMS_RM);
170 
171  /* Enable timer Interrupt(s). */
172  nvic_set_priority(PWM_INPUT2_IRQ, PWM_INPUT_IRQ_PRIO);
173  nvic_enable_irq(PWM_INPUT2_IRQ);
174 #ifdef PWM_INPUT2_IRQ2
175  nvic_set_priority(PWM_INPUT2_IRQ2, PWM_INPUT_IRQ_PRIO);
176  nvic_enable_irq(PWM_INPUT2_IRQ2);
177 #endif
178 
179  /* Enable the Capture/Compare and Update interrupt requests. */
180  timer_enable_irq(PWM_INPUT2_TIMER, (PWM_INPUT2_CC_IE | TIM_DIER_UIE));
181 
182  /* Enable capture channel. */
184  timer_ic_enable(PWM_INPUT2_TIMER, PWM_INPUT2_CHANNEL_DUTY);
185 #endif
186 
187 }
188 
191 }
192 
195 }
196 
197 #if USE_PWM_INPUT_TIM1
198 
199 #if defined(STM32F1)
200 void tim1_up_isr(void)
201 {
202 #elif defined(STM32F4)
203 void tim1_up_tim10_isr(void) {
204 #endif
205  if ((TIM1_SR & TIM_SR_UIF) != 0) {
206  timer_clear_flag(TIM1, TIM_SR_UIF);
207  // FIXME clear overflow interrupt but what else ?
208  }
209 }
210 
211 void tim1_cc_isr(void) {
212  if ((TIM1_SR & TIM1_CC_IF_PERIOD) != 0) {
213  timer_clear_flag(TIM1, TIM1_CC_IF_PERIOD);
216  }
217  if ((TIM1_SR & TIM1_CC_IF_DUTY) != 0) {
218  timer_clear_flag(TIM1, TIM1_CC_IF_DUTY);
221  }
222 }
223 
224 #endif
225 
226 #if USE_PWM_INPUT_TIM2
227 
228 void tim2_isr(void) {
229  if ((TIM2_SR & TIM2_CC_IF_PERIOD) != 0) {
230  timer_clear_flag(TIM2, TIM2_CC_IF_PERIOD);
231  pwm_input_period_tics[TIM2_PWM_INPUT_IDX] = TIM2_CCR_PERIOD;
232  pwm_input_period_valid[TIM2_PWM_INPUT_IDX] = true;
233  }
234  if ((TIM2_SR & TIM2_CC_IF_DUTY) != 0) {
235  timer_clear_flag(TIM2, TIM2_CC_IF_DUTY);
236  pwm_input_duty_tics[TIM2_PWM_INPUT_IDX] = TIM2_CCR_DUTY;
237  pwm_input_duty_valid[TIM2_PWM_INPUT_IDX] = true;
238  }
239  if ((TIM2_SR & TIM_SR_UIF) != 0) {
240  timer_clear_flag(TIM2, TIM_SR_UIF);
241  // FIXME clear overflow interrupt but what else ?
242  }
243 }
244 
245 #endif
246 
247 #if USE_PWM_INPUT_TIM3
248 
249 void tim3_isr(void) {
250  if ((TIM3_SR & TIM3_CC_IF_PERIOD) != 0) {
251  timer_clear_flag(TIM3, TIM3_CC_IF_PERIOD);
252  pwm_input_period_tics[TIM3_PWM_INPUT_IDX] = TIM3_CCR_PERIOD;
253  pwm_input_period_valid[TIM3_PWM_INPUT_IDX] = true;
254  }
255  if ((TIM3_SR & TIM3_CC_IF_DUTY) != 0) {
256  timer_clear_flag(TIM3, TIM3_CC_IF_DUTY);
257  pwm_input_duty_tics[TIM3_PWM_INPUT_IDX] = TIM3_CCR_DUTY;
258  pwm_input_duty_valid[TIM3_PWM_INPUT_IDX] = true;
259  }
260  if ((TIM3_SR & TIM_SR_UIF) != 0) {
261  timer_clear_flag(TIM3, TIM_SR_UIF);
262  // FIXME clear overflow interrupt but what else ?
263  }
264 }
265 
266 #endif
267 
268 #if USE_PWM_INPUT_TIM4
269 
270 void tim4_isr(void) {
271  if ((TIM4_SR & TIM4_CC_IF_PERIOD) != 0) {
272  timer_clear_flag(TIM4, TIM4_CC_IF_PERIOD);
273  pwm_input_period_tics[TIM4_PWM_INPUT_IDX] = TIM4_CCR_PERIOD;
274  pwm_input_period_valid[TIM4_PWM_INPUT_IDX] = true;
275  }
276  if ((TIM4_SR & TIM4_CC_IF_DUTY) != 0) {
277  timer_clear_flag(TIM4, TIM4_CC_IF_DUTY);
278  pwm_input_duty_tics[TIM4_PWM_INPUT_IDX] = TIM4_CCR_DUTY;
279  pwm_input_duty_valid[TIM4_PWM_INPUT_IDX] = true;
280  }
281  if ((TIM4_SR & TIM_SR_UIF) != 0) {
282  timer_clear_flag(TIM4, TIM_SR_UIF);
283  // FIXME clear overflow interrupt but what else ?
284  }
285 }
286 
287 #endif
288 
289 #if USE_PWM_INPUT_TIM5
290 
291 void tim5_isr(void) {
292  if ((TIM5_SR & TIM5_CC_IF_PERIOD) != 0) {
293  timer_clear_flag(TIM5, TIM5_CC_IF_PERIOD);
294  pwm_input_period_tics[TIM5_PWM_INPUT_IDX] = TIM5_CCR_PERIOD;
295  pwm_input_period_valid[TIM5_PWM_INPUT_IDX] = true;
296  }
297  if ((TIM5_SR & TIM5_CC_IF_DUTY) != 0) {
298  timer_clear_flag(TIM5, TIM5_CC_IF_DUTY);
299  pwm_input_duty_tics[TIM5_PWM_INPUT_IDX] = TIM5_CCR_DUTY;
300  pwm_input_duty_valid[TIM5_PWM_INPUT_IDX] = true;
301  }
302  if ((TIM5_SR & TIM_SR_UIF) != 0) {
303  timer_clear_flag(TIM5, TIM_SR_UIF);
304  // FIXME clear overflow interrupt but what else ?
305  }
306 }
307 
308 #endif
309 
310 #if USE_PWM_INPUT_TIM8
311 
312 #if defined(STM32F1)
313 void tim8_up_isr(void)
314 {
315 #elif defined(STM32F4)
316 void tim8_up_tim13_isr(void) {
317 #endif
318  if ((TIM8_SR & TIM_SR_UIF) != 0) {
319  timer_clear_flag(TIM8, TIM_SR_UIF);
320  // FIXME clear overflow interrupt but what else ?
321  }
322 }
323 
324 void tim8_cc_isr(void) {
325  if ((TIM8_SR & TIM8_CC_IF_PERIOD) != 0) {
326  timer_clear_flag(TIM8, TIM8_CC_IF_PERIOD);
327  pwm_input_period_tics[TIM8_PWM_INPUT_IDX] = TIM8_CCR_PERIOD;
328  pwm_input_period_valid[TIM8_PWM_INPUT_IDX] = true;
329  }
330  if ((TIM8_SR & TIM8_CC_IF_DUTY) != 0) {
331  timer_clear_flag(TIM8, TIM8_CC_IF_DUTY);
332  pwm_input_duty_tics[TIM8_PWM_INPUT_IDX] = TIM8_CCR_DUTY;
333  pwm_input_duty_valid[TIM8_PWM_INPUT_IDX] = true;
334  }
335 }
336 
337 #endif
338 
339 #if USE_PWM_INPUT_TIM9
340 
341 // TIM1 break interrupt (which we don't care here) and TIM9 global interrupt
342 void tim1_brk_tim9_isr(void) {
343  if ((TIM9_SR & TIM9_CC_IF_PERIOD) != 0) {
344  timer_clear_flag(TIM9, TIM9_CC_IF_PERIOD);
347  }
348  if ((TIM9_SR & TIM9_CC_IF_DUTY) != 0) {
349  timer_clear_flag(TIM9, TIM9_CC_IF_DUTY);
352  }
353  if ((TIM9_SR & TIM_SR_UIF) != 0) {
354  timer_clear_flag(TIM9, TIM_SR_UIF);
355  // FIXME clear overflow interrupt but what else ?
356  }
357 }
358 
359 #endif
360 
void pwm_input_init(void)
#define PWM_INPUT2_TIMER
Definition: apogee_1.0.h:382
volatile uint32_t pwm_input_duty_tics[PWM_INPUT_NB]
Definition: pwm_input.c:29
#define PWM_INPUT1_GPIO_PIN
Definition: board.h:928
#define TIM1_CC_IF_DUTY
Definition: apogee_1.0.h:373
Some architecture independent helper functions for GPIOs.
arch independent PWM input capture API
#define PWM_INPUT2_GPIO_AF
Definition: board.h:939
#define PWM_INPUT1_TIMER
Definition: apogee_1.0.h:359
#define TIM9_CCR_DUTY
Definition: apogee_1.0.h:401
uint32_t timer_get_frequency(uint32_t timer_peripheral)
Get Timer clock frequency (before prescaling) Only valid if using the internal clock for the timer...
Definition: mcu_arch.c:258
#define PWM_INPUT1_TIMER_INPUT
Definition: apogee_1.0.h:365
volatile uint8_t pwm_input_period_valid[PWM_INPUT_NB]
Definition: pwm_input.c:32
#define PWM_INPUT1_IRQ2
Definition: apogee_1.0.h:368
volatile uint8_t pwm_input_duty_valid[PWM_INPUT_NB]
Definition: pwm_input.c:30
#define FALSE
Definition: std.h:5
#define PWM_INPUT2_CHANNEL_DUTY
Definition: apogee_1.0.h:387
timer_clear_flag(TIMx, TIM_SR_UIF)
#define TIM1_PWM_INPUT_IDX
Definition: apogee_1.0.h:371
#define TIM1_CCR_PERIOD
Definition: apogee_1.0.h:374
#define TIM1_CCR_DUTY
Definition: apogee_1.0.h:375
#define PWM_INPUT1_GPIO_PORT
Definition: board.h:927
Architecture independent timing functions.
#define PWM_INPUT1_CC_IE
Definition: apogee_1.0.h:369
#define PWM_INPUT1_GPIO_AF
Definition: board.h:929
#define PWM_INPUT2_TIMER_INPUT
Definition: apogee_1.0.h:388
#define PWM_INPUT1_CHANNEL_DUTY
Definition: apogee_1.0.h:364
#define PWM_INPUT_IRQ_PRIO
#define TIM9_CC_IF_DUTY
Definition: apogee_1.0.h:399
#define PWM_INPUT2_CHANNEL_PERIOD
Definition: apogee_1.0.h:386
unsigned long uint32_t
Definition: types.h:18
static const uint32_t pwm_input_ticks_per_usec[]
#define PWM_INPUT2_IRQ
Definition: apogee_1.0.h:390
#define TIM9_CCR_PERIOD
Definition: apogee_1.0.h:400
volatile uint32_t pwm_input_period_tics[PWM_INPUT_NB]
Definition: pwm_input.c:31
#define PWM_INPUT1_TICKS_PER_USEC
The default pwm counter is set-up to have 1/6 us resolution.
#define PWM_INPUT2_CC_IE
Definition: apogee_1.0.h:391
uint32_t get_pwm_input_duty_in_usec(uint32_t channel)
void gpio_setup_pin_af(ioportid_t port, uint16_t pin, uint8_t af)
Setup a gpio for input or output with alternate function.
Definition: gpio_arch.c:61
#define PWM_INPUT2_SLAVE_TRIG
Definition: apogee_1.0.h:389
#define PWM_INPUT1_SLAVE_TRIG
Definition: apogee_1.0.h:366
#define ONE_MHZ_CLK
#define PWM_INPUT1_IRQ
Definition: apogee_1.0.h:367
#define PWM_INPUT2_TICKS_PER_USEC
#define PWM_INPUT2_GPIO_PORT
Definition: board.h:937
#define PWM_INPUT2_GPIO_PIN
Definition: board.h:938
#define TIM9_PWM_INPUT_IDX
Definition: apogee_1.0.h:397
uint32_t get_pwm_input_period_in_usec(uint32_t channel)
#define TIM1_CC_IF_PERIOD
Definition: apogee_1.0.h:372
static uint8_t channel
Definition: ADS8344.c:80
static void pwm_input_set_timer(uint32_t tim, uint32_t ticks_per_usec)
#define TIM9_CC_IF_PERIOD
Definition: apogee_1.0.h:398
#define PWM_INPUT1_CHANNEL_PERIOD
Definition: apogee_1.0.h:363