diff --git a/make/mcu/STM32F1.mk b/make/mcu/STM32F1.mk
index 0077c1920..cad3b840d 100644
--- a/make/mcu/STM32F1.mk
+++ b/make/mcu/STM32F1.mk
@@ -59,7 +59,6 @@ MCU_COMMON_SRC = \
drivers/adc_stm32f10x.c \
drivers/bus_i2c_stm32f10x.c \
drivers/dma.c \
- drivers/gpio_stm32f10x.c \
drivers/inverter.c \
drivers/light_ws2811strip_stdperiph.c \
drivers/serial_uart_init.c \
diff --git a/make/mcu/STM32F3.mk b/make/mcu/STM32F3.mk
index 2a0c8068a..71081bff7 100644
--- a/make/mcu/STM32F3.mk
+++ b/make/mcu/STM32F3.mk
@@ -70,7 +70,6 @@ MCU_COMMON_SRC = \
drivers/adc_stm32f30x.c \
drivers/bus_i2c_stm32f30x.c \
drivers/dma.c \
- drivers/gpio_stm32f30x.c \
drivers/light_ws2811strip_stdperiph.c \
drivers/pwm_output_dshot.c \
drivers/serial_uart_init.c \
diff --git a/make/mcu/STM32F4.mk b/make/mcu/STM32F4.mk
index 0d00b19e6..e4f6f0d3a 100644
--- a/make/mcu/STM32F4.mk
+++ b/make/mcu/STM32F4.mk
@@ -114,7 +114,6 @@ MCU_COMMON_SRC = \
drivers/adc_stm32f4xx.c \
drivers/bus_i2c_stm32f10x.c \
drivers/dma_stm32f4xx.c \
- drivers/gpio_stm32f4xx.c \
drivers/inverter.c \
drivers/light_ws2811strip_stdperiph.c \
drivers/pwm_output_dshot.c \
diff --git a/make/mcu/STM32F7.mk b/make/mcu/STM32F7.mk
index cb670684c..735076907 100644
--- a/make/mcu/STM32F7.mk
+++ b/make/mcu/STM32F7.mk
@@ -62,7 +62,6 @@ EXCLUDES = stm32f7xx_hal_can.c \
stm32f7xx_ll_dma2d.c \
stm32f7xx_ll_exti.c \
stm32f7xx_ll_fmc.c \
- stm32f7xx_ll_gpio.c \
stm32f7xx_ll_i2c.c \
stm32f7xx_ll_lptim.c \
stm32f7xx_ll_pwr.c \
@@ -149,7 +148,6 @@ MCU_COMMON_SRC = \
drivers/adc_stm32f7xx.c \
drivers/bus_i2c_hal.c \
drivers/dma_stm32f7xx.c \
- drivers/gpio_stm32f7xx.c \
drivers/light_ws2811strip_hal.c \
drivers/bus_spi_hal.c \
drivers/bus_spi_ll.c \
diff --git a/src/main/drivers/accgyro/accgyro_mpu6050.c b/src/main/drivers/accgyro/accgyro_mpu6050.c
index b2bf41ce5..a008d201f 100644
--- a/src/main/drivers/accgyro/accgyro_mpu6050.c
+++ b/src/main/drivers/accgyro/accgyro_mpu6050.c
@@ -28,7 +28,6 @@
#include "drivers/bus_i2c.h"
#include "drivers/exti.h"
-#include "drivers/gpio.h"
#include "drivers/gyro_sync.h"
#include "drivers/nvic.h"
#include "drivers/sensor.h"
diff --git a/src/main/drivers/accgyro/accgyro_mpu6500.c b/src/main/drivers/accgyro/accgyro_mpu6500.c
index 3693fa517..abec649c8 100644
--- a/src/main/drivers/accgyro/accgyro_mpu6500.c
+++ b/src/main/drivers/accgyro/accgyro_mpu6500.c
@@ -25,7 +25,6 @@
#include "common/maths.h"
#include "drivers/exti.h"
-#include "drivers/gpio.h"
#include "drivers/gyro_sync.h"
#include "drivers/sensor.h"
#include "drivers/time.h"
diff --git a/src/main/drivers/accgyro/accgyro_spi_icm20689.c b/src/main/drivers/accgyro/accgyro_spi_icm20689.c
index cdcfb59f5..7514b7ae9 100644
--- a/src/main/drivers/accgyro/accgyro_spi_icm20689.c
+++ b/src/main/drivers/accgyro/accgyro_spi_icm20689.c
@@ -26,7 +26,6 @@
#include "drivers/bus_spi.h"
#include "drivers/exti.h"
-#include "drivers/gpio.h"
#include "drivers/gyro_sync.h"
#include "drivers/io.h"
#include "drivers/sensor.h"
diff --git a/src/main/drivers/adc_stm32f30x.c b/src/main/drivers/adc_stm32f30x.c
index 1626a27b4..04e0802f2 100644
--- a/src/main/drivers/adc_stm32f30x.c
+++ b/src/main/drivers/adc_stm32f30x.c
@@ -22,7 +22,6 @@
#include "platform.h"
#include "drivers/accgyro/accgyro.h"
-#include "drivers/gpio.h"
#include "drivers/io.h"
#include "drivers/sensor.h"
#include "drivers/time.h"
diff --git a/src/main/drivers/barometer/barometer_bmp085.c b/src/main/drivers/barometer/barometer_bmp085.c
index 49a94b7a5..51082f9b8 100644
--- a/src/main/drivers/barometer/barometer_bmp085.c
+++ b/src/main/drivers/barometer/barometer_bmp085.c
@@ -28,7 +28,6 @@
#include "drivers/bus_i2c.h"
#include "drivers/bus_i2c_busdev.h"
#include "drivers/exti.h"
-#include "drivers/gpio.h"
#include "drivers/io.h"
#include "drivers/nvic.h"
#include "drivers/time.h"
diff --git a/src/main/drivers/compass/compass_ak8975.c b/src/main/drivers/compass/compass_ak8975.c
index d6413dad3..f36596580 100644
--- a/src/main/drivers/compass/compass_ak8975.c
+++ b/src/main/drivers/compass/compass_ak8975.c
@@ -29,7 +29,6 @@
#include "common/utils.h"
#include "drivers/bus_i2c.h"
-#include "drivers/gpio.h"
#include "drivers/sensor.h"
#include "drivers/time.h"
diff --git a/src/main/drivers/gpio.h b/src/main/drivers/gpio.h
deleted file mode 100644
index a3ad5fffc..000000000
--- a/src/main/drivers/gpio.h
+++ /dev/null
@@ -1,141 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * Cleanflight is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with Cleanflight. If not, see .
- */
-
-#pragma once
-
-#include "platform.h"
-
-#ifdef STM32F1
-typedef enum
-{
- Mode_AIN = 0x0,
- Mode_IN_FLOATING = 0x04,
- Mode_IPD = 0x28,
- Mode_IPU = 0x48,
- Mode_Out_OD = 0x14,
- Mode_Out_PP = 0x10,
- Mode_AF_OD = 0x1C,
- Mode_AF_PP = 0x18
-} GPIO_Mode;
-#endif
-
-#ifdef STM32F3
-typedef enum
-{
- Mode_AIN = (GPIO_PuPd_NOPULL << 2) | GPIO_Mode_AN,
- Mode_IN_FLOATING = (GPIO_PuPd_NOPULL << 2) | GPIO_Mode_IN,
- Mode_IPD = (GPIO_PuPd_DOWN << 2) | GPIO_Mode_IN,
- Mode_IPU = (GPIO_PuPd_UP << 2) | GPIO_Mode_IN,
- Mode_Out_OD = (GPIO_OType_OD << 4) | GPIO_Mode_OUT,
- Mode_Out_PP = (GPIO_OType_PP << 4) | GPIO_Mode_OUT,
- Mode_AF_OD = (GPIO_OType_OD << 4) | GPIO_Mode_AF,
- Mode_AF_PP = (GPIO_OType_PP << 4) | GPIO_Mode_AF,
- Mode_AF_PP_PD = (GPIO_OType_PP << 4) | (GPIO_PuPd_DOWN << 2) | GPIO_Mode_AF,
- Mode_AF_PP_PU = (GPIO_OType_PP << 4) | (GPIO_PuPd_UP << 2) | GPIO_Mode_AF
-} GPIO_Mode;
-#endif
-
-#ifdef STM32F4
-typedef enum
-{
- Mode_AIN = (GPIO_PuPd_NOPULL << 2) | GPIO_Mode_AN,
- Mode_IN_FLOATING = (GPIO_PuPd_NOPULL << 2) | GPIO_Mode_IN,
- Mode_IPD = (GPIO_PuPd_DOWN << 2) | GPIO_Mode_IN,
- Mode_IPU = (GPIO_PuPd_UP << 2) | GPIO_Mode_IN,
- Mode_Out_OD = (GPIO_OType_OD << 4) | GPIO_Mode_OUT,
- Mode_Out_PP = (GPIO_OType_PP << 4) | GPIO_Mode_OUT,
- Mode_AF_OD = (GPIO_OType_OD << 4) | GPIO_Mode_AF,
- Mode_AF_PP = (GPIO_OType_PP << 4) | GPIO_Mode_AF,
- Mode_AF_PP_PD = (GPIO_OType_PP << 4) | (GPIO_PuPd_DOWN << 2) | GPIO_Mode_AF,
- Mode_AF_PP_PU = (GPIO_OType_PP << 4) | (GPIO_PuPd_UP << 2) | GPIO_Mode_AF
-} GPIO_Mode;
-#endif
-
-#ifdef STM32F7
-typedef enum
-{
- Mode_AIN = (GPIO_NOPULL << 5) | GPIO_MODE_ANALOG,
- Mode_IN_FLOATING = (GPIO_NOPULL << 5) | GPIO_MODE_INPUT,
- Mode_IPD = (GPIO_PULLDOWN << 5) | GPIO_MODE_INPUT,
- Mode_IPU = (GPIO_PULLUP << 5) | GPIO_MODE_INPUT,
- Mode_Out_OD = GPIO_MODE_OUTPUT_OD,
- Mode_Out_PP = GPIO_MODE_OUTPUT_PP,
- Mode_AF_OD = GPIO_MODE_AF_OD,
- Mode_AF_PP = GPIO_MODE_AF_PP,
- Mode_AF_PP_PD = (GPIO_PULLDOWN << 5) | GPIO_MODE_AF_PP,
- Mode_AF_PP_PU = (GPIO_PULLUP << 5) | GPIO_MODE_AF_PP
-} GPIO_Mode;
-#endif
-
-typedef enum
-{
- Speed_10MHz = 1,
- Speed_2MHz,
- Speed_50MHz
-} GPIO_Speed;
-
-typedef enum
-{
- Pin_0 = 0x0001,
- Pin_1 = 0x0002,
- Pin_2 = 0x0004,
- Pin_3 = 0x0008,
- Pin_4 = 0x0010,
- Pin_5 = 0x0020,
- Pin_6 = 0x0040,
- Pin_7 = 0x0080,
- Pin_8 = 0x0100,
- Pin_9 = 0x0200,
- Pin_10 = 0x0400,
- Pin_11 = 0x0800,
- Pin_12 = 0x1000,
- Pin_13 = 0x2000,
- Pin_14 = 0x4000,
- Pin_15 = 0x8000,
- Pin_All = 0xFFFF
-} GPIO_Pin;
-
-typedef struct
-{
- uint16_t pin;
- GPIO_Mode mode;
- GPIO_Speed speed;
-} gpio_config_t;
-
-#ifndef UNIT_TEST
-#if defined(USE_HAL_DRIVER)
-static inline void digitalHi(GPIO_TypeDef *p, uint16_t i) { HAL_GPIO_WritePin(p,i,GPIO_PIN_SET); }
-static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { HAL_GPIO_WritePin(p,i,GPIO_PIN_RESET); }
-static inline void digitalToggle(GPIO_TypeDef *p, uint16_t i) { HAL_GPIO_TogglePin(p,i); }
-static inline uint16_t digitalIn(GPIO_TypeDef *p, uint16_t i) { return HAL_GPIO_ReadPin(p,i); }
-#else
-#if defined(STM32F4)
-static inline void digitalHi(GPIO_TypeDef *p, uint16_t i) { p->BSRRL = i; }
-static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { p->BSRRH = i; }
-#else
-static inline void digitalHi(GPIO_TypeDef *p, uint16_t i) { p->BSRR = i; }
-static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { p->BRR = i; }
-#endif
-static inline void digitalToggle(GPIO_TypeDef *p, uint16_t i) { p->ODR ^= i; }
-static inline uint16_t digitalIn(GPIO_TypeDef *p, uint16_t i) { return p->IDR & i; }
-#endif
-#endif
-
-
-void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config);
-void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc);
-void gpioPinRemapConfig(uint32_t remap, bool enable);
diff --git a/src/main/drivers/gpio_stm32f10x.c b/src/main/drivers/gpio_stm32f10x.c
deleted file mode 100644
index c20cd7a15..000000000
--- a/src/main/drivers/gpio_stm32f10x.c
+++ /dev/null
@@ -1,102 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * Cleanflight is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with Cleanflight. If not, see .
- */
-
-#include
-#include
-
-#include "platform.h"
-
-#include "drivers/gpio.h"
-
-void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
-{
- uint32_t pinpos;
- for (pinpos = 0; pinpos < 16; pinpos++) {
- // are we doing this pin?
- if (config->pin & (0x1 << pinpos)) {
- // reference CRL or CRH, depending whether pin number is 0..7 or 8..15
- __IO uint32_t *cr = &gpio->CRL + (pinpos / 8);
- // mask out extra bits from pinmode, leaving just CNF+MODE
- uint32_t currentmode = config->mode & 0x0F;
- // offset to CNF and MODE portions of CRx register
- uint32_t shift = (pinpos % 8) * 4;
- // Read out current CRx value
- uint32_t tmp = *cr;
- // if we're in output mode, add speed too.
- if (config->mode & 0x10)
- currentmode |= config->speed;
- // Mask out 4 bits
- tmp &= ~(0xF << shift);
- // apply current pinmode
- tmp |= currentmode << shift;
- *cr = tmp;
- // Special handling for IPD/IPU
- if (config->mode == Mode_IPD) {
- gpio->ODR &= ~(1U << pinpos);
- } else if (config->mode == Mode_IPU) {
- gpio->ODR |= (1U << pinpos);
- }
- }
- }
-}
-
-void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc)
-{
- uint32_t tmp = 0x00;
-
- tmp = ((uint32_t)0x0F) << (0x04 * (pinsrc & (uint8_t)0x03));
- AFIO->EXTICR[pinsrc >> 0x02] &= ~tmp;
- AFIO->EXTICR[pinsrc >> 0x02] |= (((uint32_t)portsrc) << (0x04 * (pinsrc & (uint8_t)0x03)));
-}
-
-#define LSB_MASK ((uint16_t)0xFFFF)
-#define DBGAFR_POSITION_MASK ((uint32_t)0x000F0000)
-#define DBGAFR_SWJCFG_MASK ((uint32_t)0xF0FFFFFF)
-#define DBGAFR_LOCATION_MASK ((uint32_t)0x00200000)
-#define DBGAFR_NUMBITS_MASK ((uint32_t)0x00100000)
-
-void gpioPinRemapConfig(uint32_t remap, bool enable)
-{
- uint32_t tmp = 0x00, tmp1 = 0x00, tmpreg = 0x00, tmpmask = 0x00;
- if ((remap & 0x80000000) == 0x80000000)
- tmpreg = AFIO->MAPR2;
- else
- tmpreg = AFIO->MAPR;
-
- tmpmask = (remap & DBGAFR_POSITION_MASK) >> 0x10;
- tmp = remap & LSB_MASK;
-
- if ((remap & (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) == (DBGAFR_LOCATION_MASK | DBGAFR_NUMBITS_MASK)) {
- tmpreg &= DBGAFR_SWJCFG_MASK;
- AFIO->MAPR &= DBGAFR_SWJCFG_MASK;
- } else if ((remap & DBGAFR_NUMBITS_MASK) == DBGAFR_NUMBITS_MASK) {
- tmp1 = ((uint32_t)0x03) << tmpmask;
- tmpreg &= ~tmp1;
- tmpreg |= ~DBGAFR_SWJCFG_MASK;
- } else {
- tmpreg &= ~(tmp << ((remap >> 0x15) * 0x10));
- tmpreg |= ~DBGAFR_SWJCFG_MASK;
- }
-
- if (enable)
- tmpreg |= (tmp << ((remap >> 0x15) * 0x10));
-
- if ((remap & 0x80000000) == 0x80000000)
- AFIO->MAPR2 = tmpreg;
- else
- AFIO->MAPR = tmpreg;
-}
diff --git a/src/main/drivers/gpio_stm32f30x.c b/src/main/drivers/gpio_stm32f30x.c
deleted file mode 100644
index 392ed8856..000000000
--- a/src/main/drivers/gpio_stm32f30x.c
+++ /dev/null
@@ -1,74 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * Cleanflight is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with Cleanflight. If not, see .
- */
-
-#include
-#include
-
-#include "platform.h"
-
-#include "drivers/gpio.h"
-
-#define MODE_OFFSET 0
-#define PUPD_OFFSET 2
-#define OUTPUT_OFFSET 4
-
-#define MODE_MASK ((1|2) << MODE_OFFSET)
-#define PUPD_MASK ((1|2) << PUPD_OFFSET)
-#define OUTPUT_MASK ((1|2) << OUTPUT_OFFSET)
-
-//#define GPIO_Speed_10MHz GPIO_Speed_Level_1 Fast Speed:10MHz
-//#define GPIO_Speed_2MHz GPIO_Speed_Level_2 Medium Speed:2MHz
-//#define GPIO_Speed_50MHz GPIO_Speed_Level_3 High Speed:50MHz
-
-void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
-{
- GPIO_InitTypeDef GPIO_InitStructure;
-
- uint32_t pinIndex;
- for (pinIndex = 0; pinIndex < 16; pinIndex++) {
- // are we doing this pin?
- uint32_t pinMask = (0x1 << pinIndex);
- if (config->pin & pinMask) {
-
- GPIO_InitStructure.GPIO_Pin = pinMask;
- GPIO_InitStructure.GPIO_Mode = (config->mode & MODE_MASK) >> MODE_OFFSET;
-
- GPIOSpeed_TypeDef speed = GPIO_Speed_10MHz;
- switch (config->speed) {
- case Speed_10MHz:
- speed = GPIO_Speed_Level_1;
- break;
- case Speed_2MHz:
- speed = GPIO_Speed_Level_2;
- break;
- case Speed_50MHz:
- speed = GPIO_Speed_Level_3;
- break;
- }
-
- GPIO_InitStructure.GPIO_Speed = speed;
- GPIO_InitStructure.GPIO_OType = (config->mode & OUTPUT_MASK) >> OUTPUT_OFFSET;
- GPIO_InitStructure.GPIO_PuPd = (config->mode & PUPD_MASK) >> PUPD_OFFSET;
- GPIO_Init(gpio, &GPIO_InitStructure);
- }
- }
-}
-
-void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc)
-{
- SYSCFG_EXTILineConfig(portsrc, pinsrc);
-}
diff --git a/src/main/drivers/gpio_stm32f4xx.c b/src/main/drivers/gpio_stm32f4xx.c
deleted file mode 100644
index 032cdd83a..000000000
--- a/src/main/drivers/gpio_stm32f4xx.c
+++ /dev/null
@@ -1,76 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * Cleanflight is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with Cleanflight. If not, see .
- */
-
-#include
-#include
-
-#include "platform.h"
-
-#include "build/build_config.h"
-
-#include "drivers/gpio.h"
-
-#define MODE_OFFSET 0
-#define PUPD_OFFSET 2
-#define OUTPUT_OFFSET 4
-
-#define MODE_MASK ((1|2))
-#define PUPD_MASK ((1|2))
-#define OUTPUT_MASK ((1|2))
-
-//#define GPIO_Speed_10MHz GPIO_Speed_Level_1 Fast Speed:10MHz
-//#define GPIO_Speed_2MHz GPIO_Speed_Level_2 Medium Speed:2MHz
-//#define GPIO_Speed_50MHz GPIO_Speed_Level_3 High Speed:50MHz
-
-void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
-{
- GPIO_InitTypeDef GPIO_InitStructure;
-
- uint32_t pinIndex;
- for (pinIndex = 0; pinIndex < 16; pinIndex++) {
- // are we doing this pin?
- uint32_t pinMask = (0x1 << pinIndex);
- if (config->pin & pinMask) {
-
- GPIO_InitStructure.GPIO_Pin = pinMask;
- GPIO_InitStructure.GPIO_Mode = (config->mode >> MODE_OFFSET) & MODE_MASK;
-
- GPIOSpeed_TypeDef speed = GPIO_Medium_Speed;
- switch (config->speed) {
- case Speed_10MHz:
- speed = GPIO_Medium_Speed;
- break;
- case Speed_2MHz:
- speed = GPIO_Low_Speed;
- break;
- case Speed_50MHz:
- speed = GPIO_Fast_Speed;
- break;
- }
-
- GPIO_InitStructure.GPIO_Speed = speed;
- GPIO_InitStructure.GPIO_OType = (config->mode >> OUTPUT_OFFSET) & OUTPUT_MASK;
- GPIO_InitStructure.GPIO_PuPd = (config->mode >> PUPD_OFFSET) & PUPD_MASK;
- GPIO_Init(gpio, &GPIO_InitStructure);
- }
- }
-}
-
-void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc)
-{
- SYSCFG_EXTILineConfig(portsrc, pinsrc);
-}
diff --git a/src/main/drivers/gpio_stm32f7xx.c b/src/main/drivers/gpio_stm32f7xx.c
deleted file mode 100644
index e29d07066..000000000
--- a/src/main/drivers/gpio_stm32f7xx.c
+++ /dev/null
@@ -1,69 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * Cleanflight is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with Cleanflight. If not, see .
- */
-
-#include
-#include
-
-#include "platform.h"
-
-#include "drivers/gpio.h"
-
-#define MODE_OFFSET 0
-#define PUPD_OFFSET 5
-
-#define MODE_MASK ((1|2|16))
-#define PUPD_MASK ((1|2))
-
-void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
-{
- GPIO_InitTypeDef GPIO_InitStructure;
-
- uint32_t pinIndex;
- for (pinIndex = 0; pinIndex < 16; pinIndex++) {
- // are we doing this pin?
- uint32_t pinMask = (0x1 << pinIndex);
- if (config->pin & pinMask) {
-
- GPIO_InitStructure.Pin = pinMask;
- GPIO_InitStructure.Mode = (config->mode >> MODE_OFFSET) & MODE_MASK;
-
- uint32_t speed = GPIO_SPEED_FREQ_MEDIUM;
- switch (config->speed) {
- case Speed_10MHz:
- speed = GPIO_SPEED_FREQ_MEDIUM;
- break;
- case Speed_2MHz:
- speed = GPIO_SPEED_FREQ_LOW;
- break;
- case Speed_50MHz:
- speed = GPIO_SPEED_FREQ_HIGH;
- break;
- }
-
- GPIO_InitStructure.Speed = speed;
- GPIO_InitStructure.Pull = (config->mode >> PUPD_OFFSET) & PUPD_MASK;
- HAL_GPIO_Init(gpio, &GPIO_InitStructure);
- }
- }
-}
-
-void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc)
-{
- (void)portsrc;
- (void)pinsrc;
- //SYSCFG_EXTILineConfig(portsrc, pinsrc);
-}
diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c
index 51ead6da5..f729ae264 100644
--- a/src/main/drivers/io.c
+++ b/src/main/drivers/io.c
@@ -156,8 +156,10 @@ bool IORead(IO_t io)
{
if (!io)
return false;
-#if defined(USE_HAL_DRIVER)
- return !! HAL_GPIO_ReadPin(IO_GPIO(io),IO_Pin(io));
+#if defined(USE_LOWLEVEL_DRIVER)
+ return !! (LL_GPIO_ReadInputPort(IO_GPIO(io)) & IO_Pin(io));
+#elif defined(USE_HAL_DRIVER)
+ return !! HAL_GPIO_ReadPin(IO_GPIO(io), IO_Pin(io));
#else
return !! (IO_GPIO(io)->IDR & IO_Pin(io));
#endif
@@ -167,7 +169,9 @@ void IOWrite(IO_t io, bool hi)
{
if (!io)
return;
-#if defined(USE_HAL_DRIVER)
+#if defined(USE_LOWLEVEL_DRIVER)
+ LL_GPIO_SetOutputPin(IO_GPIO(io), IO_Pin(io) << (hi ? 0 : 16));
+#elif defined(USE_HAL_DRIVER)
if (hi) {
HAL_GPIO_WritePin(IO_GPIO(io),IO_Pin(io),GPIO_PIN_SET);
}
@@ -190,7 +194,9 @@ void IOHi(IO_t io)
{
if (!io)
return;
-#if defined(USE_HAL_DRIVER)
+#if defined(USE_LOWLEVEL_DRIVER)
+ LL_GPIO_SetOutputPin(IO_GPIO(io), IO_Pin(io));
+#elif defined(USE_HAL_DRIVER)
HAL_GPIO_WritePin(IO_GPIO(io),IO_Pin(io),GPIO_PIN_SET);
#elif defined(STM32F4)
IO_GPIO(io)->BSRRL = IO_Pin(io);
@@ -203,7 +209,9 @@ void IOLo(IO_t io)
{
if (!io)
return;
-#if defined(USE_HAL_DRIVER)
+#if defined(USE_LOWLEVEL_DRIVER)
+ LL_GPIO_ResetOutputPin(IO_GPIO(io), IO_Pin(io));
+#elif defined(USE_HAL_DRIVER)
HAL_GPIO_WritePin(IO_GPIO(io),IO_Pin(io),GPIO_PIN_RESET);
#elif defined(STM32F4)
IO_GPIO(io)->BSRRH = IO_Pin(io);
@@ -216,11 +224,16 @@ void IOToggle(IO_t io)
{
if (!io)
return;
+
uint32_t mask = IO_Pin(io);
// Read pin state from ODR but write to BSRR because it only changes the pins
// high in the mask value rather than all pins. XORing ODR directly risks
// setting other pins incorrectly because it change all pins' state.
-#if defined(USE_HAL_DRIVER)
+#if defined(USE_LOWLEVEL_DRIVER)
+ if (LL_GPIO_ReadOutputPort(IO_GPIO(io)) & mask)
+ mask <<= 16; // bit is set, shift mask to reset half
+ LL_GPIO_SetOutputPin(IO_GPIO(io), mask);
+#elif defined(USE_HAL_DRIVER)
(void)mask;
HAL_GPIO_TogglePin(IO_GPIO(io),IO_Pin(io));
#elif defined(STM32F4)
@@ -284,18 +297,7 @@ void IOConfigGPIO(IO_t io, ioConfig_t cfg)
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
{
- if (!io)
- return;
- rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
- RCC_ClockCmd(rcc, ENABLE);
-
- GPIO_InitTypeDef init = {
- .Pin = IO_Pin(io),
- .Mode = (cfg >> 0) & 0x13,
- .Speed = (cfg >> 2) & 0x03,
- .Pull = (cfg >> 5) & 0x03,
- };
- HAL_GPIO_Init(IO_GPIO(io), &init);
+ IOConfigGPIOAF(io, cfg, 0);
}
void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
@@ -305,6 +307,17 @@ void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
RCC_ClockCmd(rcc, ENABLE);
+#if defined(USE_LOWLEVEL_DRIVER)
+ LL_GPIO_InitTypeDef init = {
+ .Pin = IO_Pin(io),
+ .Mode = (cfg >> 0) & 0x13,
+ .Speed = (cfg >> 2) & 0x03,
+ .Pull = (cfg >> 5) & 0x03,
+ .Alternate = af
+ };
+
+ LL_GPIO_Init(IO_GPIO(io), &init);
+#else
GPIO_InitTypeDef init = {
.Pin = IO_Pin(io),
.Mode = (cfg >> 0) & 0x13,
@@ -313,7 +326,9 @@ void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
.Alternate = af
};
HAL_GPIO_Init(IO_GPIO(io), &init);
+#endif
}
+
#elif defined(STM32F3) || defined(STM32F4)
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
diff --git a/src/main/drivers/rx_spi.c b/src/main/drivers/rx_spi.c
index 21608b8e9..f8f8bfdba 100644
--- a/src/main/drivers/rx_spi.c
+++ b/src/main/drivers/rx_spi.c
@@ -30,7 +30,6 @@
#include "drivers/bus_spi.h"
#include "bus_spi_soft.h"
-#include "drivers/gpio.h"
#include "drivers/io.h"
#include "io_impl.h"
#include "rcc.h"
diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c
index 0002b27d0..fa417bb19 100644
--- a/src/main/drivers/serial_uart.c
+++ b/src/main/drivers/serial_uart.c
@@ -33,7 +33,6 @@
#include "common/utils.h"
#include "drivers/dma.h"
-#include "drivers/gpio.h"
#include "drivers/inverter.h"
#include "drivers/nvic.h"
#include "drivers/rcc.h"
diff --git a/src/main/drivers/serial_uart_init.c b/src/main/drivers/serial_uart_init.c
index 780c822a6..1b6d9839d 100644
--- a/src/main/drivers/serial_uart_init.c
+++ b/src/main/drivers/serial_uart_init.c
@@ -34,7 +34,6 @@
#include "build/build_config.h"
#include "common/utils.h"
-#include "drivers/gpio.h"
#include "drivers/inverter.h"
#include "drivers/rcc.h"
diff --git a/src/main/drivers/system.c b/src/main/drivers/system.c
index a3eee7939..6219db349 100644
--- a/src/main/drivers/system.c
+++ b/src/main/drivers/system.c
@@ -20,7 +20,6 @@
#include "platform.h"
-#include "drivers/gpio.h"
#include "light_led.h"
#include "sound_beeper.h"
#include "drivers/nvic.h"
diff --git a/src/main/drivers/system_stm32f10x.c b/src/main/drivers/system_stm32f10x.c
index 536023fd2..ce6cb927f 100644
--- a/src/main/drivers/system_stm32f10x.c
+++ b/src/main/drivers/system_stm32f10x.c
@@ -20,7 +20,6 @@
#include "platform.h"
-#include "drivers/gpio.h"
#include "drivers/nvic.h"
#include "drivers/system.h"
@@ -48,13 +47,14 @@ void enableGPIOPowerUsageAndNoiseReductions(void)
{
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_GPIOC, ENABLE);
- gpio_config_t gpio;
+ GPIO_InitTypeDef GPIO_InitStructure = {
+ .GPIO_Mode = GPIO_Mode_AIN,
+ .GPIO_Pin = GPIO_Pin_All
+ };
- gpio.mode = Mode_AIN;
- gpio.pin = Pin_All;
- gpioInit(GPIOA, &gpio);
- gpioInit(GPIOB, &gpio);
- gpioInit(GPIOC, &gpio);
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
}
bool isMPUSoftReset(void)
@@ -91,13 +91,14 @@ void systemInit(void)
// Set USART1 TX (PA9) to output and high state to prevent a rs232 break condition on reset.
// See issue https://github.com/cleanflight/cleanflight/issues/1433
- gpio_config_t gpio;
+ GPIO_InitTypeDef GPIO_InitStructure = {
+ .GPIO_Mode = GPIO_Mode_Out_PP,
+ .GPIO_Pin = GPIO_Pin_9,
+ .GPIO_Speed = GPIO_Speed_2MHz
+ };
- gpio.mode = Mode_Out_PP;
- gpio.speed = Speed_2MHz;
- gpio.pin = Pin_9;
- digitalHi(GPIOA, gpio.pin);
- gpioInit(GPIOA, &gpio);
+ GPIOA->BSRR = GPIO_InitStructure.GPIO_Pin;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
// Turn off JTAG port 'cause we're using the GPIO for leds
#define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24)
diff --git a/src/main/drivers/system_stm32f30x.c b/src/main/drivers/system_stm32f30x.c
index f3a349706..cddc2c475 100644
--- a/src/main/drivers/system_stm32f30x.c
+++ b/src/main/drivers/system_stm32f30x.c
@@ -20,7 +20,6 @@
#include "platform.h"
-#include "drivers/gpio.h"
#include "drivers/nvic.h"
#include "drivers/system.h"
@@ -56,19 +55,21 @@ void enableGPIOPowerUsageAndNoiseReductions(void)
ENABLE
);
- gpio_config_t gpio;
+ GPIO_InitTypeDef GPIO_InitStructure = {
+ .GPIO_Mode = GPIO_Mode_AN,
+ .GPIO_OType = GPIO_OType_OD,
+ .GPIO_PuPd = GPIO_PuPd_NOPULL
+ };
- gpio.mode = Mode_AIN;
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All & ~(GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15); // Leave JTAG pins alone
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
- gpio.pin = Pin_All & ~(Pin_13 | Pin_14 | Pin_15); // Leave JTAG pins alone
- gpioInit(GPIOA, &gpio);
-
- gpio.pin = Pin_All;
- gpioInit(GPIOB, &gpio);
- gpioInit(GPIOC, &gpio);
- gpioInit(GPIOD, &gpio);
- gpioInit(GPIOE, &gpio);
- gpioInit(GPIOF, &gpio);
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+ GPIO_Init(GPIOE, &GPIO_InitStructure);
+ GPIO_Init(GPIOF, &GPIO_InitStructure);
}
bool isMPUSoftReset(void)
diff --git a/src/main/platform.h b/src/main/platform.h
index 1af328b40..42ca110b6 100644
--- a/src/main/platform.h
+++ b/src/main/platform.h
@@ -25,6 +25,9 @@
#include "stm32f7xx.h"
#include "stm32f7xx_hal.h"
+#include "stm32f7xx_ll_spi.h"
+#include "stm32f7xx_ll_gpio.h"
+
// Chip Unique ID on F7
#if defined(STM32F722xx)
#define U_ID_0 (*(uint32_t*)0x1ff07a10)
diff --git a/src/main/target/COLIBRI_RACE/i2c_bst.c b/src/main/target/COLIBRI_RACE/i2c_bst.c
index 845785a9f..7ac9476aa 100644
--- a/src/main/target/COLIBRI_RACE/i2c_bst.c
+++ b/src/main/target/COLIBRI_RACE/i2c_bst.c
@@ -23,7 +23,6 @@
#include "drivers/serial.h"
#include "drivers/bus_i2c.h"
-#include "drivers/gpio.h"
#include "drivers/system.h"
#include "drivers/time.h"
#include "drivers/timer.h"
diff --git a/src/main/target/RACEBASE/hardware_revision.c b/src/main/target/RACEBASE/hardware_revision.c
index c03d6a2c0..fc56c4e87 100755
--- a/src/main/target/RACEBASE/hardware_revision.c
+++ b/src/main/target/RACEBASE/hardware_revision.c
@@ -27,7 +27,6 @@
#include "drivers/bus_spi.h"
#include "drivers/sensor.h"
#include "drivers/io.h"
-#include "drivers/gpio.h"
#include "drivers/exti.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/accgyro/accgyro_mpu.h"
@@ -39,29 +38,23 @@ uint8_t hardwareRevision = 1;
void detectHardwareRevision(void)
{
- gpio_config_t gpio;
+ GPIO_InitTypeDef GPIO_InitStructure = {
+ .GPIO_Mode = GPIO_Mode_OUT,
+ .GPIO_OType = GPIO_OType_PP,
+ .GPIO_PuPd = GPIO_PuPd_NOPULL,
+ .GPIO_Speed = GPIO_Speed_2MHz
+ };
// GYRO CS as output
- gpio.pin = GPIO_Pin_5;
- gpio.mode = Mode_Out_PP;
- gpio.speed = Speed_2MHz;
- gpioInit(GPIOB, &gpio);
- GPIO_SetBits(GPIOB, GPIO_Pin_5);
+ GPIO_InitStructure.GPIO_Pin = (GPIO_Pin_5 | GPIO_Pin_12);
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+ GPIO_SetBits(GPIOB, GPIO_InitStructure.GPIO_Pin);
- gpio.pin = GPIO_Pin_7;
- gpio.mode = Mode_Out_PP;
- gpio.speed = Speed_2MHz;
- gpioInit(GPIOA, &gpio);
- GPIO_SetBits(GPIOA, GPIO_Pin_7);
-
- gpio.pin = GPIO_Pin_12;
- gpio.mode = Mode_Out_PP;
- gpio.speed = Speed_2MHz;
- gpioInit(GPIOB, &gpio);
- GPIO_SetBits(GPIOB, GPIO_Pin_12);
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_7;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+ GPIO_SetBits(GPIOA, GPIO_InitStructure.GPIO_Pin);
}
-
void updateHardwareRevision(void)
{
diff --git a/src/main/target/stm32f7xx_hal_conf.h b/src/main/target/stm32f7xx_hal_conf.h
index 7a87a45fa..e8114a5a0 100644
--- a/src/main/target/stm32f7xx_hal_conf.h
+++ b/src/main/target/stm32f7xx_hal_conf.h
@@ -370,7 +370,6 @@
#ifdef HAL_SPI_MODULE_ENABLED
#include "stm32f7xx_hal_spi.h"
- #include "stm32f7xx_ll_spi.h"
#endif /* HAL_SPI_MODULE_ENABLED */
#ifdef HAL_TIM_MODULE_ENABLED