diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/P1.jpg b/libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/P1.jpg
new file mode 100644
index 0000000000..230ca56463
Binary files /dev/null and b/libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/P1.jpg differ
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/README.md b/libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/README.md
new file mode 100644
index 0000000000..2c2f255986
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/README.md
@@ -0,0 +1,112 @@
+# SULILGH7P1/P2 Flight Controller
+
+# This firmware is compatible with SULILGH7-P1 and SULILGH7-P2.
+
+This is the open-source hardware I have released, and you can find more details at the following link: https://oshwhub.com/shuyedeye/p1-flight-control.
+
+
+
+
+## Features:
+- Separate flight control core design.
+- MCU
+ STM32H743IIK6 32-bit processor running at 480MHz
+ 2MB Flash
+ 1MB RAM
+- IO MCU
+ STM32F103
+- Sensors
+- IMU:
+ P2:Internal Vibration Isolation for IMUs
+ P2:IMU constant temperature heating(1 W heating power).
+ With Triple Synced IMUs, BalancedGyro technology, low noise and more shock-resistant:
+ IMU1-BMI088(With vibration isolation)
+ IMU2-ICM42688-P(With vibration isolation)
+ IMU3-ICM20689(No vibration isolation)
+- Baro:
+ Two barometers:Baro1-BMP581 , Baro2-ICP20100
+ Magnetometer: Builtin IST8310 magnetometer
+
+
+## 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 | Function | MCU PINS | DMA |
+| :-----: | :------: | :------: | :------:|
+| SERIAL0 | OTG1 | USB |
+| SERIAL1 | Telem1 | USART2 |DMA Enabled |
+| SERIAL2 | Telem2 | USART3 |DMA Enabled |
+| SERIAL3 | GPS1 | USART1 |DMA Enabled |
+| SERIAL4 | GPS2 | UART4 |DMA Enabled |
+| SERIAL5 | RC | UART8 |DMA Enabled |
+| SERIAL7 |FMU DEBUG | UART7 |DMA Enabled |
+| SERIAL8 | OTG-SLCAN| USB |
+
+## RC Input
+The RCIN pin, which by default is mapped to a timer input, can be used for all ArduPilot supported receiver protocols, except CRSF/ELRS and SRXL2 which require a true UART connection. However, FPort, when connected in this manner, will only provide RC without telemetry.
+
+To allow CRSF and embedded telemetry available in Fport, CRSF, and SRXL2 receivers, a full UART, such as SERIAL5 (UART8) would need to be used for receiver connections. Below are setups using Serial5.
+
+* :ref:`SERIAL5_PROTOCOL` should be set to “23”.
+* CRSF would require :ref:`SERIAL5_OPTIONS` set to “0”.
+* SRXL2 would require :ref:`SERIAL5_OPTIONS` set to “4”. And only connect the TX pin.
+
+* The SBUS_IN pin is internally tied to the RCIN pin.
+
+Any UART can also be used for RC system connections in ArduPilot and is compatible with all protocols except PPM. See :ref:`Radio Control Systems ` for details.
+
+## PWM Output
+The SULILLGH7-P1/P2 flight controller supports up to 16 PWM outputs.
+First 8 outputs (labelled 1 to 8) are controlled by a dedicated STM32F103 IO controller.
+The remaining 8 outputs (labelled 9 to 16) are the "auxiliary" outputs. These are directly attached to the STM32H753 FMU controller.
+All 16 outputs support normal PWM output formats. All 16 outputs support DShot, except 15 and 16.
+
+The 8 IO PWM outputs are in 4 groups:
+- Outputs 1 and 2 in group1
+- Outputs 3 and 4 in group2
+- Outputs 5, 6, 7 and 8 in group3
+
+The 8 FMU PWM outputs are in 4 groups:
+- Outputs 1, 2, 3 and 4 in group1
+- Outputs 5 and 6 in group2
+- Outputs 7 and 8 in group3
+
+Channels within the same group need to use the same output rate. If any channel in a group uses DShot then all channels in the group need to use DShot.
+
+## GPIO
+All PWM outputs can be used as GPIOs (relays, camera, RPM etc). To use them you need to set the output’s SERVOx_FUNCTION to -1. The numbering of the GPIOs for PIN variables in ArduPilot is:
+
+
+
+ IO Pins |
+ |
+ FMU Pins |
+
+ Name | Value | Option | | Name | Value | Option |
+ M1 | 101 | MainOut1 | | M9 | 50 | AuxOut1 |
+ M2 | 102 | MainOut2 | | M10 | 51 | AuxOut2 |
+ M3 | 103 | MainOut3 | | M11 | 52 | AuxOut3 |
+ M4 | 104 | MainOut4 | | M12 | 53 | AuxOut4 |
+ M5 | 105 | MainOut5 | | M13 | 54 | AuxOut5 |
+ M6 | 106 | MainOut6 | | M14 | 55 | AuxOut6 |
+ M7 | 107 | MainOut7 | | M15 | 56 | |
+ M8 | 108 | MainOut8 | | M16 | 57 | |
+
+
+## Battery Monitoring
+Two DroneCAN power monitor interfaces have been configured
+These are set by default in the firmware and shouldn't need to be adjusted.
+
+## Compass
+The P1/P2 flight controllers have an integrated IST8310 high-precision magnetometer.
+
+## Analog inputs
+The P1/P2 flight controller has 2 analog inputs.
+- ADC Pin12 -> ADC 6.6V Sense
+- ADC Pin13 -> ADC 3.3V Sense
+- RSSI input pin = 103
+
+## Loading Firmware
+
+The board comes pre-installed with an ArduPilot compatible bootloader, allowing the loading of xxxxxx.apj firmware files with any ArduPilot compatible ground station.
+
+Firmware for these boards can be found [here](https://firmware.ardupilot.org/) in sub-folders labeled “SULIGH7-P1-P2”.
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/defaults.parm
new file mode 100644
index 0000000000..83cd93a214
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/defaults.parm
@@ -0,0 +1,5 @@
+CAN_P1_DRIVER 1
+CAN_P2_DRIVER 1
+
+BATT_MONITOR 8
+GPS1_TYPE 9
\ No newline at end of file
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/hwdef-bl.dat
new file mode 100644
index 0000000000..007d8e7edd
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/hwdef-bl.dat
@@ -0,0 +1,105 @@
+# hw definition file for processing by chibios_hwdef.py
+# for the SULILGH7_P1 hardware
+
+# MCU class and specific type
+MCU STM32H7xx STM32H743xx
+
+# crystal frequency
+OSCILLATOR_HZ 16000000
+
+# board ID for firmware load
+APJ_BOARD_ID AP_HW_SULILGH7-P1-P2
+
+# bootloader is installed at zero offset
+FLASH_RESERVE_START_KB 0
+
+# the location where the bootloader will put the firmware
+FLASH_BOOTLOADER_LOAD_KB 128
+
+# flash size
+FLASH_SIZE_KB 2048
+
+MCU_CLOCKRATE_MHZ 480
+
+# ChibiOS system timer
+STM32_ST_USE_TIMER 2
+
+# order of UARTs (and USB)
+SERIAL_ORDER OTG1 UART7 USART2 USART3
+
+# USB
+PA11 OTG_FS_DM OTG1
+PA12 OTG_FS_DP OTG1
+PA9 VBUS INPUT OPENDRAIN
+
+# pins for SWD debugging
+PA13 JTMS-SWDIO SWD
+PA14 JTCK-SWCLK SWD
+
+# CS pins
+PI9 ICM20689_CS CS
+PH5 BMP_581_CS CS
+PI4 BMI088_A_CS CS
+PI8 BMI088_G_CS CS
+PH15 ICM_42688_CS CS
+PG7 FRAM_CS CS
+PC2 EXT1_CS CS
+PC3 EXT2_CS CS
+
+# DEBUG
+PE8 UART7_TX UART7
+PE7 UART7_RX UART7
+
+# telem1
+PD5 USART2_TX USART2
+PA3 USART2_RX USART2
+PD4 USART2_RTS USART2
+PD3 USART2_CTS USART2
+
+# telem2
+PD8 USART3_TX USART3
+PD9 USART3_RX USART3
+PD12 USART3_RTS USART3
+PD11 USART3_CTS USART3
+
+# LEDs
+PE3 LED_RED OUTPUT OPENDRAIN HIGH # red
+PE4 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # blue
+PE5 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # green
+
+define HAL_STORAGE_SIZE 16384
+
+# enable DFU by default
+ENABLE_DFU_BOOT 1
+
+# support flashing from SD card:
+# power enable pins
+PG3 VDD_3V3_SD_CARD_EN OUTPUT HIGH
+PG6 VDD_3V3_IMU_EN OUTPUT HIGH
+
+# FATFS support:
+define CH_CFG_USE_MEMCORE 1
+define CH_CFG_USE_HEAP 1
+define CH_CFG_USE_SEMAPHORES 0
+define CH_CFG_USE_MUTEXES 1
+define CH_CFG_USE_DYNAMIC 1
+define CH_CFG_USE_WAITEXIT 1
+define CH_CFG_USE_REGISTRY 1
+
+# microSD support
+PD6 SDMMC2_CK SDMMC2
+PD7 SDMMC2_CMD SDMMC2
+PB14 SDMMC2_D0 SDMMC2
+PB15 SDMMC2_D1 SDMMC2
+PG11 SDMMC2_D2 SDMMC2
+PB4 SDMMC2_D3 SDMMC2
+define FATFS_HAL_DEVICE SDCD2
+
+DMA_PRIORITY SDMMC* USART6* ADC* UART* USART* SPI* TIM*
+
+# enable FAT filesystem support (needs a microSD defined via SDMMC)
+define HAL_OS_FATFS_IO 1
+
+define BOOTLOADER_DEBUG SD7
+
+define AP_BOOTLOADER_FLASH_FROM_SD_ENABLED 1
diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/hwdef.dat
new file mode 100644
index 0000000000..48e80720f1
--- /dev/null
+++ b/libraries/AP_HAL_ChibiOS/hwdef/SULILGH7-P1-P2/hwdef.dat
@@ -0,0 +1,307 @@
+# hw definition file for processing by chibios_hwdef.py
+# for the SULILGH7_P1 hardware
+
+# default to all pins low to avoid ESD issues
+DEFAULTGPIO OUTPUT LOW PULLDOWN
+
+# MCU class and specific type
+MCU STM32H7xx STM32H743xx
+
+# crystal frequency
+OSCILLATOR_HZ 16000000
+
+# ChibiOS system timer
+STM32_ST_USE_TIMER 2
+
+# board ID for firmware load
+APJ_BOARD_ID AP_HW_SULILGH7-P1-P2
+
+FLASH_RESERVE_START_KB 128
+
+# flash size
+FLASH_SIZE_KB 2048
+
+# to be compatible with the px4 bootloader we need
+# to use a different RAM_MAP
+env USE_ALT_RAM_MAP 1
+
+MCU_CLOCKRATE_MHZ 480
+
+env OPTIMIZE -O2
+
+# order of UARTs (and USB)
+SERIAL_ORDER OTG1 USART2 USART3 USART1 UART4 UART8 UART7 OTG2
+
+# USB
+PA11 OTG_FS_DM OTG1
+PA12 OTG_FS_DP OTG1
+PA9 VBUS INPUT OPENDRAIN
+
+# pins for SWD debugging
+PA13 JTMS-SWDIO SWD
+PA14 JTCK-SWCLK SWD
+
+# telem1
+PD5 USART2_TX USART2
+PA3 USART2_RX USART2
+PD4 USART2_RTS USART2
+PD3 USART2_CTS USART2
+
+# telem2
+PD8 USART3_TX USART3
+PD9 USART3_RX USART3
+PD12 USART3_RTS USART3
+PD11 USART3_CTS USART3
+
+# GPS1
+PB6 USART1_TX USART1
+PB7 USART1_RX USART1
+
+# GPS2
+PH13 UART4_TX UART4
+PH14 UART4_RX UART4
+
+# USART6 is for IOMCU
+PC6 USART6_TX USART6
+PC7 USART6_RX USART6
+IOMCU_UART USART6
+
+# DEBUG
+PE8 UART7_TX UART7
+PE7 UART7_RX UART7
+
+# SBUS/CRSF
+PE1 UART8_TX UART8
+PE0 UART8_RX UART8
+define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_RCIN
+
+# Ethernet
+PC1 ETH_MDC ETH1
+PA2 ETH_MDIO ETH1
+PC4 ETH_RMII_RXD0 ETH1
+PC5 ETH_RMII_RXD1 ETH1
+PG13 ETH_RMII_TXD0 ETH1
+PG12 ETH_RMII_TXD1 ETH1
+PB11 ETH_RMII_TX_EN ETH1
+PA7 ETH_RMII_CRS_DV ETH1
+PA1 ETH_RMII_REF_CLK ETH1
+
+define BOARD_PHY_ID MII_LAN8742A_ID
+define BOARD_PHY_RMII
+
+# ADC
+PA0 SCALED1_V3V3 ADC1 SCALE(2)
+PA4 SCALED2_V3V3 ADC1 SCALE(2)
+PB0 SCALED3_V3V3 ADC1 SCALE(2)
+PC0 SCALED4_V3V3 ADC1 SCALE(2)
+PB1 VDD_5V_SENS ADC1 SCALE(2.02)
+
+PF13 ADC1_6V6 ADC2 SCALE(2)
+PF12 ADC1_3V3 ADC1 SCALE(1)
+
+# SPI1 - IMU3 ICM20689
+PA5 SPI1_SCK SPI1
+PB5 SPI1_MOSI SPI1
+PG9 SPI1_MISO SPI1
+PI9 ICM20689_CS CS
+
+# SPI2 -BARO1 BMP581
+PI1 SPI2_SCK SPI2
+PI2 SPI2_MISO SPI2
+PI3 SPI2_MOSI SPI2
+PH5 BMP_581_CS CS
+PA10 DRDY6_BMP581 INPUT
+
+# SPI3 -IMU1 BMI088
+PB2 SPI3_MOSI SPI3
+PC10 SPI3_SCK SPI3
+PC11 SPI3_MISO SPI3
+PI4 BMI088_A_CS CS
+PI8 BMI088_G_CS CS
+DRDY1_BMI088_ACC1 INPUT
+DRDY2_BMI088_ACC2 INPUT
+DRDY3_BMI088_GYRO1 INPUT
+DRDY4_BMI088_GYRO2 INPUT
+
+# SPI4 - IMU2
+PE12 SPI4_SCK SPI4
+PE13 SPI4_MISO SPI4
+PE14 SPI4_MOSI SPI4
+PH15 ICM_42688_CS CS
+PF3 DRDY5_ICM_42688 INPUT
+
+# SPI5 - FRAM
+PF7 SPI5_SCK SPI5
+PH7 SPI5_MISO SPI5
+PF11 SPI5_MOSI SPI5
+PG7 FRAM_CS CS
+
+# SPI6 - external1
+PB3 SPI6_SCK SPI6
+PA6 SPI6_MISO SPI6
+PG14 SPI6_MOSI SPI6
+PC2 EXT1_CS CS
+PC3 EXT2_CS CS
+
+# PWM output pins
+PI0 TIM5_CH4 TIM5 PWM(1) GPIO(50) BIDIR
+PH12 TIM5_CH3 TIM5 PWM(2) GPIO(51)
+PH11 TIM5_CH2 TIM5 PWM(3) GPIO(52) BIDIR
+PH10 TIM5_CH1 TIM5 PWM(4) GPIO(53)
+PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
+PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
+PH6 TIM12_CH1 TIM12 PWM(7) GPIO(56) NODMA
+PH9 TIM12_CH2 TIM12 PWM(8) GPIO(57) NODMA
+
+# PWM output for buzzer
+PF9 TIM14_CH1 TIM14 GPIO(77) ALARM
+
+# CAN bus
+PD0 CAN1_RX CAN1
+PD1 CAN1_TX CAN1
+
+PB12 CAN2_RX CAN2
+PB13 CAN2_TX CAN2
+
+# control for silent (no output) for CAN
+PC12 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70)
+PG2 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(71)
+
+# I2C buses
+
+# I2C1, GPS+MAG
+PB9 I2C1_SDA I2C1
+PB8 I2C1_SCL I2C1
+
+# I2C2, GPS2+MAG
+PF1 I2C2_SCL I2C2
+PF0 I2C2_SDA I2C2
+
+# I2C3
+PA8 I2C3_SCL I2C3
+PH8 I2C3_SDA I2C3
+
+# I2C4 (ICP20100)
+PF14 I2C4_SCL I2C4
+PF15 I2C4_SDA I2C4
+
+# order of I2C buses
+I2C_ORDER I2C3 I2C4 I2C1 I2C2
+define HAL_I2C_INTERNAL_MASK 0
+
+# power enable pins
+PG3 VDD_3V3_SD_CARD_EN OUTPUT HIGH
+PG6 VDD_3V3_IMU_EN OUTPUT HIGH
+PE6 VDD_3V3_IMU2_EN OUTPUT HIGH
+PD15 VDD_I2C_BATT1_EN OUTPUT HIGH
+PF10 VDD_I2C_CAN_EN OUTPUT HIGH
+
+# start peripheral power on
+PE2 HIPOWER_EN OUTPUT HIGH
+PD2 PERIPH_EN OUTPUT HIGH
+
+# power sensing
+PA15 PERIPH_OC INPUT PULLUP
+PE10 HIPOWER_OC INPUT PULLUP
+
+#Not in use, but reserved
+PB10 VDD_BRICKA_nVALID INPUT PULLUP
+PE15 VDD_BRICKB_nVALID INPUT PULLUP
+PE11 VDD_BRICKC_nVALID INPUT PULLUP
+
+# microSD support
+PD6 SDMMC2_CK SDMMC2
+PD7 SDMMC2_CMD SDMMC2
+PB14 SDMMC2_D0 SDMMC2
+PB15 SDMMC2_D1 SDMMC2
+PG11 SDMMC2_D2 SDMMC2
+PB4 SDMMC2_D3 SDMMC2
+define FATFS_HAL_DEVICE SDCD2
+
+# ID pins
+PG0 HW_VER_REV_DRIVE OUTPUT LOW
+
+# safety
+PD10 LED_SAFETY OUTPUT
+PF5 SAFETY_IN INPUT PULLDOWN
+
+# heater
+PG15 HEATER_EN OUTPUT LOW GPIO(80)
+define HAL_HEATER_GPIO_PIN 80
+
+# Setup the IMU heater
+define HAL_HAVE_IMU_HEATER 1
+define HAL_IMU_TEMP_DEFAULT 45
+define HAL_IMUHEAT_P_DEFAULT 50
+define HAL_IMUHEAT_I_DEFAULT 0.07
+
+# LED
+PE3 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0)
+PE4 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1)
+PE5 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2)
+
+define HAL_GPIO_A_LED_PIN 0
+define HAL_GPIO_B_LED_PIN 1
+define HAL_GPIO_C_LED_PIN 2
+
+# use pixracer style 3-LED indicators
+define HAL_HAVE_PIXRACER_LED
+
+define HAL_GPIO_LED_ON 0
+
+# compass
+#define HAL_PROBE_EXTERNAL_I2C_COMPASSES
+
+# compass
+define HAL_PROBE_EXTERNAL_I2C_COMPASSES
+define HAL_SKIP_AUTO_INTERNAL_I2C_PROBE
+define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE
+define AP_COMPASS_IST8310_DEFAULT_ROTATION ROTATION_ROLL_180_YAW_90
+COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_90_YAW_90
+COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90
+
+# IMU devices for SULILGH7_P1
+SPIDEV bmi088_a SPI3 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ
+SPIDEV bmi088_g SPI3 DEVID1 BMI088_G_CS MODE3 10*MHZ 10*MHZ
+SPIDEV icm42688 SPI4 DEVID2 ICM_42688_CS MODE3 2*MHZ 8*MHZ
+SPIDEV icm20689 SPI1 DEVID2 ICM20689_CS MODE3 2*MHZ 8*MHZ
+SPIDEV bmp581 SPI2 DEVID1 BMP_581_CS MODE3 7.5*MHZ 12*MHZ
+
+SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
+
+# SULILGH7_P1 3 IMUs
+IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_NONE
+IMU Invensensev3 SPI:icm42688 ROTATION_YAW_90
+IMU Invensense SPI:icm20689 ROTATION_PITCH_180_YAW_90
+
+define HAL_INS_HIGHRES_SAMPLE 7
+define HAL_DEFAULT_INS_FAST_SAMPLE 7
+
+# barometers
+BARO BMP581 SPI:bmp581
+BARO ICP201XX I2C:1:0x63
+
+# enable RAMTROM parameter storage
+define HAL_STORAGE_SIZE 32768
+define HAL_WITH_RAMTRON 1
+
+# allow to have have a dedicated safety switch pin
+define HAL_HAVE_SAFETY_SWITCH 1
+
+DMA_PRIORITY TIM5* TIM4* SPI1* SPI2* SPI3* SDMMC* USART6* ADC* UART* USART*
+
+# enable FAT filesystem support (needs a microSD defined via SDMMC)
+define HAL_OS_FATFS_IO 1
+
+# enable DFU reboot for installing bootloader
+# note that if firmware is build with --secure-bl then DFU is
+# disabled
+ENABLE_DFU_BOOT 1
+
+# build ABIN for flash-from-bootloader support:
+env BUILD_ABIN True
+
+ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin
+ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_f103_8MHz_dshot_lowpolh.bin
+
+define HAL_WITH_IO_MCU_DSHOT 1