mirror of https://github.com/ArduPilot/ardupilot
58 lines
1000 B
Plaintext
58 lines
1000 B
Plaintext
# hw definition file f405 Matek CAN GPS
|
|
|
|
# MCU class and specific type
|
|
MCU STM32F4xx STM32F405xx
|
|
|
|
# crystal frequency
|
|
OSCILLATOR_HZ 8000000
|
|
|
|
# board ID for firmware load
|
|
APJ_BOARD_ID 1014
|
|
|
|
# setup build for a peripheral firmware
|
|
env AP_PERIPH 1
|
|
|
|
FLASH_RESERVE_START_KB 0
|
|
FLASH_SIZE_KB 1024
|
|
FLASH_BOOTLOADER_LOAD_KB 64
|
|
|
|
PA14 LED_BOOTLOADER OUTPUT LOW GPIO(0) # blue
|
|
define HAL_LED_ON 0
|
|
|
|
# order of UARTs
|
|
SERIAL_ORDER OTG1
|
|
|
|
PA9 USART1_TX USART1
|
|
PA10 USART1_RX USART1
|
|
|
|
PA2 USART2_TX USART2
|
|
PA3 USART2_RX USART2
|
|
|
|
PC10 USART3_TX USART3
|
|
PC11 USART3_RX USART3
|
|
|
|
PA0 UART4_TX UART4
|
|
PA1 UART4_RX UART4
|
|
|
|
PC12 UART5_TX UART5
|
|
PD2 UART5_RX UART5
|
|
|
|
PA11 OTG_FS_DM OTG1
|
|
PA12 OTG_FS_DP OTG1
|
|
|
|
# enable CAN support
|
|
PB8 CAN1_RX CAN1
|
|
PB9 CAN1_TX CAN1
|
|
PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
|
|
|
define HAL_USE_CAN TRUE
|
|
define STM32_CAN_USE_CAN1 TRUE
|
|
|
|
define CAN_APP_NODE_NAME "org.ardupilot.f405_MatekGPS"
|
|
|
|
|
|
# Add CS pins to ensure they are high in bootloader
|
|
PA4 MPU_CS CS
|
|
PB12 MAG_CS CS
|
|
PC14 SDCARD_CS CS
|