diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/CrazyF405HD_pinout.jpg b/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/CrazyF405HD_pinout.jpg
new file mode 100644
index 0000000000..1bb3aecbf7
Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/CrazyF405HD_pinout.jpg differ
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/CrazyF405_external_elrs.jpg b/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/CrazyF405_external_elrs.jpg
new file mode 100644
index 0000000000..493f316fe6
Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/CrazyF405_external_elrs.jpg differ
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/README.md b/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/README.md
new file mode 100644
index 0000000000..e62fd0a8ed
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/README.md
@@ -0,0 +1,76 @@
+# CrazyF405HD ELRS 1-2SAIO Flight Controller
+
+The CrazyF405HD ELRS 1-2S AIO is a flight controller produced by [Happymodel](https://www.happymodel.cn/index.php/2023/05/26/crazyf405hd-elrs-1-2s-aio-fc-built-in-uart-elrs-receiver-and-12a-blheli_s-esc/.)
+
+## Features
+
+ - MCU: STM32F405RGT6, 168MHz
+ - Gyro: BMI270 (SPI)
+ - 1Mb Onboard Flash
+ - BEC output: 5V, 2A@4V
+ - Barometer: BMP280
+ - 3 UARTS: (UART1, UART2 ,UART6)
+ - 5 PWM outputs (4 motor outputs used internally for integrated 4-in-1 ESC and 1 integrated LED)
+ - Integrated 4-in-1 BlueJay ESC
+ - Firmware target: BetaflightF4
+
+## Pinout
+
+
+
+## UART Mapping
+
+The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the
+receive pin for UARTn. The Tn pin is the transmit pin for UARTn.
+|Name|Pin|Function|
+|:-|:-|:-|
+|SERIAL0|COMPUTER|USB|
+|SERIAL1|RX1/TX1|UART1 (Display Port,DMA-enabled)|
+|SERIAL2|TX2/RX2|UART2 (RCIN,ELRS, internal)
+|SERIAL5|RX6|UART6 (USER,DMA-disabled)|
+
+## RC Input
+
+RC input is configured on the on-board ELRS on UART2 or through (UART2_RX/UART2_TX) pins. It supports all serial RC protocols.
+To disable the onboard ELRS module and use an external RC on TX2/RX2, desolder the RX/TX pads of the onboard ELRS receiver as shown in the image.
+
+
+
+
+## OSD Support
+The CrazyF405HDAIO is optimized for Digital HD FPV and does not require the analog OSD chip (MAX7456); OSD data is transmitted via MSP to the digital VTX.
+
+## PWM Output
+
+The Carzyf405HD AIO has 4 PWM outputs internally connected to its 4-in-1 ESC. The pads for motor output are M1 to M4 on the board. All 4 outputs support DShot, as well as all PWM types. The default configuration is for DShot using the already installed BlueJay firmware.
+
+
+## Battery Monitoring
+
+The board has a builtin voltage sensor and a current sensor input tied to its 4 in 1 ESC current sensor. The voltage sensor can handle up to 2S
+LiPo/Li-Hv batteries.
+
+The correct battery setting parameters are:
+
+ - BATT_MONITOR 4
+ - BATT_VOLT_PIN 12
+ - BATT_VOLT_MULT 10.9
+ - BATT_CURR_PIN 13
+ - BATT_CURR_MULT 50
+
+These are set by default in the firmware and shouldn't need to be adjusted
+
+## Compass
+
+The BETAFPV F405 AIO does not have a builtin compass.
+
+
+## Loading Firmware
+
+Initial firmware load can be done with DFU by plugging in USB with the
+bootloader button pressed. Then you should load the "with_bl.hex"
+firmware, using your favourite DFU loading tool.
+
+Once the initial firmware is loaded you can update the firmware using
+any ArduPilot ground station software. Updates should be done with the
+*.apj firmware files.
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/defaults.parm
new file mode 100644
index 0000000000..f02dfea013
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/defaults.parm
@@ -0,0 +1,5 @@
+# Bluejay installed by default
+SERVO_BLH_AUTO 1
+SERVO_BLH_BDMASK 15
+SERVO_DSHOT_ESC 2
+MOT_PWM_TYPE 6
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/hwdef-bl.dat
new file mode 100644
index 0000000000..759973bb0f
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/hwdef-bl.dat
@@ -0,0 +1,43 @@
+
+# hw definition file for processing by chibios_hwdef.py
+# for BETAFLIGHTF4 hardware.
+# thanks to betaflight for pin information
+
+# MCU class and specific type
+MCU STM32F4xx STM32F405xx
+
+# board ID for firmware load
+APJ_BOARD_ID AP_HW_CrazyF405
+
+# crystal frequency, setup to use external oscillator
+OSCILLATOR_HZ 8000000
+
+FLASH_SIZE_KB 1024
+
+# bootloader starts at zero offset
+FLASH_RESERVE_START_KB 0
+
+# the location where the bootloader will put the firmware
+FLASH_BOOTLOADER_LOAD_KB 48
+
+# order of UARTs (and USB)
+SERIAL_ORDER OTG1
+
+# PA10 IO-debug-console
+PA11 OTG_FS_DM OTG1
+PA12 OTG_FS_DP OTG1
+
+PA13 JTMS-SWDIO SWD
+PA14 JTCK-SWCLK SWD
+
+# default to all pins low to avoid ESD issues
+DEFAULTGPIO OUTPUT LOW PULLDOWN
+
+
+# Chip select pins
+PA15 FLASH1_CS CS
+PB12 OSD1_CS CS
+PA4 GYRO1_CS CS
+
+PB5 LED_BOOTLOADER OUTPUT LOW
+define HAL_LED_ON 0
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/hwdef.dat
new file mode 100644
index 0000000000..df761f5092
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/CrazyF405/hwdef.dat
@@ -0,0 +1,130 @@
+
+# hw definition file for processing by chibios_hwdef.py
+# for BETAFLIGHTF4 hardware.
+# thanks to betaflight for pin information
+
+# MCU class and specific type
+MCU STM32F4xx STM32F405xx
+
+# board ID for firmware load
+APJ_BOARD_ID AP_HW_CrazyF405
+
+# crystal frequency, setup to use external oscillator
+OSCILLATOR_HZ 8000000
+
+FLASH_SIZE_KB 1024
+
+# bootloader takes first sector
+FLASH_RESERVE_START_KB 48
+
+define HAL_STORAGE_SIZE 16384
+define STORAGE_FLASH_PAGE 1
+
+STM32_ST_USE_TIMER 5
+
+# SPI devices
+
+# SPI1
+PA5 SPI1_SCK SPI1
+PA6 SPI1_MISO SPI1
+PA7 SPI1_MOSI SPI1
+
+# SPI2
+PB13 SPI2_SCK SPI2
+PB14 SPI2_MISO SPI2
+PB15 SPI2_MOSI SPI2
+
+# SPI3
+PC10 SPI3_SCK SPI3
+PC11 SPI3_MISO SPI3
+PC12 SPI3_MOSI SPI3
+
+# Chip select pins
+PA15 FLASH1_CS CS
+PB12 OSD_CS CS
+PA4 GYRO1_CS CS
+
+# Beeper
+PB4 BUZZER OUTPUT GPIO(80) LOW
+define HAL_BUZZER_PIN 80
+
+# SERIAL ports
+SERIAL_ORDER OTG1 USART1 USART2 EMPTY EMPTY USART6
+# PA10 IO-debug-console
+PA11 OTG_FS_DM OTG1
+PA12 OTG_FS_DP OTG1
+
+# USART1
+PA10 USART1_RX USART1
+PA9 USART1_TX USART1
+define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_MSP_DisplayPort
+
+# USART2
+PA2 USART2_TX USART2
+PA3 USART2_RX USART2
+define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_RCIN
+
+# USART6
+PC6 USART6_TX USART6 NODMA
+PC7 USART6_RX USART6 NODMA
+
+# I2C ports
+I2C_ORDER I2C2
+
+# I2C2
+PB10 I2C2_SCL I2C2
+PB11 I2C2_SDA I2C2
+
+
+# ADC ports
+
+# ADC1
+PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
+define HAL_BATT_CURR_PIN 11
+define HAL_BATT_CURR_SCALE 25.0
+PC2 BATT_VOLTAGE_SENS ADC1 SCALE(1)
+define HAL_BATT_VOLT_PIN 12
+define HAL_BATT_VOLT_SCALE 11.0
+define HAL_BATT_MONITOR_DEFAULT 4
+
+# MOTORS
+PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) # M1
+PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51) # M2
+PC9 TIM8_CH4 TIM8 PWM(3) GPIO(52) # M3
+PC8 TIM8_CH3 TIM8 PWM(4) GPIO(53) # M4
+PB6 TIM4_CH1 TIM4 PWM(5) GPIO(54) # M5
+
+# LEDs
+
+PB5 LED0 OUTPUT LOW GPIO(90)
+define HAL_GPIO_A_LED_PIN 90
+define AP_NOTIFY_GPIO_LED_ENABLED 1
+
+
+# Dataflash setup
+SPIDEV dataflash SPI3 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ
+
+define HAL_LOGGING_DATAFLASH_ENABLED 1
+define HAL_OSD_TYPE_DEFAULT 5
+
+# IMU setup
+SPIDEV bmi270 SPI1 DEVID1 GYRO1_CS MODE3 2*MHZ 10*MHZ
+IMU BMI270 SPI:bmi270 ROTATION_NONE
+DMA_NOSHARE TIM3_UP TIM8_UP TIM4_UP SPI1*
+DMA_PRIORITY TIM3_UP TIM8_UP TIM4_UP SPI1*
+
+# Baro Setup
+BARO BMP280 I2C:0:0x76
+
+# no built-in compass, but probe the i2c bus for all possible
+# external compass types
+define ALLOW_ARM_NO_COMPASS
+define HAL_PROBE_EXTERNAL_I2C_COMPASSES
+define HAL_I2C_INTERNAL_MASK 0
+define HAL_COMPASS_AUTO_ROT_DEFAULT 2
+define HAL_DEFAULT_INS_FAST_SAMPLE 3
+# Motor order implies Betaflight/X for standard ESCs
+define HAL_FRAME_TYPE_DEFAULT 12
+
+include ../include/minimize_fpv_osd.inc
+AUTOBUILD_TARGETS Copter