diff --git a/docs/boards/Board - SPRacingH7NANO.md b/docs/boards/Board - SPRacingH7NANO.md
new file mode 100644
index 000000000..eb58f487d
--- /dev/null
+++ b/docs/boards/Board - SPRacingH7NANO.md
@@ -0,0 +1,89 @@
+# Board - Seriously Pro SP Racing H7 NANO
+
+The SPRacingH7NANO flight controller features a 400Mhz H7 CPU that runs twice as fast as the previous generation F7 boards.
+A fast control-loop is what you need for perfect flight performance, the H7 at 400Mhz gives you all the processing power you need.
+
+The SPRacingH7NANO is features a 20x20 mounting pattern, has integrated 5V BEC and 128MB BlackBox logging and has support for
+external OSDs (e.g. via RunCam Camera or CrossFire/CRSF VTX's like the TBS Unify Evo OSD/VTX.)
+
+Full details available on the website, here:
+
+http://seriouslypro.com/spracingh7nano
+
+Purchasing boards directly from SeriouslyPro / SP Racing and official retailers helps fund software development.
+
+Shop here: https://shop.seriouslypro.com/sp-racing-h7-nano
+
+## Background
+
+The SPRacingH7NANO FC is the second STM32H750 based FC to ship with Betaflight. Like the SPRacingH7EXTREME before it, it too uses
+the External Storage (EXST) build system which allows a bootloader to load the flight-controller firmware from external flash.
+
+See the EXST documentation for more details on the EXST system.
+
+## Hardware Features
+
+The SPRacingH7NANO is available in two versions, the NANO-S (solder-pads only) or NANO-E (with connectors for 4in1 ESC + RX + IO)
+
+### SPRacingH7NANO FC board.
+
+
+
+
+
+
+* STM32H750 CPU, 400MHz inc FPU
+* 128MByte 1GBit NAND flash via QuadSPI
+* Low-noise ICM20602 accelerometer/gyro with dedicated filtering(connected via SPI)
+* 1.0mm thick 4-layer copper gold-plated PCB
+* 2-6S BEC 5V Switching regulator, 1A
+* TVS protection diode (NANO-E: Fitted, NANO-S: optional extra)
+* Transponder circuitry (LED and code available separately)
+* Buzzer circuitry
+* RSSI Analog input
+* 8 motor outputs (NANO-S: 8 on pads, NANO-E: 4 on 4in1 connector, 4 on pads)
+* 1x Dual SPI + GPIO breakout onto stacking connector (NANO-E only)
+* 6 Serial Ports (5x TX+RX + 1x TX only bi-directional)
+* 3 LEDs for 5V, 3V and STATUS (Green, Blue, Red)
+* 26.5x26.5mm PCB with 20mm mounting hole pattern
+* 4mm mounting holes for soft-mount grommets and M3 bolts
+* MicroUSB socket for configuration and ESC programming
+* Bootable from External flash.
+* Supplied with 4x soft-mount grommets.
+* Optionally supplied with 2x JST-SH 8-way IO cables. (NANO-E only)
+* Optionally supplied with 2x PicoBlade 6-way IO cables. (NANO-E only)
+
+* 1x solder pad for LED Strip
+* 2x solder pad for DAC out (NANO-S only)
+* 2x solder pad for ADC in (for 4in1 current sensor output, etc)
+* 2x solder pads for UART8 RX/TX
+* 2x solder pads for 5V/GND power
+* 2x solder pads for Buzzer
+* 2x solder pads for TVS Diode
+* 1x Row of pads for Motor 1-4 + Battery wires (NANO-S only)
+* 1x Row of pads for RX connections (UART1 RX+TX, RSSI, 5V, GND, IR) (NANO-S only)
+* 2x Rows of pads for additional IO (UART2,UART5,IR,LED-Strip,etc)
+* 2x 8pin JST-SH socket for GND/5V/I2C/UART4/UART5 (IO port, e.g. for external GPS module)
+* 2x 8pin JST-SH socket for GND/5V/SWD/UART3 (IO port, e.g. for debugging, etc)
+* 1x 6pin PicoBlade socket for RX (NANO-E only)
+* 1x 6pin PicoBlade socket for 4in1 ESC (NANO-E only)
+* 1x solder pads for BOOT
+* 1x solder pads for BIND
+* Cleanflight and Betaflight logos - they're on there, you just have to find them
+* SP Racing logo
+* 1x Additional easter egg!
+
+
+## Connection Diagrams
+
+Connection diagrams can be found on the website, here:
+
+http://seriouslypro.com/spracingh7nano#diagrams
+
+
+## Manual
+
+The manual can be downloaded from the website, here:
+
+http://seriouslypro.com/files/SPRacingH7NANO-Manual-latest.pdf
+
diff --git a/docs/boards/images/spracingh7nano-cpu-e-s.jpg b/docs/boards/images/spracingh7nano-cpu-e-s.jpg
new file mode 100644
index 000000000..e4ad247c7
Binary files /dev/null and b/docs/boards/images/spracingh7nano-cpu-e-s.jpg differ
diff --git a/docs/boards/images/spracingh7nano-cpu.jpg b/docs/boards/images/spracingh7nano-cpu.jpg
new file mode 100644
index 000000000..04627368e
Binary files /dev/null and b/docs/boards/images/spracingh7nano-cpu.jpg differ
diff --git a/docs/boards/images/spracingh7nano-pcb-top-with-connectors.jpg b/docs/boards/images/spracingh7nano-pcb-top-with-connectors.jpg
new file mode 100644
index 000000000..bef1c7386
Binary files /dev/null and b/docs/boards/images/spracingh7nano-pcb-top-with-connectors.jpg differ
diff --git a/docs/boards/images/spracingh7nano-pcb-top.jpg b/docs/boards/images/spracingh7nano-pcb-top.jpg
new file mode 100644
index 000000000..31ca7d7be
Binary files /dev/null and b/docs/boards/images/spracingh7nano-pcb-top.jpg differ
diff --git a/src/main/target/SPRACINGH7NANO/config.c b/src/main/target/SPRACINGH7NANO/config.c
new file mode 100644
index 000000000..016d37ad2
--- /dev/null
+++ b/src/main/target/SPRACINGH7NANO/config.c
@@ -0,0 +1,44 @@
+/*
+ * This file is part of Cleanflight and Betaflight.
+ *
+ * Cleanflight and Betaflight are free software. You can redistribute
+ * this software and/or modify this software 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 and Betaflight are distributed in the hope that they
+ * 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 this software.
+ *
+ * If not, see .
+ */
+
+#include
+#include
+
+#include "platform.h"
+
+#ifdef USE_TARGET_CONFIG
+
+#include "config_helper.h"
+
+#include "io/serial.h"
+#include "osd/osd.h"
+#include "pg/pg.h"
+
+static targetSerialPortFunction_t targetSerialPortFunction[] = {
+ { SERIAL_PORT_USART1, FUNCTION_MSP },
+ { SERIAL_PORT_USART2, FUNCTION_MSP },
+};
+
+void targetConfiguration(void)
+{
+ osdConfigMutable()->core_temp_alarm = 85;
+ targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction));
+}
+#endif
diff --git a/src/main/target/SPRACINGH7NANO/target.c b/src/main/target/SPRACINGH7NANO/target.c
new file mode 100644
index 000000000..6a043dcd3
--- /dev/null
+++ b/src/main/target/SPRACINGH7NANO/target.c
@@ -0,0 +1,60 @@
+/*
+ * This file is part of Cleanflight and Betaflight.
+ *
+ * Cleanflight and Betaflight are free software. You can redistribute
+ * this software and/or modify this software 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 and Betaflight are distributed in the hope that they
+ * 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 this software.
+ *
+ * If not, see .
+ */
+
+#include
+
+#include "platform.h"
+#include "drivers/io.h"
+
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 10, 0 ), // LED Strip
+ DEF_TIM(TIM2, CH4, PB11, TIM_USE_TRANSPONDER, 0, 11, 0 ), // Transponder
+
+ DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM | TIM_USE_PWM, 0, 0, 0 ), // Also USART1 RX
+
+ DEF_TIM(TIM15, CH1, PE5, TIM_USE_CAMERA_CONTROL, 0, 0, 0 ),
+ DEF_TIM(TIM15, CH2, PE6, TIM_USE_NONE, 0, 0, 0 ),
+
+ DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 0, 0 ), // M1
+ DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 1, 0 ),
+ DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR, 0, 2, 0 ),
+ DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR, 0, 3, 0 ), // M4
+
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 4, 1 ), // M5
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 5, 1 ), // M6
+
+ DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 6, 2 ), // M7
+ DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 7, 2 ), // M8
+
+ DEF_TIM(TIM4, CH3, PD14, TIM_USE_MOTOR, 0, 12, 0 ), // M9
+ DEF_TIM(TIM4, CH4, PD15, TIM_USE_MOTOR, 0, 0, 0 ), // M10 // Note: No DMA on TIM4_CH4, can use with BURST DSHOT using TIM4_UP
+
+ DEF_TIM(TIM3, CH1, PA6, TIM_USE_NONE, 0, 0, 0 ), // Also TIM13/CH1
+ DEF_TIM(TIM3, CH2, PA7, TIM_USE_NONE, 0, 0, 0 ), // Also TIM14/CH1
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_NONE, 0, 0, 0 ), // Also TIM8/CH2_N
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_NONE, 0, 0, 0 ), // Also TIM8/CH3_N
+};
+
+
+
diff --git a/src/main/target/SPRACINGH7NANO/target.h b/src/main/target/SPRACINGH7NANO/target.h
new file mode 100644
index 000000000..96876b7dc
--- /dev/null
+++ b/src/main/target/SPRACINGH7NANO/target.h
@@ -0,0 +1,237 @@
+/*
+ * This file is part of Cleanflight and Betaflight.
+ *
+ * Cleanflight and Betaflight are free software. You can redistribute
+ * this software and/or modify this software 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 and Betaflight are distributed in the hope that they
+ * 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 this software.
+ *
+ * If not, see .
+ */
+
+#pragma once
+
+#define TARGET_BOARD_IDENTIFIER "SP7N"
+#define USBD_PRODUCT_STRING "SPRacingH7NANO"
+
+#define USE_TARGET_CONFIG
+
+#define DEBUG_MODE DEBUG_ADC_INTERNAL
+
+#define LED0_PIN PE3
+
+#define USE_BEEPER
+#define BEEPER_PIN PD7
+#define BEEPER_INVERTED
+
+// Force two buttons to look at the single button so config reset on button works
+#define USE_BUTTONS
+#define BUTTON_A_PIN PE4
+#define BUTTON_A_PIN_INVERTED // Active high
+#define BUTTON_B_PIN PE4
+#define BUTTON_B_PIN_INVERTED // Active high
+
+#define USE_QUADSPI
+#define USE_QUADSPI_DEVICE_1
+
+#define QUADSPI1_SCK_PIN PB2
+
+#define QUADSPI1_BK1_IO0_PIN PD11
+#define QUADSPI1_BK1_IO1_PIN PD12
+#define QUADSPI1_BK1_IO2_PIN PE2
+#define QUADSPI1_BK1_IO3_PIN PD13
+#define QUADSPI1_BK1_CS_PIN NONE
+
+#define QUADSPI1_BK2_IO0_PIN PE7
+#define QUADSPI1_BK2_IO1_PIN PE8
+#define QUADSPI1_BK2_IO2_PIN PE9
+#define QUADSPI1_BK2_IO3_PIN PE10
+#define QUADSPI1_BK2_CS_PIN PB10
+
+#define QUADSPI1_MODE QUADSPI_MODE_BK2_ONLY
+#define QUADSPI1_CS_FLAGS (QUADSPI_BK1_CS_NONE | QUADSPI_BK2_CS_SOFTWARE | QUADSPI_CS_MODE_SEPARATE)
+
+#define USE_FLASH_CHIP
+#define EEPROM_IN_EXTERNAL_FLASH
+//#define EEPROM_IN_SDCARD
+//#define EEPROM_IN_RAM
+#if !defined(EEPROM_IN_RAM) && !defined(EEPROM_IN_SDCARD) && !defined(EEPROM_IN_EXTERNAL_FLASH)
+#error "EEPROM storage location not defined"
+#endif
+
+#define USE_UART
+
+#define USE_UART1
+#define UART1_RX_PIN PB15
+#define UART1_TX_PIN PB14
+
+#define USE_UART2
+#define UART2_RX_PIN NONE
+#define UART2_TX_PIN PD5 // TX pin is bidirectional.
+
+#define USE_UART3
+#define UART3_RX_PIN PD9
+#define UART3_TX_PIN PD8
+
+#define USE_UART4
+#define UART4_RX_PIN PD0
+#define UART4_TX_PIN PD1
+
+#define USE_UART5
+#define UART5_RX_PIN PB5
+#define UART5_TX_PIN PB13
+
+#define USE_UART6
+#define UART6_RX_PIN PC7 // aka M7
+#define UART6_TX_PIN PC6 // aka M8
+
+#define USE_UART8
+#define UART8_RX_PIN PE0
+#define UART8_TX_PIN PE1
+
+#define USE_VCP
+#define USE_USB_ID
+
+#define SERIAL_PORT_COUNT 8
+
+#define USE_SPI
+
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PD3
+#define SPI2_MISO_PIN PC2
+#define SPI2_MOSI_PIN PC3
+#define SPI2_NSS_PIN PB12
+
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PB3
+#define SPI3_MISO_PIN PB4
+#define SPI3_MOSI_PIN PD6
+#define SPI3_NSS_PIN PA15
+
+#define USE_SPI_DEVICE_4
+#define SPI4_SCK_PIN PE12
+#define SPI4_MISO_PIN PE13
+#define SPI4_MOSI_PIN PE14
+#define SPI4_NSS_PIN PE11
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+#define I2C_DEVICE (I2CDEV_1)
+
+#define USE_MAG
+#define USE_MAG_HMC5883
+
+#define USE_BARO
+#define USE_BARO_BMP388
+#define USE_BARO_BMP280
+#define USE_BARO_MS5611
+
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6500
+#define USE_MULTI_GYRO
+#undef USE_GYRO_REGISTER_DUMP
+
+#define USE_EXTI
+#define USE_GYRO_EXTI
+#define GYRO_1_EXTI_PIN PE15
+#define GYRO_2_EXTI_PIN PD4
+#define USE_MPU_DATA_READY_SIGNAL
+#define ENSURE_MPU_DATA_READY_IS_LOW
+
+
+#define GYRO_1_CS_PIN SPI2_NSS_PIN
+#define GYRO_1_SPI_INSTANCE SPI2
+
+#define GYRO_2_CS_PIN SPI3_NSS_PIN
+#define GYRO_2_SPI_INSTANCE SPI3
+
+#define USE_ACC
+#define USE_ACC_SPI_MPU6500
+
+#define GYRO_1_ALIGN CW0_DEG_FLIP
+#define GYRO_2_ALIGN CW0_DEG_FLIP
+
+#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1
+
+#define USE_FLASHFS
+#define USE_FLASH_TOOLS
+#define USE_FLASH_W25N01G
+#define FLASH_QUADSPI_INSTANCE QUADSPI
+
+// SD card not present on hardware, but pins are reserved.
+//#define USE_SDCARD
+#ifdef USE_SDCARD
+#define USE_SDCARD_SDIO
+#define SDCARD_DETECT_PIN PD10
+#define SDCARD_DETECT_INVERTED
+#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
+#else
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+#endif
+
+
+#define USE_TRANSPONDER
+
+// MAX7456 not present on hardware, but pins are reserved and available on stacking connector.
+#define USE_MAX7456
+#define MAX7456_SPI_INSTANCE SPI4
+#define MAX7456_SPI_CS_PIN SPI4_NSS_PIN
+
+#ifdef USE_DMA_SPEC
+//#define UART1_TX_DMA_OPT 0
+//#define UART2_TX_DMA_OPT 1
+//#define UART3_TX_DMA_OPT 2
+//#define UART4_TX_DMA_OPT 3
+//#define UART5_TX_DMA_OPT 4
+//#define UART6_TX_DMA_OPT 5
+//#define UART7_TX_DMA_OPT 6
+//#define UART8_TX_DMA_OPT 7
+#define ADC1_DMA_OPT 8
+#define ADC3_DMA_OPT 9
+//#define ADC2_DMA_OPT 10 // ADC2 not used.
+#else
+#define ADC1_DMA_STREAM DMA2_Stream0
+#define ADC3_DMA_STREAM DMA2_Stream1
+//#define ADC2_DMA_STREAM DMA2_Stream2 // ADC2 not used.
+#endif
+
+#define USE_ADC
+#define USE_ADC_INTERNAL // ADC3
+
+#define ADC1_INSTANCE ADC1
+#define ADC2_INSTANCE ADC2 // ADC2 not used
+#define ADC3_INSTANCE ADC3 // ADC3 only for core temp and vrefint
+
+#define RSSI_ADC_PIN PC4 // ADC123
+#define VBAT_ADC_PIN PC1 // ADC12
+#define CURRENT_METER_ADC_PIN PC0 // ADC123
+#define EXTERNAL1_ADC_PIN PC5 // ADC12
+
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_LED_STRIP)
+
+#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 TARGET_IO_PORTF 0xffff
+#define TARGET_IO_PORTG 0xffff
+
+#define USABLE_TIMER_CHANNEL_COUNT 19
+
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(12) | TIM_N(15) )
diff --git a/src/main/target/SPRACINGH7NANO/target.mk b/src/main/target/SPRACINGH7NANO/target.mk
new file mode 100644
index 000000000..3560f6f40
--- /dev/null
+++ b/src/main/target/SPRACINGH7NANO/target.mk
@@ -0,0 +1,21 @@
+H750xB_TARGETS += $(TARGET)
+
+HSE_VALUE = 8000000
+
+EXST = yes
+
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC += \
+ drivers/bus_quadspi_hal.c \
+ drivers/bus_quadspi.c \
+ drivers/max7456.c \
+ drivers/accgyro/accgyro_mpu.c \
+ drivers/accgyro/accgyro_mpu6500.c \
+ drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/compass/compass_hmc5883l.c \
+ drivers/barometer/barometer_bmp085.c \
+ drivers/barometer/barometer_bmp280.c \
+ drivers/barometer/barometer_bmp388.c \
+ drivers/barometer/barometer_ms5611.c \
+
diff --git a/unified_targets/configs/SPRACINGH7NANO.config b/unified_targets/configs/SPRACINGH7NANO.config
new file mode 100644
index 000000000..1edd8985d
--- /dev/null
+++ b/unified_targets/configs/SPRACINGH7NANO.config
@@ -0,0 +1,175 @@
+# Betaflight / SPRACINGH7NANO (SP7N) 4.1.0 Jul 10 2019 / 22:20:39 (8d37147db) MSP API: 1.42
+
+board_name SPRACINGH7NANO
+manufacturer_id SPRO
+
+# resources
+resource BEEPER 1 D07
+resource MOTOR 1 A00
+resource MOTOR 2 A01
+resource MOTOR 3 A02
+resource MOTOR 4 A03
+resource MOTOR 5 B06
+resource MOTOR 6 B07
+resource MOTOR 7 C06
+resource MOTOR 8 C07
+resource PPM 1 B15
+resource PWM 1 B15
+resource LED_STRIP 1 A08
+resource SERIAL_TX 1 B14
+resource SERIAL_TX 2 D05
+resource SERIAL_TX 3 D08
+resource SERIAL_TX 4 D01
+resource SERIAL_TX 5 B13
+resource SERIAL_TX 6 C06
+resource SERIAL_TX 8 E01
+resource SERIAL_RX 1 B15
+resource SERIAL_RX 3 D09
+resource SERIAL_RX 4 D00
+resource SERIAL_RX 5 B05
+resource SERIAL_RX 6 C07
+resource SERIAL_RX 8 E00
+resource I2C_SCL 1 B08
+resource I2C_SDA 1 B09
+resource LED 1 E03
+resource TRANSPONDER 1 B11
+resource SPI_SCK 2 D03
+resource SPI_SCK 3 B03
+resource SPI_SCK 4 E12
+resource SPI_MISO 2 C02
+resource SPI_MISO 3 B04
+resource SPI_MISO 4 E13
+resource SPI_MOSI 2 C03
+resource SPI_MOSI 3 D06
+resource SPI_MOSI 4 E14
+resource CAMERA_CONTROL 1 E05
+resource ADC_BATT 1 C01
+resource ADC_RSSI 1 C04
+resource ADC_CURR 1 C00
+resource ADC_EXT 1 C05
+resource OSD_CS 1 E11
+resource GYRO_EXTI 1 E15
+resource GYRO_EXTI 2 D04
+resource GYRO_CS 1 B12
+resource GYRO_CS 2 A15
+
+# timer
+timer A08 AF1
+# pin A08: TIM1 CH1 (AF1)
+timer B11 AF1
+# pin B11: TIM2 CH4 (AF1)
+timer B15 AF2
+# pin B15: TIM12 CH2 (AF2)
+timer E05 AF4
+# pin E05: TIM15 CH1 (AF4)
+timer E06 AF4
+# pin E06: TIM15 CH2 (AF4)
+timer A00 AF2
+# pin A00: TIM5 CH1 (AF2)
+timer A01 AF2
+# pin A01: TIM5 CH2 (AF2)
+timer A02 AF2
+# pin A02: TIM5 CH3 (AF2)
+timer A03 AF2
+# pin A03: TIM5 CH4 (AF2)
+timer B06 AF2
+# pin B06: TIM4 CH1 (AF2)
+timer B07 AF2
+# pin B07: TIM4 CH2 (AF2)
+timer C06 AF3
+# pin C06: TIM8 CH1 (AF3)
+timer C07 AF3
+# pin C07: TIM8 CH2 (AF3)
+timer D14 AF2
+# pin D14: TIM4 CH3 (AF2)
+timer D15 AF2
+# pin D15: TIM4 CH4 (AF2)
+timer A06 AF2
+# pin A06: TIM3 CH1 (AF2)
+timer A07 AF2
+# pin A07: TIM3 CH2 (AF2)
+timer B00 AF2
+# pin B00: TIM3 CH3 (AF2)
+timer B01 AF2
+# pin B01: TIM3 CH4 (AF2)
+
+# dma
+dma ADC 1 8
+# ADC 1: DMA2 Stream 0 Request 9
+dma ADC 2 NONE
+dma ADC 3 9
+# ADC 3: DMA2 Stream 1 Request 115
+dma TIMUP 1 0
+# TIMUP 1: DMA1 Stream 0 Request 15
+dma TIMUP 2 0
+# TIMUP 2: DMA1 Stream 0 Request 22
+dma TIMUP 3 0
+# TIMUP 3: DMA1 Stream 0 Request 27
+dma TIMUP 4 0
+# TIMUP 4: DMA1 Stream 0 Request 32
+dma TIMUP 5 0
+# TIMUP 5: DMA1 Stream 0 Request 59
+dma TIMUP 8 2
+# TIMUP 8: DMA1 Stream 2 Request 51
+dma TIMUP 15 0
+# TIMUP 15: DMA1 Stream 0 Request 106
+dma pin A08 10
+# pin A08: DMA2 Stream 2 Request 11
+dma pin B11 11
+# pin B11: DMA2 Stream 3 Request 21
+dma pin E05 0
+# pin E05: DMA1 Stream 0 Request 105
+dma pin A00 0
+# pin A00: DMA1 Stream 0 Request 55
+dma pin A01 1
+# pin A01: DMA1 Stream 1 Request 56
+dma pin A02 2
+# pin A02: DMA1 Stream 2 Request 57
+dma pin A03 3
+# pin A03: DMA1 Stream 3 Request 58
+dma pin B06 4
+# pin B06: DMA1 Stream 4 Request 29
+dma pin B07 5
+# pin B07: DMA1 Stream 5 Request 30
+dma pin C06 6
+# pin C06: DMA1 Stream 6 Request 47
+dma pin C07 7
+# pin C07: DMA1 Stream 7 Request 48
+dma pin D14 12
+# pin D14: DMA2 Stream 4 Request 31
+dma pin A06 0
+# pin A06: DMA1 Stream 0 Request 23
+dma pin A07 0
+# pin A07: DMA1 Stream 0 Request 24
+dma pin B00 0
+# pin B00: DMA1 Stream 0 Request 25
+dma pin B01 0
+# pin B01: DMA1 Stream 0 Request 26
+
+# master
+set gyro_to_use = FIRST
+set mag_bustype = I2C
+set mag_i2c_device = 1
+set mag_i2c_address = 0
+set mag_spi_device = 0
+set baro_bustype = I2C
+set baro_spi_device = 0
+set baro_i2c_device = 1
+set baro_i2c_address = 0
+set adc_device = 1
+set blackbox_device = SPIFLASH
+set dshot_burst = OFF
+set current_meter = ADC
+set battery_meter = ADC
+set beeper_inversion = ON
+set beeper_od = OFF
+set max7456_spi_bus = 4
+set dashboard_i2c_bus = 1
+set gyro_1_bustype = SPI
+set gyro_1_spibus = 2
+set gyro_1_sensor_align = CW0FLIP
+set gyro_2_bustype = SPI
+set gyro_2_spibus = 3
+set gyro_2_sensor_align = CW0FLIP
+
+#
\ No newline at end of file