8 #pragma GCC optimize ("O2") 19 .clk = RCC_AHB1Periph_GPIOA,
27 .clk = RCC_AHB1Periph_GPIOB,
35 .clk = RCC_AHB1Periph_GPIOC,
43 .clk = RCC_AHB1Periph_GPIOD,
51 .clk = RCC_AHB1Periph_GPIOE,
59 .clk = RCC_AHB1Periph_GPIOF,
67 .clk = RCC_AHB1Periph_GPIOG,
84 GPIO_DeInit(dev->
GPIOx);
86 RCC_AHB1PeriphClockCmd(dev->
clk, ENABLE);
92 RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOA, ENABLE);
93 RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOA, DISABLE);
95 RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOB, ENABLE);
96 RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOB, DISABLE);
98 RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOC, ENABLE);
99 RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOC, DISABLE);
101 RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOD, ENABLE);
102 RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOD, DISABLE);
104 RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOE, ENABLE);
105 RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOE, DISABLE);
107 RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOF, ENABLE);
108 RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOF, DISABLE);
110 RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOG, ENABLE);
111 RCC_AHB1PeriphResetCmd(RCC_AHB1Periph_GPIOG, DISABLE);
114 RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE);
115 RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOB, ENABLE);
116 RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE);
117 RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOD, ENABLE);
118 RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOE, ENABLE);
119 RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOF, ENABLE);
120 RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOG, ENABLE);
131 GPIO_InitTypeDef config;
134 RCC_AHB1PeriphClockCmd(dev->
clk, ENABLE);
137 GPIO_StructInit(&config);
138 config.GPIO_Speed = GPIO_Speed_2MHz;
142 config.GPIO_Mode = GPIO_Mode_OUT;
143 config.GPIO_PuPd = GPIO_PuPd_NOPULL;
144 config.GPIO_OType = GPIO_OType_PP;
147 config.GPIO_Mode = GPIO_Mode_OUT;
148 config.GPIO_PuPd = GPIO_PuPd_NOPULL;
149 config.GPIO_OType = GPIO_OType_OD;
152 config.GPIO_Mode = GPIO_Mode_OUT;
153 config.GPIO_PuPd = GPIO_PuPd_UP;
154 config.GPIO_OType = GPIO_OType_OD;
157 config.GPIO_Mode = GPIO_Mode_IN;
158 config.GPIO_PuPd = GPIO_PuPd_NOPULL;
159 config.GPIO_OType = GPIO_OType_PP;
162 config.GPIO_Mode = GPIO_Mode_AN;
163 config.GPIO_PuPd = GPIO_PuPd_NOPULL;
164 config.GPIO_OType = GPIO_OType_PP;
167 config.GPIO_Mode = GPIO_Mode_IN;
168 config.GPIO_PuPd = GPIO_PuPd_UP;
169 config.GPIO_OType = GPIO_OType_PP;
172 config.GPIO_Mode = GPIO_Mode_IN;
173 config.GPIO_PuPd = GPIO_PuPd_DOWN;
174 config.GPIO_OType = GPIO_OType_PP;
177 config.GPIO_Mode = GPIO_Mode_AF;
178 config.GPIO_PuPd = GPIO_PuPd_NOPULL;
179 config.GPIO_OType = GPIO_OType_PP;
182 config.GPIO_Mode = GPIO_Mode_AF;
183 config.GPIO_PuPd = GPIO_PuPd_NOPULL;
184 config.GPIO_OType = GPIO_OType_OD;
187 config.GPIO_Mode = GPIO_Mode_AF;
188 config.GPIO_PuPd = GPIO_PuPd_UP;
189 config.GPIO_OType = GPIO_OType_OD;
195 config.GPIO_Pin =
BIT(pin);
196 GPIO_Init(dev->
GPIOx, &config);
const gpio_dev *const _GPIOF
#define assert_param(expr)
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
const gpio_dev *const _GPIOE
void gpio_init(const gpio_dev *const dev)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
static const gpio_dev * _gpios[]
gpio_pin_mode
GPIO Pin modes.
const gpio_dev *const _GPIOA
const gpio_dev *const _GPIOG
const gpio_dev *const _GPIOC
const gpio_dev *const _GPIOB
const gpio_dev *const _GPIOD