APM:Libraries
GPIO.cpp
Go to the documentation of this file.
1 /*
2 (c) 2017 night_ghost@ykoctpa.ru
3 
4 */
5 
6 #pragma GCC optimize ("O2")
7 
8 #include "gpio_hal.h"
9 #include <boards.h>
10 
11 #include <exti.h>
12 
13 #include "GPIO.h"
14 #include "Scheduler.h"
15 #include "RCOutput.h"
16 
17 
18 
19 using namespace F4Light;
20 
21 void GPIO::_pinMode(uint8_t pin, uint8_t mode)
22 {
23  gpio_pin_mode outputMode;
24  bool pwm = false;
25 
26  switch(mode) { // modes defined to be compatible so no transcode required
27  case OUTPUT:
28  case OUTPUT_OPEN_DRAIN:
29  case INPUT:
30 // case INPUT_FLOATING: synonim and cause doubled 'case'
31  case INPUT_ANALOG:
32  case INPUT_PULLUP:
33  case INPUT_PULLDOWN:
34  outputMode = (gpio_pin_mode)mode;
35  break;
36 
37  case PWM:
38  outputMode = GPIO_AF_OUTPUT_PP;
39  pwm = true;
40  break;
41 
42  case PWM_OPEN_DRAIN:
43  outputMode = GPIO_AF_OUTPUT_OD;
44  pwm = true;
45  break;
46 
47  default:
48  assert_param(0);
49  return;
50  }
51 
52 
53  const stm32_pin_info &p = PIN_MAP[pin];
54 
55  const gpio_dev* dev = p.gpio_device;
56  uint8_t bit = p.gpio_bit;
57  const timer_dev * timer = p.timer_device;
58 
59  gpio_set_mode(dev, bit, outputMode);
60 
61  if (pwm && timer != NULL) {
62  gpio_set_speed(dev, bit, GPIO_speed_25MHz); // cleanflight sets 2MHz
63  gpio_set_af_mode(dev, bit, timer->af);
64  timer_set_mode(timer, p.timer_channel, TIMER_PWM); // init in setupTimers()
65  } else {
66  gpio_set_af_mode(dev, bit, 0); // reset
67  }
68 }
69 
70 
71 void GPIO::pinMode(uint8_t pin, uint8_t output){
72 
73  if ((pin >= BOARD_NR_GPIO_PINS)) return;
74 
75  _pinMode(pin, output);
76 }
77 
78 
79 uint8_t GPIO::read(uint8_t pin) {
80  if (pin >= BOARD_NR_GPIO_PINS) return 0;
81 
82  return _read(pin);
83 }
84 
85 
86 void GPIO::write(uint8_t pin, uint8_t value) {
87  if ((pin >= BOARD_NR_GPIO_PINS)) return;
88 
89 #ifdef BUZZER_PWM_HZ // passive buzzer
90 
91 // AP_Notify Buzzer.cpp don't supports passive buzzer so we need a small hack
92  if(pin == BOARD_BUZZER_PIN){
93  if(value == HAL_BUZZER_ON){
94  const stm32_pin_info &p = PIN_MAP[pin];
95  const timer_dev *dev = p.timer_device;
96  if(dev->state->freq==0) {
97  configTimeBase(dev, 0, BUZZER_PWM_HZ * 10); // it should be personal timer
98  }
99  _pinMode(pin, PWM);
100  uint32_t n = RCOutput::_timer_period(BUZZER_PWM_HZ, dev);
101  timer_set_reload(dev, n);
102  timer_set_compare(dev, p.timer_channel, n/2);
103  return;
104  } else {
105  _pinMode(pin, OUTPUT); // to disable, just change mode
106  }
107  }
108 #endif
109 
110  _write(pin, value);
111 }
112 
113 
114 void GPIO::toggle(uint8_t pin)
115 {
116  if ((pin >= BOARD_NR_GPIO_PINS)) return;
117 
118  _toggle(pin);
119 }
120 
121 
122 /* Interrupt interface: */
123 bool GPIO::_attach_interrupt(uint8_t pin, Handler p, uint8_t mode, uint8_t priority)
124 {
125  if ( (pin >= BOARD_NR_GPIO_PINS) || !p) return false;
126 
127  const stm32_pin_info &pp = PIN_MAP[pin];
128 
132  priority);
133 
134  return true;
135 }
136 
138 {
139  if ( pin >= BOARD_NR_GPIO_PINS) return;
140 
141  exti_detach_interrupt((afio_exti_num)(PIN_MAP[pin].gpio_bit));
142 }
143 
144 
145 
146 /* Alternative interface: */
148 
149  if ((pin >= BOARD_NR_GPIO_PINS)) return NULL;
150 
151  return get_channel(pin);
152 }
153 
154 
155 void DigitalSource::mode(uint8_t md)
156 {
157  gpio_pin_mode outputMode;
158 
159  switch(md) {
160  case OUTPUT:
161  case OUTPUT_OPEN_DRAIN:
162  case INPUT:
163 // case INPUT_FLOATING:
164  case INPUT_ANALOG:
165  case INPUT_PULLUP:
166  case INPUT_PULLDOWN:
167  outputMode = (gpio_pin_mode)md;
168  break;
169 
170  // no PWM via this interface!
171  default:
172  assert_param(0);
173  return;
174  }
175 
176  gpio_set_mode( _device, _bit, outputMode);
177  gpio_set_speed(_device, _bit, GPIO_speed_100MHz); // to use as CS
178 }
179 
180 void digitalWrite(uint8_t pin, uint8_t value) { F4Light::GPIO::_write(pin, value); }
181 uint8_t digitalRead(uint8_t pin) { return F4Light::GPIO::_read(pin); }
182 
183 void digitalToggle(uint8_t pin) { return F4Light::GPIO::_toggle(pin); }
#define HAL_BUZZER_ON
Definition: board.h:39
uint16_t af
Definition: timer.h:580
Definition: GPIO.h:27
void timer_set_mode(const timer_dev *dev, timer_Channel channel, timer_mode mode)
Definition: timer.c:442
static void _pinMode(uint8_t pin, uint8_t output)
Definition: GPIO.cpp:21
void mode(uint8_t output)
Definition: GPIO.cpp:155
static uint32_t _timer_period(uint16_t speed_hz, const timer_dev *dev)
Definition: RCOutput.h:79
#define BOARD_BUZZER_PIN
Definition: board.h:33
#define BUZZER_PWM_HZ
Definition: board.h:34
timer_Channel timer_channel
Definition: boards.h:93
#define assert_param(expr)
static void _write(uint8_t pin, uint8_t value)
Definition: GPIO.h:165
static afio_exti_port gpio_exti_port(const gpio_dev *const dev)
Definition: gpio_hal.h:153
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
Definition: GPIO.h:35
uint32_t timer
static uint16_t pwm
Definition: RCOutput.cpp:20
void digitalToggle(uint8_t pin)
Definition: GPIO.cpp:183
void detach_interrupt(uint8_t pin)
Definition: GPIO.cpp:137
uint32_t freq
Definition: timer.h:563
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
Definition: gpio_hal.c:125
ExtIntTriggerMode
Definition: GPIO.h:99
void exti_attach_interrupt_pri(afio_exti_num num, afio_exti_port port, Handler handler, exti_trigger_mode mode, uint8_t priority)
Definition: exti.c:103
void digitalWrite(uint8_t pin, uint8_t value)
Definition: GPIO.cpp:180
uint8_t read(uint8_t pin) override
Definition: GPIO.cpp:79
uint8_t digitalRead(uint8_t pin)
Definition: GPIO.cpp:181
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
void toggle(uint8_t pin) override
Definition: GPIO.cpp:114
const timer_dev *const timer_device
Definition: boards.h:90
static uint8_t _read(uint8_t pin)
Definition: GPIO.h:164
afio_exti_num
Definition: exti.h:15
void write(uint8_t pin, uint8_t value) override
Definition: GPIO.cpp:86
static void timer_set_compare(const timer_dev *dev, timer_Channel channel, uint16_t value)
Set the compare value for the given timer channel.
Definition: timer.h:783
#define BOARD_NR_GPIO_PINS
Definition: board.h:96
#define NULL
Definition: hal_types.h:59
Definition: GPIO.h:87
Board-specific pin information.
gpio_pin_mode
GPIO Pin modes.
Definition: gpio_hal.h:23
static void _toggle(uint8_t pin)
Definition: GPIO.h:166
static bool _attach_interrupt(uint8_t pin, Handler h, uint8_t mode, uint8_t priority)
Definition: GPIO.cpp:123
timerState * state
Definition: timer.h:578
static void gpio_set_speed(const gpio_dev *const dev, uint8_t pin, GPIOSpeed_t gpio_speed)
Definition: gpio_hal.h:161
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
void pinMode(uint8_t pin, uint8_t output) override
Definition: GPIO.cpp:71
float value
uint64_t Handler
Definition: hal_types.h:19
static INLINE void timer_set_reload(const timer_dev *dev, uint32_t arr)
Set a timer&#39;s reload value.
Definition: timer.h:763
void exti_detach_interrupt(afio_exti_num num)
Unregister an external interrupt handler.
Definition: exti.c:143
static int8_t pin
Definition: AnalogIn.cpp:15
static DigitalSource * get_channel(uint16_t pin)
Definition: GPIO.h:170
AP_HAL::DigitalSource * channel(uint16_t n)
Definition: GPIO.cpp:147
uint8_t gpio_bit
Definition: boards.h:92
Stores STM32-specific information related to a given Maple pin.
Definition: boards.h:88
const gpio_dev *const gpio_device
Definition: boards.h:89
static exti_trigger_mode exti_out_mode(ExtIntTriggerMode mode)
Definition: GPIO.h:174