APM:Libraries
pwm_in.c
Go to the documentation of this file.
1 /******************************************************************************
2  * The GPLv3 License
3  *
4  *
5  * Permission is hereby granted, free of charge, to any person
6  * obtaining a copy of this software and associated documentation
7  * files (the "Software"), to deal in the Software without
8  * restriction, including without limitation the rights to use, copy,
9  * modify, merge, publish, distribute, sublicense, and/or sell copies
10  * of the Software, and to permit persons to whom the Software is
11  * furnished to do so, subject to the following conditions:
12  *
13  * The above copyright notice and this permission notice shall be
14  * included in all copies or substantial portions of the Software.
15  *
16  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
17  * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
18  * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
19  * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS
20  * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN
21  * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
22  * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
23  * SOFTWARE.
24  *****************************************************************************/
25 
34 #pragma GCC optimize ("O2")
35 
36 #include "pwm_in.h"
37 #include <stdbool.h>
38 #include "hal_types.h"
39 #include "timer.h"
40 #include <systick.h>
41 #include "gpio_hal.h"
42 #include <boards.h>
43 #include "ring_buffer_pulse.h"
44 
45 #define PPM_CHANNELS 2 // independent input pins
46 
47 
48 /**************** PWM INPUT **************************************/
49 
50 // Forward declaration
51 static void pwmIRQHandler(uint32_t v/*TIM_TypeDef *tim */);
52 
53 static void pwmInitializeInput(uint8_t ppmsum);
54 
55 extern const struct TIM_Channel PWM_Channels[];
56 
57 
59 static uint16_t num_ppm_channels = 1;
60 
61 
62 static void pwmIRQHandler(uint32_t v /* TIM_TypeDef *tim */){
63  TIM_TypeDef * tim = (TIM_TypeDef *)v;
64  uint8_t i;
65  uint16_t val = 0;
66 
67  for (i = 0; i < num_ppm_channels; i++) {
68 
69  const struct TIM_Channel *channel = &PWM_Channels[i];
70  struct PPM_State *input = &PPM_Inputs[i];
71 
72  const stm32_pin_info *p = &PIN_MAP[channel->pin];
73  const timer_dev *timer = p->timer_device;
74 
75 /*
76 struct PPM_State {
77  uint8_t state; // 1 or 0
78  uint16_t last_val; // length
79  uint32_t last_pulse; // time of edge
80  volatile pulse_buffer pulses; // ring buffer
81  Pulse pulse_mem[PULSES_QUEUE_SIZE]; // memory
82 };
83 */
84  if (timer->regs == tim && (TIM_GetITStatus(tim, 1<<(p->timer_channel & TIMER_CH_MASK)) == SET)) {
85 
86  val = timer_get_capture(timer, p->timer_channel);
87 
88  input->last_pulse = systick_uptime();
89 
90  uint16_t time;
91 
92  if (val > input->last_val) {
93  time = val - input->last_val;
94  } else {
95  time = ((0xFFFF - input->last_val) + val)+1;
96  }
97  input->last_val = val;
98 
99  if(time>0x7fff) time=0x7fff; // limit to 15 bit
100 
101  {
102  Pulse pl={
103  .length = time,
104  .state = input->state // we store last state, so state reflects input line
105  };
106 
107  if(!pb_is_full(&input->pulses)){ // save pulse length and state
108  pb_insert(&input->pulses, pl);
109  }
110  }
111 
112  if (input->state == 0) { // rising edge
113  input->state = 1;
115  } else { // falling edge
116  input->state = 0;
118  }
119 
120  if(input->handler) revo_call_handler(input->handler, i); // call callback on each edge, SBUS decoding requires only 1.4% of CPU (2.5 for full io_completion)
121  }
122  }
123 }
124 
125 static inline void pwmInitializeInput(uint8_t ppmsum){
126  uint8_t i;
127  uint8_t last_tim=99;
128 
129  for (i = 0; i < num_ppm_channels; i++) {
130  const struct TIM_Channel *channel = &PWM_Channels[i];
131 
132  const stm32_pin_info *p = &PIN_MAP[channel->pin];
133  const gpio_dev *dev = p->gpio_device;
134  uint8_t bit = p->gpio_bit;
135  const timer_dev *timer = p->timer_device;
136 
138  gpio_set_af_mode(dev, bit, timer->af); // connect pin to timer
139 
140  timer_pause(timer);
141 
142  if(last_tim != timer->id) {
143  configTimeBase(timer, 0, 2000); // 2MHz
144 
146  timer_attach_all_interrupts(timer, h.h);
147  timer_enable_NVICirq(timer, p->timer_channel, PWM_INT_PRIORITY); // almost highest - bit time is ~10uS only - ~1680 commands
148 
149  last_tim = timer->id;
150  }
151 
152  // PWM input capture ************************************************************
153  timer_ic_set_mode(timer, p->timer_channel, TIM_ICSelection_DirectTI | TIM_ICPSC_DIV1, 0);
155 
156  timer_cc_enable( timer, p->timer_channel); // enable capture
157 
158  timer_resume(timer);
159 
160  // enable the CC interrupt request **********************************************
161  timer_enable_irq(timer, p->timer_channel);
162  }
163 }
164 
165 void pwmInit(bool ppmsum) {
166  uint8_t i;
167 
168  memset(PPM_Inputs, 0, sizeof(PPM_Inputs));
169 
170  for (i = 0; i < PPM_CHANNELS; i++){
171  struct PPM_State *input = &PPM_Inputs[i];
172  input->state = 1;
173  pb_init(&input->pulses, PULSES_QUEUE_SIZE, input->pulse_mem); // init ring buffer
174  }
175 
176 // TODO use parameters!
178 
179  pwmInitializeInput(ppmsum);
180 }
181 
182 
183 bool getPPM_Pulse(Pulse *p, uint8_t ch) {
184  if(ch>PPM_CHANNELS) return false;
185 
186  volatile pulse_buffer *bp = &PPM_Inputs[ch].pulses;
187  if(pb_is_empty(bp)) return false;
188 
189  *p = pb_remove(bp);
190  return true;
191 }
192 
193 uint16_t getPPM_count(uint8_t ch){
194  volatile pulse_buffer *bp = &PPM_Inputs[ch].pulses;
195  return pb_full_count(bp);
196 }
static Pulse pb_remove(volatile pulse_buffer *pb)
Remove and return the first item from a ring buffer.
Handler handler
Definition: pwm_in.h:51
uint16_t af
Definition: timer.h:580
#define TIMER_CH_MASK
Definition: timer.h:455
uint32_t last_pulse
Definition: pwm_in.h:52
static void timer_cc_enable(const timer_dev *dev, timer_Channel channel)
Enable a timer channel&#39;s capture/compare signal.
Definition: timer.h:858
static void timer_cc_set_pol(const timer_dev *dev, timer_Channel channel, timer_cc_polarity pol)
Set a timer channel&#39;s capture/compare output polarity.
Definition: timer.h:950
static int pb_is_empty(volatile pulse_buffer *pb)
Returns true if and only if the ring buffer is empty.
static uint16_t pb_full_count(volatile pulse_buffer *pb)
Return the number of elements stored in the ring buffer.
#define PWM_INT_PRIORITY
Definition: Config.h:39
Simple circular buffer for PEM input.
volatile pulse_buffer pulses
Definition: pwm_in.h:53
timer_Channel timer_channel
Definition: boards.h:93
void pwmInit(bool ppmsum)
Definition: pwm_in.c:165
static uint64_t systick_uptime(void)
Returns the system uptime, in milliseconds.
Definition: systick.h:44
static void pb_init(volatile pulse_buffer *pb, uint16_t size, Pulse *buf)
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
static INLINE uint16_t timer_get_capture(const timer_dev *dev, timer_Channel channel)
Definition: timer.h:791
#define PPM_CHANNELS
Definition: pwm_in.c:45
const struct TIM_Channel PWM_Channels[]
void timer_enable_NVICirq(const timer_dev *dev, uint8_t interrupt, uint8_t priority)
Definition: timer.c:845
uint32_t timer
static INLINE void timer_pause(const timer_dev *dev)
Stop a timer&#39;s counter from changing.
Definition: timer.h:679
Pulse pulse_mem[PULSES_QUEUE_SIZE]
Definition: pwm_in.h:56
timer interface.
uint16_t last_val
Definition: pwm_in.h:54
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
Definition: gpio_hal.c:125
static INLINE void timer_resume(const timer_dev *dev)
Start a timer&#39;s counter.
Definition: timer.h:690
#define PULSES_QUEUE_SIZE
Definition: pwm_in.h:45
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
static int pb_is_full(volatile pulse_buffer *pb)
Returns true if and only if the ring buffer is full.
const timer_dev *const timer_device
Definition: boards.h:90
struct PPM_State PPM_Inputs[]
bool getPPM_Pulse(Pulse *p, uint8_t ch)
Definition: pwm_in.c:183
void timer_attach_all_interrupts(const timer_dev *dev, Handler handler)
Definition: timer.c:494
float v
Definition: Printf.cpp:15
uint8_t pin
Definition: pwm_in.h:63
Definition: pwm_in.h:40
Board-specific pin information.
static void timer_enable_irq(const timer_dev *dev, timer_interrupt_id interrupt)
Enable a timer interrupt.
Definition: timer.h:1125
uint8_t state
Definition: pwm_in.h:55
static void timer_ic_set_mode(const timer_dev *dev, timer_Channel _channel, uint8_t mode, uint16_t filter)
Configure a channel&#39;s input capture mode.
Definition: timer.h:1096
struct PPM_State PPM_Inputs [PPM_CHANNELS] IN_CCM
Definition: pwm_in.c:58
static uint16_t num_ppm_channels
Definition: pwm_in.c:59
TIM_TypeDef * regs
Definition: timer.h:575
uint8_t id
Definition: timer.h:585
uint32_t configTimeBase(const timer_dev *dev, uint16_t period, uint16_t khz)
Definition: timer.c:357
static void gpio_set_af_mode(const gpio_dev *const dev, uint8_t pin, uint8_t mode)
Definition: gpio_hal.h:102
static void pb_insert(volatile pulse_buffer *pb, Pulse element)
revo_isr_handler isr
Definition: hal_types.h:24
unsigned int length
Definition: pwm_in.h:41
static void pwmInitializeInput(uint8_t ppmsum)
Definition: pwm_in.c:125
void revo_call_handler(Handler h, uint32_t arg)
Definition: Scheduler.cpp:1420
uint8_t gpio_bit
Definition: boards.h:92
static void pwmIRQHandler(uint32_t v)
Definition: pwm_in.c:62
uint16_t getPPM_count(uint8_t ch)
Definition: pwm_in.c:193
Stores STM32-specific information related to a given Maple pin.
Definition: boards.h:88
const gpio_dev *const gpio_device
Definition: boards.h:89