diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt
index 325dd047df8d4..050b0f686191a 100644
--- a/Tools/AP_Bootloader/board_types.txt
+++ b/Tools/AP_Bootloader/board_types.txt
@@ -430,7 +430,10 @@ AP_HW_CUAV-7-NANO 7000
# IDs 7100-7109 reserved for V-UAV
AP_HW_VUAV-V7pro 7100
-# please fill gaps in the above ranges rather than adding past ID #7109
+# IDs 7110-7199 reserved for AEROFOX
+AP_HW_AEROFOX_H7 7110
+
+# please fill gaps in the above ranges rather than adding past ID #7199
# OpenDroneID enabled boards. Use 10000 + the base board ID
diff --git a/Tools/bootloaders/AEROFOX-H7_bl.bin b/Tools/bootloaders/AEROFOX-H7_bl.bin
new file mode 100644
index 0000000000000..e35dcf11a726c
Binary files /dev/null and b/Tools/bootloaders/AEROFOX-H7_bl.bin differ
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/AEROFOX-H7_IMG.png b/libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/AEROFOX-H7_IMG.png
new file mode 100644
index 0000000000000..221e5db5988ad
Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/AEROFOX-H7_IMG.png differ
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/AEROFOX-H7_pinout.png b/libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/AEROFOX-H7_pinout.png
new file mode 100644
index 0000000000000..7aa7f573a4da7
Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/AEROFOX-H7_pinout.png differ
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/README.md b/libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/README.md
new file mode 100644
index 0000000000000..5f5b4dbc24b25
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/README.md
@@ -0,0 +1,101 @@
+# AEROFOX-H7 Flight Controller
+
+The AEROFOX-H7 is a flight controller produced by AEROFOX(http://aerofox.cn)
+
+
+
+## Features
+ Processor
+ STM32H743
+
+ Sensors
+ ADIS16470 (appears in the advanced version)
+ ICM45686 (appears in the advanced version)
+ ICM42688
+ QMC5883L
+ SPL06-001
+
+ Power
+ 2S-12S (MAX60V) Lipo input voltage
+ 5V BEC for system power supply( 5V peripheral current limit 1.2A)
+ 5V/12V BEC for VTX( Current limit 2.5A, need strong heat dissipation)
+ Dual power automatic switching and condition monitoring
+
+ Interfaces
+ 16x PWM output
+ 7x UARTs for RC, TELEM, GPS and other peripherals
+ 2x I2C ports for external compass, airspeed, baro
+ 2x CAN port
+ 4x Relay output
+ 4x ADC input
+
+ FPC connector
+ The connector includes an SPI, an I2C, an PWM IMU heating control pin.
+
+## Pinout
+
+
+## UART Mapping
+
+All UARTs, except UART1, are DMA enabled. UART corresponding to each SERIAL port, and its default protocol, are shown below:
+- SERIAL0 -> USB (MAVLink2)
+- SERIAL1 -> UART7 (ESC Telemetry)
+- SERIAL2 -> UART4 (User configured)
+- SERIAL3 -> UART5 (User configured)
+- SERIAL4 -> USART2 (User configured)
+- SERIAL5 -> USART1 (GPS)
+- SERIAL6 -> UART8 (RCIN)
+- SERIAL7 -> USART3 (MAVLink2)
+
+## RC Input
+
+SERIAL 6 is configured for RC input by default and is compatible with all ArduPilot supported protocols except PPM. For protocols requiring half-duplex serial to transmit telemetry (such as FPort) you should set SERAIL6_OPTIONS = 4 (Half-Duplex)
+
+## PWM Output
+
+The AEROFOXH7 support up to 16PWM outputs. All pins support DShot. Outputs 1-8 support bi-directional DShot.
+
+The 16 PWM outputs are in 9 groups:
+
+- PWM 1,2 in group1
+- PWM 3,4 in group2
+- PWM 5,6 in group3
+- PWM 7,8 in group4
+- PWM 9,10 in group5
+- PWM 11 in group6
+- PWM 12 in group7
+- PWM 13,14 in group8
+- PWM 15,16 in group9
+
+Channels within the same group need to use the same output rate. If any channel in a group uses DShot, then all channels in that group need to use DShot.
+
+## Battery Monitoring
+
+The board has a builting voltage and current sensor. The voltage sensor can handle up
+to 12S LiPo batteries.
+
+### The power A is onboard voltage sensor
+It is enabled by default and has the following parameters set by default:s
+- BATT_MONITOR 4
+- BATT_VOLT_PIN 19
+- BATT_CURR_PIN 9
+- BATT_VOLT_MULT 21
+- BATT_AMP_PERVL 40
+
+### The power B is external PMU input
+An additional power monitor input is provided and can be enabled by setting:
+- BATT_MONITOR 4, then reboot and set the following:
+- BATT_VOLT_PIN 10
+- BATT_CURR_PIN 11
+- BATT_VOLT_MULT 34
+- BATT_AMP_PERVLT should be set as required by the specific monitor used
+
+## Compass
+
+A 5883L compass is installed inside the H7 flight control. When high current devices such as ESC and BEC are installed under the flight control board, the on-board compass is usually disabled and an external compass used mounted to minimize motor current effects.
+
+## Loading Firmware
+The board comes pre-installed with an ArduPilot compatible bootloader, allowing the
+loading of *.apj firmware files with any ArduPilot compatible ground station. The
+hardware also supports the PX4 Betaflight INAV firmware, which needs to be changed with STlink.
+
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/hwdef-bl.dat
new file mode 100644
index 0000000000000..fca224f35da43
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/hwdef-bl.dat
@@ -0,0 +1,53 @@
+# MCU class and specific type
+MCU STM32H7xx STM32H743xx
+
+# crystal frequency
+OSCILLATOR_HZ 24000000
+
+# board ID for firmware load
+APJ_BOARD_ID AP_HW_AEROFOX_H7
+
+FLASH_SIZE_KB 2048
+
+# bootloader is installed at zero offset
+FLASH_RESERVE_START_KB 0
+
+# the location where the bootloader will put the firmware
+# the H743 has 128k sectors
+FLASH_BOOTLOADER_LOAD_KB 128
+
+#define LED pins
+PE14 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # red
+PE12 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # green
+PE13 LED_RED OUTPUT OPENDRAIN HIGH # blue
+
+# order of UARTs (and USB)
+SERIAL_ORDER OTG1 USART1
+
+# UART1 is debug
+PA9 USART1_TX USART1 NODMA
+PA10 USART1_RX USART1 NODMA
+
+PC13 VDD_3V3_SENSORS_EN OUTPUT LOW OPENDRAIN
+PC4 nVDD_5V_PERIPH_EN OUTPUT HIGH OPENDRAIN
+PE8 nVDD_12V_PERIPH_EN OUTPUT LOW OPENDRAIN
+
+PA11 OTG_FS_DM OTG1
+PA12 OTG_FS_DP OTG1
+
+PA13 JTMS-SWDIO SWD
+PA14 JTCK-SWCLK SWD
+
+define HAL_USE_EMPTY_STORAGE 1
+define HAL_STORAGE_SIZE 32768
+define HAL_LED_ON 1
+
+# define BOOTLOADER_DEBUG SD7
+
+# Add CS pins to ensure they are high in bootloader
+PD7 16470_CS CS
+PD4 42688_1_CS CS
+PC15 42688_2_CS CS
+
+PD10 FRAM_CS CS SPEED_VERYLOW
+PC14 FLASH_CS CS
\ No newline at end of file
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/hwdef.dat
new file mode 100644
index 0000000000000..fde69f988ab9d
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/AEROFOX-H7/hwdef.dat
@@ -0,0 +1,238 @@
+# MCU class and specific type
+MCU STM32H7xx STM32H743xx
+
+# crystal frequency
+OSCILLATOR_HZ 24000000
+
+# board ID for firmware load
+APJ_BOARD_ID AP_HW_AEROFOX_H7
+
+FLASH_SIZE_KB 2048
+
+# bootloader is installed at zero offset
+FLASH_RESERVE_START_KB 128
+
+PA11 OTG_FS_DM OTG1
+PA12 OTG_FS_DP OTG1
+
+# supports upto 8MBits/s
+CANFD_SUPPORTED 8
+
+# with 2M flash we can afford to optimize for speed
+env OPTIMIZE -O2
+
+# system timer
+STM32_ST_USE_TIMER 5
+
+# UART
+SERIAL_ORDER OTG1 UART7 UART4 UART5 USART2 USART1 UART8 USART3 OTG2
+
+#serial1
+PA15 UART7_TX UART7
+PA8 UART7_RX UART7
+define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_ESCTelemetry
+
+# serial2
+PC10 UART4_TX UART4
+PC11 UART4_RX UART4
+define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_None
+
+# serial3
+PC12 UART5_TX UART5
+PD2 UART5_RX UART5
+define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None
+
+# serial4
+PD5 USART2_TX USART2
+PD6 USART2_RX USART2
+define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None
+
+# serial5
+PA9 USART1_TX USART1 NODMA
+PA10 USART1_RX USART1 NODMA
+define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_GPS
+
+# serial6
+PE1 UART8_TX UART8
+PE0 UART8_RX UART8
+define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN
+
+# serial7
+PD8 USART3_TX USART3
+PD9 USART3_RX USART3
+define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_MAVLink2
+
+# default the 2nd interface to MAVLink2
+define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
+
+# CAN
+PD0 CAN1_RX CAN1
+PD1 CAN1_TX CAN1
+
+PB12 CAN2_RX CAN2
+PB13 CAN2_TX CAN2
+
+# I2C
+I2C_ORDER I2C1 I2C2
+
+PB6 I2C1_SCL I2C1
+PB7 I2C1_SDA I2C1
+
+PB10 I2C2_SCL I2C2
+PB11 I2C2_SDA I2C2
+
+# SPI
+PB3 SPI1_SCK SPI1
+PB4 SPI1_MISO SPI1
+PB5 SPI1_MOSI SPI1
+
+PD3 SPI2_SCK SPI2
+PC2 SPI2_MISO SPI2
+PC3 SPI2_MOSI SPI2
+
+PE2 SPI4_SCK SPI4
+PE5 SPI4_MISO SPI4
+PE6 SPI4_MOSI SPI4
+
+# IMU
+IMU ADIS1647x SPI:16470 ROTATION_PITCH_180 ADIS_DRDY_PIN
+IMU Invensensev3 SPI:42688_1 ROTATION_NONE
+IMU Invensensev3 SPI:42688_2 ROTATION_PITCH_180_YAW_270
+
+SPIDEV 16470 SPI1 DEVID1 16470_CS MODE3 1*MHZ 2*MHZ
+SPIDEV 42688_1 SPI1 DEVID2 42688_1_CS MODE3 2*MHZ 16*MHZ
+SPIDEV 42688_2 SPI4 DEVID3 42688_2_CS MODE3 2*MHZ 16*MHZ
+
+SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
+SPIDEV sdcard SPI2 DEVID2 FLASH_CS MODE0 1*MHZ 8*MHZ
+
+PD7 16470_CS CS
+PD4 42688_1_CS CS
+PC15 42688_2_CS CS
+
+PD10 FRAM_CS CS SPEED_VERYLOW
+PC14 FLASH_CS CS
+
+PE7 DRDY1_ADIS16470 INPUT GPIO(90)
+define ADIS_DRDY_PIN 90
+
+# ADC
+PA5 BATT_VOLTAGE_SENS ADC1 SCALE(1)
+PB0 BATT_CURRENT_SENS ADC1 SCALE(1)
+
+PC0 BATT2_VOLTAGE_SENS ADC1 SCALE(1)
+PC1 BATT2_CURRENT_SENS ADC1 SCALE(1)
+
+PB1 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(12)
+PA4 VDD_5V_SENS ADC1 SCALE(2)
+
+# GPIO
+PA0 TIM2_CH1 TIM2 PWM(1) GPIO(50) BIDIR
+PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51)
+PE9 TIM1_CH1 TIM1 PWM(3) GPIO(52) BIDIR
+PE11 TIM1_CH2 TIM1 PWM(4) GPIO(53)
+PD12 TIM4_CH1 TIM4 PWM(5) GPIO(54) BIDIR
+PD13 TIM4_CH2 TIM4 PWM(6) GPIO(55)
+PC6 TIM3_CH1 TIM3 PWM(7) GPIO(56) BIDIR
+PC7 TIM3_CH2 TIM3 PWM(8) GPIO(57)
+
+PA2 TIM15_CH1 TIM15 PWM(9) GPIO(58)
+PA3 TIM15_CH2 TIM15 PWM(10) GPIO(59)
+PA7 TIM14_CH1 TIM14 PWM(11) GPIO(60)
+PA6 TIM13_CH1 TIM13 PWM(12) GPIO(61)
+PC9 TIM8_CH4 TIM8 PWM(13) GPIO(62)
+PC8 TIM8_CH3 TIM8 PWM(14) GPIO(63)
+PB15 TIM12_CH2 TIM12 PWM(15) GPIO(64)
+PB14 TIM12_CH1 TIM12 PWM(16) GPIO(65)
+
+PB9 TIM17_CH1 TIM17 ALARM
+
+PE3 EXTERN_GPIO1 OUTPUT GPIO(1)
+PE4 EXTERN_GPIO2 OUTPUT GPIO(2)
+PD11 EXTERN_GPIO3 OUTPUT GPIO(3)
+#PD14 EXTERN_GPIO4 OUTPUT GPIO(4)
+
+PD14 LED_SAFETY OUTPUT
+PD15 SAFETY_IN INPUT PULLDOWN
+
+PC13 VDD_3V3_SENSORS_EN OUTPUT LOW OPENDRAIN
+PC4 nVDD_5V_PERIPH_EN OUTPUT LOW OPENDRAIN
+PE8 nVDD_12V_PERIPH_EN OUTPUT HIGH OPENDRAIN
+
+PE10 VDD_5V_HIPOWER_oOC INPUT PULLUP
+PC5 VDD_BRICK_nVALID INPUT PULLUP
+
+# I2C BMP280 or SPL06
+BARO SPL06 I2C:0:0x76
+BARO BMP280 I2C:0:0x76
+
+# COMPASS
+COMPASS QMC5883L I2C:0:0x0D false ROTATION_NONE
+
+# LED setup is similar to PixRacer
+
+define AP_NOTIFY_GPIO_LED_RGB_ENABLED 1
+PE14 LED_RED OUTPUT GPIO(10)
+PE12 LED_GREEN OUTPUT GPIO(11)
+PE13 LED_BLUE OUTPUT GPIO(12)
+
+define AP_NOTIFY_GPIO_LED_RGB_RED_PIN 10
+define AP_NOTIFY_GPIO_LED_RGB_GREEN_PIN 11
+define AP_NOTIFY_GPIO_LED_RGB_BLUE_PIN 12
+
+
+# IMU heater
+PB8 HEATER_EN OUTPUT LOW GPIO(80)
+define HAL_HEATER_GPIO_PIN 80
+define HAL_HAVE_IMU_HEATER 1
+define HAL_IMU_TEMP_DEFAULT 40
+define HAL_IMUHEAT_P_DEFAULT 50
+define HAL_IMUHEAT_I_DEFAULT 0.07
+define HAL_IMU_TEMP_MARGIN_LOW_DEFAULT 40
+
+# compass
+define HAL_PROBE_EXTERNAL_I2C_COMPASSES
+
+define HAL_SKIP_AUTO_INTERNAL_I2C_PROBE
+
+define HAL_I2C_INTERNAL_MASK 1
+
+# SWD debugging
+PA13 JTMS-SWDIO SWD
+PA14 JTCK-SWCLK SWD
+
+define HAL_CHIBIOS_ARCH_FMUV3 1
+
+define BOARD_TYPE_DEFAULT 3
+
+# safety switch
+define HAL_HAVE_SAFETY_SWITCH 1
+
+# FRAM
+define HAL_WITH_RAMTRON 1
+define HAL_STORAGE_SIZE 32768
+
+# open all IMUs
+define HAL_EKF_IMU_MASK_DEFAULT 7
+
+# IMU fast sample
+define HAL_DEFAULT_INS_FAST_SAMPLE 7
+
+# Enable FAT
+define HAL_OS_FATFS_IO 1
+
+# DMA
+DMA_NOSHARE SPI2* UART2* UART4* UART5*
+
+ENABLE_DFU_BOOT 1
+
+define HAL_BATT_MONITOR 4
+define HAL_BATT_VOLT_PIN 19
+define HAL_BATT_CURR_PIN 9
+define HAL_BATT_VOLT_SCALE 21
+define HAL_BATT_CURR_SCALE 40
+
+define HAL_BATT2_VOLT_PIN 10
+define HAL_BATT2_CURR_PIN 11
+define HAL_BATT2_VOLT_SCALE 34
+define HAL_BATT2_CURR_SCALE 40
\ No newline at end of file