mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
8ec404c6fc
add bi-directional dshot add back in features. juggle DMA allocations to allow CRSF to work correctly disable dshot on PWM 10 as it is not used do not enable quadplane by default do not disable arming checks run ICM42688 at 1Mhz for low speed to avoid gyro noise add HEEWING README and picture
42 lines
790 B
Plaintext
42 lines
790 B
Plaintext
# hw definition file for HEEWING-F405
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F4xx STM32F405xx
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 8000000
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1119
|
|
|
|
FLASH_RESERVE_START_KB 0
|
|
FLASH_SIZE_KB 1024
|
|
FLASH_BOOTLOADER_LOAD_KB 64
|
|
|
|
PC13 LED_BOOTLOADER OUTPUT LOW GPIO(0)
|
|
PC15 LED_ACTIVITY OUTPUT LOW GPIO(1) # optional
|
|
define HAL_LED_ON 0
|
|
|
|
# order of UARTs
|
|
SERIAL_ORDER OTG1 USART1
|
|
|
|
PA13 JTMS-SWDIO SWD
|
|
PA14 JTCK-SWCLK SWD
|
|
|
|
PA9 USART1_TX USART1
|
|
PA10 USART1_RX USART1
|
|
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
|
|
# Add CS pins to ensure they are high in bootloader
|
|
PA4 IMU_CS CS
|
|
PC4 OSD_CS CS
|
|
PC14 FLASH_CS CS
|
|
#PC1 SDCARD_CS CS
|
|
|
|
# Turn on switched supply and camera switch/output during bootloader to match default
|
|
#PA4 PINIO1 OUTPUT LOW
|
|
#PB5 PINIO2 OUTPUT LOW
|