diff --git a/src/main/target/BLUEJAYF4/target.h.orig b/src/main/target/BLUEJAYF4/target.h.orig
deleted file mode 100644
index a3c6593f84..0000000000
--- a/src/main/target/BLUEJAYF4/target.h.orig
+++ /dev/null
@@ -1,175 +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
-#define TARGET_BOARD_IDENTIFIER "BJF4"
-#define TARGET_CONFIG
-#define TARGET_VALIDATECONFIG
-#define TARGET_PREINIT
-
-#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
-
-#define USBD_PRODUCT_STRING "BlueJayF4"
-
-#define USE_HARDWARE_REVISION_DETECTION
-#define HW_PIN PB2
-
-#define BOARD_HAS_VOLTAGE_DIVIDER
-
-#define LED0 PB6
-#define LED1 PB5
-#define LED2 PB4
-
-#define BEEPER PC1
-#define BEEPER_OPT PB7
-#define BEEPER_INVERTED
-
-#define INVERTER_PIN_USART6 PB15
-//#define INVERTER_PIN_USART1 PC9
-
-#define UART1_INVERTER PC9
-
-// MPU6500 interrupt
-#define USE_EXTI
-#define MPU_INT_EXTI PC5
-#define USE_MPU_DATA_READY_SIGNAL
-//#define DEBUG_MPU_DATA_READY_INTERRUPT
-
-#define MPU6500_CS_PIN PC4
-#define MPU6500_SPI_INSTANCE SPI1
-
-#define ACC
-#define USE_ACC_MPU6500
-#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW0_DEG
-
-#define GYRO
-#define USE_GYRO_MPU6500
-#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW0_DEG
-
-//#define MAG
-//#define USE_MAG_AK8963
-
-#define BARO
-#define USE_BARO_MS5611
-#define MS5611_I2C_INSTANCE I2CDEV_1
-
-#define USE_SDCARD
-
-#define SDCARD_DETECT_INVERTED
-
-#define SDCARD_DETECT_PIN PD2
-#define SDCARD_SPI_INSTANCE SPI3
-#define SDCARD_SPI_CS_PIN PA15
-
-// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
-#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
-// Divide to under 25MHz for normal operation:
-#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
-
-#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5
-#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF5
-#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
-#define SDCARD_DMA_CHANNEL DMA_Channel_0
-
-// Performance logging for SD card operations:
-// #define AFATFS_USE_INTROSPECTIVE_LOGGING
-
-#define M25P16_CS_PIN PB7
-#define M25P16_SPI_INSTANCE SPI3
-
-#define USE_FLASHFS
-#define USE_FLASH_M25P16
-
-#define USE_VCP
-//#define VBUS_SENSING_PIN PA8
-//#define VBUS_SENSING_ENABLED
-
-#define USE_UART1
-#define UART1_RX_PIN PA10
-#define UART1_TX_PIN PA9
-
-#define USE_UART3
-#define UART3_RX_PIN PB11
-#define UART3_TX_PIN PB10
-
-#define USE_UART6
-#define UART6_RX_PIN PC7
-#define UART6_TX_PIN PC6
-
-#define USE_SOFTSERIAL1
-#define SOFTSERIAL1_RX_PIN PB0 // PWM5
-#define SOFTSERIAL1_TX_PIN PB1 // PWM6
-<<<<<<< HEAD
-
-#define USE_SOFTSERIAL2
-
-#define SERIAL_PORT_COUNT 6
-
-=======
-
-#define SERIAL_PORT_COUNT 5
-
->>>>>>> betaflight/patch_v3.1.6
-#define USE_ESCSERIAL
-#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
-
-#define USE_SPI
-
-#define USE_SPI_DEVICE_1
-#define SPI1_NSS_PIN PC4
-#define SPI1_SCK_PIN PA5
-#define SPI1_MISO_PIN PA6
-#define SPI1_MOSI_PIN PA7
-
-#define USE_SPI_DEVICE_3
-#define SPI3_NSS_PIN PB3
-#define SPI3_SCK_PIN PC10
-#define SPI3_MISO_PIN PC11
-#define SPI3_MOSI_PIN PC12
-
-#define USE_I2C
-#define I2C_DEVICE (I2CDEV_1)
-#define USE_I2C_PULLUP
-
-#define USE_ADC
-#define VBAT_ADC_PIN PC3
-#define CURRENT_METER_ADC_PIN PC2
-
-#define USE_ESC_SENSOR
-#define LED_STRIP
-
-#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
-
-#define DEFAULT_FEATURES FEATURE_BLACKBOX
-#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
-#define SERIALRX_PROVIDER SERIALRX_SBUS
-#define SERIALRX_UART SERIAL_PORT_USART6
-
-#define USE_SERIAL_4WAY_BLHELI_INTERFACE
-
-#define SPEKTRUM_BIND
-#define BIND_PIN PB11
-
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC 0xffff
-#define TARGET_IO_PORTD (BIT(2))
-
-#define USABLE_TIMER_CHANNEL_COUNT 7
-#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9) )
diff --git a/src/main/target/CC3D/target.h.orig b/src/main/target/CC3D/target.h.orig
deleted file mode 100644
index c2da16cb98..0000000000
--- a/src/main/target/CC3D/target.h.orig
+++ /dev/null
@@ -1,139 +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 .
- */
-
-#define TARGET_BOARD_IDENTIFIER "CC3D" // CopterControl 3D
-
-#define LED0 PB3
-
-#define INVERTER_PIN_USART1 PB2 // PB2 (BOOT1) used as inverter select GPIO
-
-#define BEEPER PA15
-#define BEEPER_OPT PA2
-
-#define USE_EXTI
-#define MPU_INT_EXTI PA3
-#define USE_MPU_DATA_READY_SIGNAL
-//#define DEBUG_MPU_DATA_READY_INTERRUPT
-
-#define USE_SPI
-#define USE_SPI_DEVICE_1
-#define USE_SPI_DEVICE_2
-
-#define USE_I2C
-#define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11
-
-#define MPU6000_CS_GPIO GPIOA
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
-
-#define M25P16_CS_GPIO GPIOB
-#define M25P16_CS_PIN PB12
-#define M25P16_SPI_INSTANCE SPI2
-
-#define USE_FLASHFS
-#define USE_FLASH_M25P16
-
-#define GYRO
-#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
-
-#define ACC
-#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
-
-// MPU6000 interrupts
-#define USE_MPU_DATA_READY_SIGNAL
-
-// External I2C BARO
-//#define BARO
-//#define USE_BARO_MS5611
-//#define USE_BARO_BMP085
-//#define USE_BARO_BMP280
-
-// External I2C MAG
-//#define MAG
-//#define USE_MAG_HMC5883
-
-#define USE_VCP
-#define USE_UART1
-#define USE_UART3
-#define USE_SOFTSERIAL1
-<<<<<<< HEAD
-#define USE_SOFTSERIAL2
-
-#define SERIAL_PORT_COUNT 5
-
-#ifndef CC3D_OPBL
-#define SOFTSERIAL1_TX_PIN PB5 // PWM 2
-#define SOFTSERIAL1_RX_PIN PB0 // PWM 3
-=======
-#define SOFTSERIAL1_TX_PIN PB5 // PWM 2
-#define SOFTSERIAL1_RX_PIN PB0 // PWM 3
-#define SERIAL_PORT_COUNT 4
->>>>>>> betaflight/patch_v3.1.6
-#endif
-
-#ifdef USE_UART1_RX_DMA
-#undef USE_UART1_RX_DMA
-#endif
-
-#define UART3_RX_PIN PB11
-#define UART3_TX_PIN PB10
-
-#define USE_ADC
-#define CURRENT_METER_ADC_PIN PB1
-#define VBAT_ADC_PIN PA0
-#define RSSI_ADC_PIN PB0
-
-#define SPEKTRUM_BIND
-// USART3, PB11 (Flexport)
-#define BIND_PIN PB11
-
-#define USE_SERIAL_4WAY_BLHELI_INTERFACE
-
-//#define SONAR
-//#define SONAR_ECHO_PIN PB0
-//#define SONAR_TRIGGER_PIN PB5
-
-#undef GPS
-#undef MAG
-
-#ifdef CC3D_OPBL
-#define SKIP_CLI_COMMAND_HELP
-//#undef USE_SERVOS
-#undef BARO
-#undef SONAR
-#undef LED_STRIP
-#undef USE_SERIAL_4WAY_BLHELI_INTERFACE
-//#undef USE_SERIALRX_SPEKTRUM // SRXL, DSM2 and DSMX protocol
-//#undef USE_SERIALRX_SBUS // Frsky and Futaba receivers
-//#undef USE_SERIALRX_IBUS // FlySky and Turnigy receivers
-#undef USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol
-#undef USE_SERIALRX_SUMD // Graupner Hott protocol
-#undef USE_SERIALRX_SUMH // Graupner legacy protocol
-#undef USE_SERIALRX_XBUS // JR
-#endif
-
-#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
-
-// IO - from schematics
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC ( BIT(14) )
-
-#define USABLE_TIMER_CHANNEL_COUNT 12
-#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
diff --git a/src/main/target/KISSFC/target.h.orig b/src/main/target/KISSFC/target.h.orig
deleted file mode 100644
index a089bea162..0000000000
--- a/src/main/target/KISSFC/target.h.orig
+++ /dev/null
@@ -1,123 +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
-
-#define TARGET_BOARD_IDENTIFIER "KISS"
-
-#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
-
-#define SBUS_PORT_OPTIONS (SERIAL_STOPBITS_2 | SERIAL_PARITY_EVEN | SERIAL_INVERTED | SERIAL_BIDIR)
-
-#define USE_ESC_SENSOR
-
-#define USE_ESCSERIAL
-#define ESCSERIAL_TIMER_TX_HARDWARE 6
-#define REMAP_TIM17_DMA
-
-#define LED0 PB1
-
-#define BEEPER PB13
-#define BEEPER_INVERTED
-
-#define USE_EXTI
-#define MPU_INT_EXTI PB2
-#define USE_MPU_DATA_READY_SIGNAL
-#define ENSURE_MPU_DATA_READY_IS_LOW
-#ifdef KISSCC
-#define TARGET_CONFIG
-
-#define GYRO
-#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW90_DEG
-
-#define ACC
-#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW90_DEG
-#else
-#define GYRO
-#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW180_DEG
-
-#define ACC
-#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW180_DEG
-
-#define LED_STRIP
-#endif
-
-#define USE_VCP
-#define USE_UART1
-#define USE_UART2
-#define USE_UART3
-<<<<<<< HEAD
-#define USE_SOFTSERIAL1
-#define USE_SOFTSERIAL2
-
-#define SERIAL_PORT_COUNT 6
-=======
->>>>>>> betaflight/patch_v3.1.6
-
-#define UART1_TX_PIN PA9
-#define UART1_RX_PIN PA10
-
-#define UART2_TX_PIN PB3
-#define UART2_RX_PIN PB4
-
-#define UART3_TX_PIN PB10 // PB10 (AF7)
-#define UART3_RX_PIN PB11 // PB11 (AF7)
-
-#ifdef KISSCC
-<<<<<<< HEAD
-#define SOFTSERIAL1_TX_PIN PA13
-=======
-#define USE_SOFTSERIAL1
-#define SOFTSERIAL1_TX_PIN PA13
-#define SERIAL_PORT_COUNT 5
-#else
-#define SERIAL_PORT_COUNT 4
->>>>>>> betaflight/patch_v3.1.6
-#endif
-
-#define USE_I2C
-#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
-
-#define USE_ADC
-#define VBAT_SCALE_DEFAULT 160
-#define ADC_INSTANCE ADC1
-#define VBAT_ADC_PIN PA0
-//#define CURRENT_METER_ADC_PIN PA5
-//#define RSSI_ADC_PIN PB2
-
-#define DEFAULT_FEATURES FEATURE_VBAT
-#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
-#define SERIALRX_PROVIDER SERIALRX_SBUS
-#define SERIALRX_UART SERIAL_PORT_USART2
-
-#define AVOID_UART2_FOR_PWM_PPM
-
-#define SPEKTRUM_BIND
-#define BIND_PIN PB4
-
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC 0xffff
-#define TARGET_IO_PORTD 0xffff
-#define TARGET_IO_PORTF (BIT(4))
-
-#define USABLE_TIMER_CHANNEL_COUNT 11
-#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17))
diff --git a/src/main/target/OMNIBUS/target.h.orig b/src/main/target/OMNIBUS/target.h.orig
deleted file mode 100644
index bd80fb5336..0000000000
--- a/src/main/target/OMNIBUS/target.h.orig
+++ /dev/null
@@ -1,192 +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
-
-#define TARGET_BOARD_IDENTIFIER "OMNI" // https://en.wikipedia.org/wiki/Omnibus
-
-#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
-
-#define LED0 PB3
-
-#define BEEPER PC15
-#define BEEPER_INVERTED
-
-#define USE_EXTI
-#define MPU_INT_EXTI PC13
-#define USE_MPU_DATA_READY_SIGNAL
-#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect
-
-#define MPU6000_SPI_INSTANCE SPI1
-#define MPU6000_CS_PIN PA4
-
-#define GYRO
-#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW90_DEG
-
-#define ACC
-#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW90_DEG
-
-#define BMP280_SPI_INSTANCE SPI1
-#define BMP280_CS_PIN PA13
-
-#define BARO
-#define USE_BARO_BMP280
-#define USE_BARO_SPI_BMP280
-
-#define MAG // External
-#define USE_MAG_AK8963
-#define USE_MAG_AK8975
-#define USE_MAG_HMC5883
-
-//#define SONAR
-//#define SONAR_ECHO_PIN PB1
-//#define SONAR_TRIGGER_PIN PB0
-
-#undef GPS
-
-#define USB_IO
-#define USB_CABLE_DETECTION
-#define USB_DETECT_PIN PB5
-
-#define USE_VCP
-#define USE_UART1
-#define USE_UART2
-#define USE_UART3
-<<<<<<< HEAD
-#define USE_SOFTSERIAL1
-#define USE_SOFTSERIAL2
-
-#define SERIAL_PORT_COUNT 6
-=======
-#define SERIAL_PORT_COUNT 4
->>>>>>> betaflight/patch_v3.1.6
-
-#define UART1_TX_PIN PA9
-#define UART1_RX_PIN PA10
-
-#define UART2_TX_PIN PA14 // PA14 / SWCLK
-#define UART2_RX_PIN PA15
-
-#define UART3_TX_PIN PB10 // PB10 (AF7)
-#define UART3_RX_PIN PB11 // PB11 (AF7)
-
-#undef USE_I2C
-//#define USE_I2C
-//#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
-
-#define USE_ESCSERIAL
-#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
-
-#define USE_SPI
-#define USE_SPI_DEVICE_1
-
-#define SPI1_NSS_PIN PA4
-#define SPI1_SCK_PIN PA5
-#define SPI1_MISO_PIN PA6
-#define SPI1_MOSI_PIN PA7
-
-// OSD define info:
-// feature name (includes source) -> MAX_OSD, used in target.mk
-// include the osd code
-#define OSD
-
-// include the max7456 driver
-#define USE_MAX7456
-#define MAX7456_SPI_INSTANCE SPI1
-#define MAX7456_SPI_CS_PIN PB1
-#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD*2)
-#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
-//#define MAX7456_DMA_CHANNEL_TX DMA1_Channel3
-//#define MAX7456_DMA_CHANNEL_RX DMA1_Channel2
-//#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_CH3_HANDLER
-
-#define USE_SPI
-#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
-
-#define SPI2_NSS_PIN PB12
-#define SPI2_SCK_PIN PB13
-#define SPI2_MISO_PIN PB14
-#define SPI2_MOSI_PIN PB15
-
-#define USE_SDCARD
-#define USE_SDCARD_SPI2
-
-#define SDCARD_DETECT_INVERTED
-
-#define SDCARD_DETECT_PIN PC14
-#define SDCARD_SPI_INSTANCE SPI2
-#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
-
-// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
-#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
-// Divide to under 25MHz for normal operation:
-#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
-
-#define USE_ESC_SENSOR
-
-// DSHOT output 4 uses DMA1_Channel5, so don't use it for the SDCARD until we find an alternative
-#ifndef USE_DSHOT
-#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
-#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
-#endif
-
-// Performance logging for SD card operations:
-// #define AFATFS_USE_INTROSPECTIVE_LOGGING
-
-#define USE_ADC
-//#define BOARD_HAS_VOLTAGE_DIVIDER
-#define VBAT_ADC_PIN PA0
-#define CURRENT_METER_ADC_PIN PA1
-#define ADC_INSTANCE ADC1
-
-//#define RSSI_ADC_PIN PB1
-//#define ADC_INSTANCE ADC3
-
-#define LED_STRIP
-
-#define TRANSPONDER
-#define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT
-
-#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
-
-#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
-#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX)
-
-#define BUTTONS
-#define BUTTON_A_PIN PB1
-#define BUTTON_B_PIN PB0
-
-//#define AVOID_UART3_FOR_PWM_PPM // Disable this for using UART3
-
-#define SPEKTRUM_BIND
-// USART3,
-#define BIND_PIN PB11
-
-#define HARDWARE_BIND_PLUG
-#define BINDPLUG_PIN PB0
-
-#define USE_SERIAL_4WAY_BLHELI_INTERFACE
-
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
-#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
-
-#define USABLE_TIMER_CHANNEL_COUNT 8 // PPM + 6 Outputs (2 shared with UART3)
-#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15))
diff --git a/src/main/target/REVO/target.h.orig b/src/main/target/REVO/target.h.orig
deleted file mode 100644
index e1a2dd8def..0000000000
--- a/src/main/target/REVO/target.h.orig
+++ /dev/null
@@ -1,224 +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
-
-#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
-
-#if defined(AIRBOTF4)
-#define TARGET_BOARD_IDENTIFIER "AIR4"
-#define USBD_PRODUCT_STRING "AirbotF4"
-
-#elif defined(REVOLT)
-#define TARGET_BOARD_IDENTIFIER "RVLT"
-#define USBD_PRODUCT_STRING "Revolt"
-#define TARGET_DEFAULT_MIXER MIXER_QUADX_1234
-
-#elif defined(SOULF4)
-#define TARGET_BOARD_IDENTIFIER "SOUL"
-#define USBD_PRODUCT_STRING "DemonSoulF4"
-
-#elif defined(PODIUMF4)
-#define TARGET_BOARD_IDENTIFIER "PODI"
-#define USBD_PRODUCT_STRING "PodiumF4"
-
-#else
-#define TARGET_BOARD_IDENTIFIER "REVO"
-#define USBD_PRODUCT_STRING "Revolution"
-
-#ifdef OPBL
-#define USBD_SERIALNUMBER_STRING "0x8020000"
-#endif
-
-#endif
-
-#define USE_ESC_SENSOR
-
-#define LED0 PB5
-#if defined(PODIUMF4)
-#define LED1 PB4
-#define LED2 PB6
-#endif
-
-// Disable LED1, conflicts with AirbotF4/Flip32F4/Revolt beeper
-#if defined(AIRBOTF4)
-#define BEEPER PB4
-#define BEEPER_INVERTED
-#elif defined(REVOLT)
-#define BEEPER PB4
-#elif defined(SOULF4)
-#define BEEPER PB6
-#define BEEPER_INVERTED
-#else
-#define LED1 PB4
-// Leave beeper here but with none as io - so disabled unless mapped.
-#define BEEPER NONE
-#endif
-
-// PC0 used as inverter select GPIO
-#define INVERTER_PIN_USART1 PC0
-
-#define MPU6000_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
-
-#define MPU6500_CS_PIN PA4
-#define MPU6500_SPI_INSTANCE SPI1
-
-#if defined(SOULF4)
-#define ACC
-#define USE_ACC_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW180_DEG
-
-#define GYRO
-#define USE_GYRO_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW180_DEG
-
-#elif defined(REVOLT) || defined(PODIUMF4)
-
-#define USE_ACC_MPU6500
-#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW0_DEG
-
-#define USE_GYRO_MPU6500
-#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW0_DEG
-
-#else
-#define ACC
-#define USE_ACC_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
-
-#define USE_ACC_MPU6500
-#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
-
-#define GYRO
-#define USE_GYRO_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
-
-#define USE_GYRO_MPU6500
-#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
-
-#endif
-
-// MPU6000 interrupts
-#define USE_EXTI
-#define MPU_INT_EXTI PC4
-#define USE_MPU_DATA_READY_SIGNAL
-
-#if !defined(AIRBOTF4) && !defined(REVOLT) && !defined(SOULF4) && !defined(PODIUMF4)
-#define MAG
-#define USE_MAG_HMC5883
-#define MAG_HMC5883_ALIGN CW90_DEG
-
-#define BARO
-#define USE_BARO_MS5611
-
-#endif
-
-#define M25P16_CS_PIN PB3
-#define M25P16_SPI_INSTANCE SPI3
-
-#define USE_FLASHFS
-#define USE_FLASH_M25P16
-
-#define USE_VCP
-#if defined(PODIUMF4)
-#define VBUS_SENSING_PIN PA8
-#else
-#define VBUS_SENSING_PIN PC5
-#endif
-
-#define USE_UART1
-#define UART1_RX_PIN PA10
-#define UART1_TX_PIN PA9
-#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
-
-#define USE_UART3
-#define UART3_RX_PIN PB11
-#define UART3_TX_PIN PB10
-
-#define USE_UART6
-#define UART6_RX_PIN PC7
-#define UART6_TX_PIN PC6
-
-<<<<<<< HEAD
-#define USE_SOFTSERIAL1
-#define USE_SOFTSERIAL2
-
-#define SERIAL_PORT_COUNT 6 //VCP, USART1, USART3, USART6, SOFTSERIAL x 2
-=======
-#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6
->>>>>>> betaflight/patch_v3.1.6
-
-#define USE_ESCSERIAL
-#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
-
-#define USE_SPI
-
-#define USE_SPI_DEVICE_1
-
-#define USE_SPI_DEVICE_3
-#define SPI3_NSS_PIN PB3
-#define SPI3_SCK_PIN PC10
-#define SPI3_MISO_PIN PC11
-#define SPI3_MOSI_PIN PC12
-
-#define USE_I2C
-#define I2C_DEVICE (I2CDEV_1)
-
-#define USE_ADC
-#if !defined(PODIUMF4)
-#define CURRENT_METER_ADC_PIN PC1
-#define VBAT_ADC_PIN PC2
-#else
-#define VBAT_ADC_PIN PC3
-#define VBAT_ADC_CHANNEL ADC_Channel_13
-#endif
-
-#define LED_STRIP
-
-#define SENSORS_SET (SENSOR_ACC)
-
-#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
-#if defined(PODIUMF4)
-#define SERIALRX_PROVIDER SERIALRX_SBUS
-#define SERIALRX_UART SERIAL_PORT_USART6
-#define DEFAULT_FEATURES FEATURE_TELEMETRY
-#else
-#define DEFAULT_FEATURES (FEATURE_BLACKBOX)
-#endif
-
-#define SPEKTRUM_BIND
-// USART3,
-#define BIND_PIN PB11
-
-#define USE_SERIAL_4WAY_BLHELI_INTERFACE
-
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC 0xffff
-#define TARGET_IO_PORTD (BIT(2))
-
-#ifdef REVOLT
-#define USABLE_TIMER_CHANNEL_COUNT 11
-#else
-#define USABLE_TIMER_CHANNEL_COUNT 12
-#endif
-
-#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) )
diff --git a/src/main/target/SPRACINGF3/target.h.orig b/src/main/target/SPRACINGF3/target.h.orig
deleted file mode 100644
index c618d93a44..0000000000
--- a/src/main/target/SPRACINGF3/target.h.orig
+++ /dev/null
@@ -1,203 +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
-
-#if defined(RMDO)
-#define TARGET_BOARD_IDENTIFIER "RMDO"
-#elif defined(ZCOREF3)
-#define TARGET_BOARD_IDENTIFIER "ZCF3"
-#elif defined(FLIP32F3OSD)
-#define TARGET_BOARD_IDENTIFIER "FLF3"
-#else
-#define TARGET_BOARD_IDENTIFIER "SRF3"
-#endif
-
-#if defined(ZCOREF3)
-#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
-
-#define LED0 PB8
-#else
-#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
-
-#define LED0 PB3
-#endif
-
-#if defined(ZCOREF3)
-#define EXTI15_10_CALLBACK_HANDLER_COUNT 1
-#elif defined(FLIP32F3OSD)
-#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready and MAG data ready
-#endif
-
-#define BEEPER PC15
-#define BEEPER_INVERTED
-
-#define USE_EXTI
-#define MPU_INT_EXTI PC13
-#define USE_MPU_DATA_READY_SIGNAL
-#define ENSURE_MPU_DATA_READY_IS_LOW
-
-#define GYRO
-
-#define ACC
-
-#define BARO
-#define USE_BARO_BMP280
-
-#if defined(FLIP32F3OSD)
-#define USE_GYRO_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
-
-#define USE_ACC_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
-
-#elif defined(ZCOREF3)
-#define GYRO
-#define USE_GYRO_MPU6500
-#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW180_DEG
-
-#define ACC
-#define USE_ACC_MPU6500
-#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW180_DEG
-
-#define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU)
-
-#define SPI1_NSS_PIN PB9
-#define SPI1_SCK_PIN PB3
-#define SPI1_MISO_PIN PB4
-#define SPI1_MOSI_PIN PB5
-
-#define MPU6500_CS_PIN PB9
-#define MPU6500_SPI_INSTANCE SPI1
-
-#else
-#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW270_DEG
-
-#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW270_DEG
-#endif
-
-#if defined(FLIP32F3OSD)
-#define SONAR
-#define SONAR_TRIGGER_PIN PB0
-#define SONAR_ECHO_PIN PB1
-
-#elif defined(RMDO)
-#undef USE_GPS
-
-#elif defined(ZCOREF3)
-#define USE_MAG_DATA_READY_SIGNAL
-#define ENSURE_MAG_DATA_READY_IS_HIGH
-
-#else //SPRACINGF3
-#define USE_BARO_MS5611
-#define USE_BARO_BMP085
-
-#define MAG
-#define USE_MAG_AK8975
-#define USE_MAG_HMC5883
-#define MAG_HMC5883_ALIGN CW270_DEG
-
-#define USE_MAG_DATA_READY_SIGNAL
-#define ENSURE_MAG_DATA_READY_IS_HIGH
-#define MAG_INT_EXTI PC14
-#endif
-
-#define USE_FLASHFS
-#define USE_FLASH_M25P16
-
-#define USE_UART1
-#define USE_UART2
-#define USE_UART3
-#define USE_SOFTSERIAL1
-#define USE_SOFTSERIAL2
-
-#define SERIAL_PORT_COUNT 5
-
-<<<<<<< HEAD
-#if !defined(ZCOREF3)
-=======
->>>>>>> betaflight/patch_v3.1.6
-#define SOFTSERIAL1_RX_PIN PB4 // PWM 5
-#define SOFTSERIAL1_TX_PIN PB5 // PWM 6
-
-#define SOFTSERIAL2_RX_PIN PB0 // PWM 7
-#define SOFTSERIAL2_TX_PIN PB1 // PWM 8
-
-#define SONAR_SOFTSERIAL2_EXCLUSIVE
-#endif
-
-#define USE_ESCSERIAL
-#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
-
-#define UART1_TX_PIN PA9
-#define UART1_RX_PIN PA10
-
-#define UART2_TX_PIN PA14 // PA14 / SWCLK
-#define UART2_RX_PIN PA15
-
-#define UART3_TX_PIN PB10 // PB10 (AF7)
-#define UART3_RX_PIN PB11 // PB11 (AF7)
-
-#define USE_I2C
-#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
-
-#define USE_SPI
-#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
-
-#define M25P16_CS_PIN PB12
-#define M25P16_SPI_INSTANCE SPI2
-
-#define BOARD_HAS_VOLTAGE_DIVIDER
-#define USE_ADC
-#define ADC_INSTANCE ADC2
-#define VBAT_ADC_PIN PA4
-#define CURRENT_METER_ADC_PIN PA5
-#define RSSI_ADC_PIN PB2
-
-#define USE_ESC_SENSOR
-#define REMAP_TIM17_DMA
-
-// UART1 TX uses DMA1_Channel4, which is also used by dshot on motor 4
-#if defined(USE_UART1_TX_DMA) && defined(USE_DSHOT)
-#undef USE_UART1_TX_DMA
-#endif
-
-#define LED_STRIP
-
-#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
-
-#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
-#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY)
-
-#define SPEKTRUM_BIND
-// USART3,
-#define BIND_PIN PB11
-
-#define USE_SERIAL_4WAY_BLHELI_INTERFACE
-
-// IO - stm32f303cc in 48pin package
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
-#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
-
-#define USABLE_TIMER_CHANNEL_COUNT 17
-#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
diff --git a/src/main/target/SPRACINGF3MINI/target.h.orig b/src/main/target/SPRACINGF3MINI/target.h.orig
deleted file mode 100644
index 2c2f35fa4b..0000000000
--- a/src/main/target/SPRACINGF3MINI/target.h.orig
+++ /dev/null
@@ -1,218 +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
-
-#ifdef TINYBEEF3
-#define TARGET_BOARD_IDENTIFIER "TBF3"
-
-#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
-
-#define LED0 PB8
-#else
-#define TARGET_BOARD_IDENTIFIER "SRFM"
-
-#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
-
-// early prototype had slightly different pin mappings.
-//#define SPRACINGF3MINI_MKII_REVA
-
-#define LED0 PB3
-#endif
-
-#define BEEPER PC15
-#define BEEPER_INVERTED
-
-#define USE_EXTI
-#define MPU_INT_EXTI PC13
-#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect
-#define USE_MPU_DATA_READY_SIGNAL
-#define ENSURE_MPU_DATA_READY_IS_LOW
-
-#define USE_MAG_DATA_READY_SIGNAL
-#define ENSURE_MAG_DATA_READY_IS_HIGH
-
-#define GYRO
-#define ACC
-
-#define BARO
-#define USE_BARO_BMP280
-
-#ifdef TINYBEEF3
-#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
-
-#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
-
-#define MAG_AK8963_ALIGN CW90_DEG_FLIP
-#else
-//#define USE_FAKE_GYRO
-#define USE_GYRO_MPU6500
-#define GYRO_MPU6500_ALIGN CW180_DEG
-
-//#define USE_FAKE_ACC
-#define USE_ACC_MPU6500
-#define ACC_MPU6500_ALIGN CW180_DEG
-
-#define MAG
-#define USE_MPU9250_MAG // Enables bypass configuration
-#define USE_MAG_AK8975
-#define USE_MAG_HMC5883 // External
-#define MAG_AK8975_ALIGN CW90_DEG_FLIP
-#endif
-
-//#define SONAR
-//#define SONAR_ECHO_PIN PB1
-//#define SONAR_TRIGGER_PIN PB0
-
-#define USB_IO
-
-#ifndef TINYBEEF3
-#define USB_CABLE_DETECTION
-
-#define USB_DETECT_PIN PB5
-#endif
-
-#define USE_VCP
-#define USE_UART1
-#define USE_UART2
-#define USE_UART3
-
-#ifdef TINYBEEF3
-#define SERIAL_PORT_COUNT 4
-#else
-#define USE_SOFTSERIAL1
-<<<<<<< HEAD
-#define USE_SOFTSERIAL2
-#define SERIAL_PORT_COUNT 6
-=======
-#define SERIAL_PORT_COUNT 5
->>>>>>> betaflight/patch_v3.1.6
-#endif
-
-#define USE_ESCSERIAL
-#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
-
-#define UART1_TX_PIN PA9
-#define UART1_RX_PIN PA10
-
-#define UART2_TX_PIN PA14 // PA14 / SWCLK
-#define UART2_RX_PIN PA15
-
-#define UART3_TX_PIN PB10 // PB10 (AF7)
-#define UART3_RX_PIN PB11 // PB11 (AF7)
-
-#ifndef TINYBEEF3
-#define SOFTSERIAL1_RX_PIN PA0 // PA0 / PAD3
-#define SOFTSERIAL1_TX_PIN PA1 // PA1 / PAD4
-#endif
-
-#define SONAR_SOFTSERIAL1_EXCLUSIVE
-
-#define USE_I2C
-#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
-
-#define USE_SPI
-#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
-
-#define SPI2_NSS_PIN PB12
-#define SPI2_SCK_PIN PB13
-#define SPI2_MISO_PIN PB14
-#define SPI2_MOSI_PIN PB15
-
-#ifdef TINYBEEF3
-#define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU)
-
-#define SPI1_NSS_PIN PB9
-#define SPI1_SCK_PIN PB3
-#define SPI1_MISO_PIN PB4
-#define SPI1_MOSI_PIN PB5
-
-#define MPU6500_CS_PIN PB9
-#define MPU6500_SPI_INSTANCE SPI1
-#endif
-
-#define USE_SDCARD
-#define USE_SDCARD_SPI2
-
-#define SDCARD_DETECT_INVERTED
-
-#define SDCARD_DETECT_PIN PC14
-#define SDCARD_SPI_INSTANCE SPI2
-#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
-
-// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
-#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
-// Divide to under 25MHz for normal operation:
-#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
-
-// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
-#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
-#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
-
-// Performance logging for SD card operations:
-// #define AFATFS_USE_INTROSPECTIVE_LOGGING
-
-#define BOARD_HAS_VOLTAGE_DIVIDER
-#define USE_ADC
-#define ADC_INSTANCE ADC2
-#define VBAT_ADC_PIN PA4
-#define CURRENT_METER_ADC_PIN PA5
-#define RSSI_ADC_PIN PB2
-
-#define LED_STRIP
-
-#define TRANSPONDER
-
-#define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT
-
-#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
-
-#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
-#ifdef TINYBEEF3
-#define BRUSHED_ESC_AUTODETECT
-#else
-#define DEFAULT_FEATURES FEATURE_BLACKBOX
-#endif
-
-#ifndef TINYBEEF3
-#define BUTTONS
-#define BUTTON_A_PIN PB1
-#define BUTTON_B_PIN PB0
-
-#define HARDWARE_BIND_PLUG
-#define BINDPLUG_PIN PB0
-#endif
-
-#define SPEKTRUM_BIND
-// USART3,
-#define BIND_PIN PB11
-
-#define USE_SERIAL_4WAY_BLHELI_INTERFACE
-
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
-#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
-
-#define USABLE_TIMER_CHANNEL_COUNT 12 // 8 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins.
-#ifdef TINYBEEF3
-#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15))
-#else
-#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))
-#endif
diff --git a/src/main/target/VRRACE/target.h.orig b/src/main/target/VRRACE/target.h.orig
deleted file mode 100644
index d2a8211681..0000000000
--- a/src/main/target/VRRACE/target.h.orig
+++ /dev/null
@@ -1,185 +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
-
-#define TARGET_BOARD_IDENTIFIER "VRRA"
-#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
-
-#define USBD_PRODUCT_STRING "VRRACE"
-
-#define LED0 PD14
-#define LED1 PD15
-#define BEEPER PA0
-#define BEEPER_INVERTED
-
-#define INVERTER_PIN_USART6 PD7
-
-#define MPU6500_CS_PIN PE10
-#define MPU6500_SPI_INSTANCE SPI2
-
-#define ACC
-#define USE_ACC_SPI_MPU6500
-#define ACC_MPU6500_ALIGN CW270_DEG
-
-#define GYRO
-#define USE_GYRO_SPI_MPU6500
-#define GYRO_MPU6500_ALIGN CW270_DEG
-
-// MPU6500 interrupts
-#define USE_EXTI
-#define MPU_INT_EXTI PD10
-#define USE_MPU_DATA_READY_SIGNAL
-
-/*
-#define BARO
-#define USE_BARO_MS5611
-#define MS5611_I2C_INSTANCE I2CDEV_1
-
-#define USE_SDCARD
-
-#define SDCARD_DETECT_INVERTED
-
-#define SDCARD_DETECT_PIN PD2
-#define SDCARD_SPI_INSTANCE SPI2
-#define SDCARD_SPI_CS_PIN PB12
-*/
-
-/*
-#define SDCARD_DETECT_PIN PD2
-#define SDCARD_DETECT_EXTI_LINE EXTI_Line2
-#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource2
-#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOD
-#define SDCARD_DETECT_EXTI_IRQn EXTI2_IRQn
-
-#define SDCARD_SPI_INSTANCE SPI3
-#define SDCARD_SPI_CS_PIN PB3
-*/
-
-// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
-/*
-#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
-*/
-// Divide to under 25MHz for normal operation:
-/*
-#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
-*/
-
-/*
-#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
-#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
-#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
-#define SDCARD_DMA_CHANNEL DMA_Channel_0
-*/
-
-
-/*
-#define USE_FLASHFS
-#define USE_FLASH_M25P16
-#define M25P16_CS_PIN PB3
-#define M25P16_SPI_INSTANCE SPI3
-*/
-
-#define USE_VCP
-#define VBUS_SENSING_PIN PA9
-//#define VBUS_SENSING_ENABLED
-
-#define USE_UART1
-#define UART1_RX_PIN PB7
-#define UART1_TX_PIN PB6
-
-#define USE_UART2
-#define UART2_RX_PIN PD6
-#define UART2_TX_PIN PD5
-
-#define USE_UART3
-#define UART3_RX_PIN PD9
-#define UART3_TX_PIN PD8
-
-#define USE_UART6
-#define UART6_RX_PIN PC7
-#define UART6_TX_PIN PC6
-
-#define USE_SOFTSERIAL1
-
-#define SOFTSERIAL1_RX_PIN PE13 // PWM 3
-#define SOFTSERIAL1_TX_PIN PE11 // PWM 2
-<<<<<<< HEAD
-
-#define USE_SOFTSERIAL2
-
-#define SERIAL_PORT_COUNT 8 //VCP, USART1, USART2, USART3, USART6, SOFTSERIAL x 2
-=======
-#define SERIAL_PORT_COUNT 6 //VCP, USART1, USART2, USART3, USART6, SOFTSERIAL1
->>>>>>> betaflight/patch_v3.1.6
-
-#define USE_ESCSERIAL
-#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
-
-
-#define USE_SPI
-
-#define USE_SPI_DEVICE_1
-
-#define USE_SPI_DEVICE_2
-#define SPI2_NSS_PIN PE10
-#define SPI2_SCK_PIN PB13
-#define SPI2_MISO_PIN PB14
-#define SPI2_MOSI_PIN PB15
-
-/*
-#define USE_SPI_DEVICE_3
-#define SPI3_NSS_PIN PB3
-#define SPI3_SCK_PIN PC10
-#define SPI3_MISO_PIN PC11
-#define SPI3_MOSI_PIN PC12
-
-#define USE_I2C
-#define I2C_DEVICE (I2CDEV_1) // PB8-SCL, PB8-SDA
-#define USE_I2C_PULLUP
-#define I2C1_SCL PB8
-#define I2C1_SDA PB9
-*/
-
-#define USE_ADC
-#define BOARD_HAS_VOLTAGE_DIVIDER
-#define VBAT_ADC_PIN PC0
-#define RSSI_ADC_PIN PB1
-#define CURRENT_METER_ADC_PIN PA5
-
-#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_SOFTSERIAL | FEATURE_TELEMETRY)
-#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
-#define SERIALRX_PROVIDER SERIALRX_SBUS
-
-//#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
-
-/*
-#define SPEKTRUM_BIND
-// USART3 Rx, PB11
-#define BIND_PIN PB11
-*/
-
-#define USE_SERIAL_4WAY_BLHELI_INTERFACE
-
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC 0xffff
-#define TARGET_IO_PORTD 0xffff
-#define TARGET_IO_PORTE 0xffff
-
-#define USABLE_TIMER_CHANNEL_COUNT 12
-#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) )